Go to the documentation of this file.
41 #ifndef _GAZEBO_ROS_CONTROL___DEFAULT_ROBOT_HW_SIM_H_
42 #define _GAZEBO_ROS_CONTROL___DEFAULT_ROBOT_HW_SIM_H_
54 #include <gazebo/common/common.hh>
55 #include <gazebo/physics/physics.hh>
56 #include <gazebo/gazebo.hh>
79 const std::string& robot_namespace,
81 gazebo::physics::ModelPtr parent_model,
83 std::vector<transmission_interface::TransmissionInfo> transmissions);
103 int *
const joint_type,
double *
const lower_limit,
104 double *
const upper_limit,
double *
const effort_limit);
135 std::vector<gazebo::physics::JointPtr>
sim_joints_;
147 #endif // #ifndef __GAZEBO_ROS_CONTROL_PLUGIN_DEFAULT_ROBOT_HW_SIM_H_
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_
std::vector< double > joint_upper_limits_
std::vector< double > joint_lower_limits_
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
std::string physics_type_
boost::shared_ptr< DefaultRobotHWSim > DefaultRobotHWSimPtr
virtual void readSim(ros::Time time, ros::Duration period)
Read state data from the simulated robot hardware.
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
Gazebo plugin version of RobotHW.
hardware_interface::EffortJointInterface ej_interface_
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
std::vector< std::string > joint_names_
std::vector< gazebo::physics::JointPtr > sim_joints_
std::vector< control_toolbox::Pid > pid_controllers_
std::vector< double > joint_position_
virtual void writeSim(ros::Time time, ros::Duration period)
Write commands to the simulated robot hardware.
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)
Plugin template for hardware interfaces for ros_control and Gazebo.
hardware_interface::VelocityJointInterface vj_interface_
virtual void eStopActive(const bool active)
Set the emergency stop state.
std::vector< ControlMethod > joint_control_methods_
hardware_interface::JointStateInterface js_interface_
std::vector< double > joint_effort_command_
std::vector< double > joint_velocity_
std::vector< int > joint_types_
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_
std::vector< double > last_joint_position_command_
std::vector< double > joint_effort_
std::vector< double > joint_effort_limits_
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)
Initialize the simulated robot hardware.
std::vector< double > joint_velocity_command_
std::vector< double > joint_position_command_
gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Sun Mar 2 2025 03:49:21