2 #ifndef ARMADILLO2_SIM_INTERFACE_ARMADILLO2_SIM_INTERFACE_H 3 #define ARMADILLO2_SIM_INTERFACE_ARMADILLO2_SIM_INTERFACE_H 16 #include <gazebo/common/common.hh> 17 #include <gazebo/physics/physics.hh> 18 #include <gazebo/gazebo.hh> 39 const std::string& robot_namespace,
41 gazebo::physics::ModelPtr parent_model,
43 std::vector<transmission_interface::TransmissionInfo> transmissions);
63 int *
const joint_type,
double *
const lower_limit,
64 double *
const upper_limit,
double *
const effort_limit);
71 int *
const joint_type,
double *
const lower_limit,
72 double *
const upper_limit,
double *
const effort_limit);
114 #endif //ARMADILLO2_SIM_INTERFACE_ARMADILLO2_SIM_INTERFACE_H hardware_interface::PosVelJointInterface pvj_interface_
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_
boost::shared_ptr< DefaultRobotHWSim > DefaultRobotHWSimPtr
virtual void readSim(ros::Time time, ros::Duration period)
std::vector< double > joint_lower_limits_
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
std::vector< double > joint_upper_limits_
std::vector< ControlMethod > joint_control_methods_
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_
std::vector< double > joint_effort_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
std::vector< double > joint_effort_command_
std::vector< double > joint_velocity_
hardware_interface::JointStateInterface js_interface_
std::vector< int > joint_types_
void registerJointLimits(const std::string &joint_name, const hardware_interface::JointHandle &joint_handle, const ControlMethod ctrl_method, const ros::NodeHandle &joint_limit_nh, const urdf::Model *const urdf_model, int *const joint_type, double *const lower_limit, double *const upper_limit, double *const effort_limit)
virtual void eStopActive(const bool active)
std::vector< double > joint_position_command_
virtual void writeSim(ros::Time time, ros::Duration period)
std::vector< double > joint_position_
hardware_interface::VelocityJointInterface vj_interface_
hardware_interface::EffortJointInterface ej_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
std::vector< gazebo::physics::JointPtr > sim_joints_
std::vector< double > joint_effort_limits_
std::vector< double > last_joint_position_command_
std::vector< double > joint_velocity_command_
std::vector< control_toolbox::Pid > pid_controllers_
virtual bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
std::vector< std::string > joint_names_