49 double clamp(
const double val,
const double min_val,
const double max_val)
51 return std::min(std::max(val, min_val), max_val);
61 const std::string& robot_namespace,
63 gazebo::physics::ModelPtr parent_model,
65 std::vector<transmission_interface::TransmissionInfo> transmissions)
72 n_dof_ = transmissions.size();
88 for(
unsigned int j=0; j <
n_dof_; j++)
91 if(transmissions[j].joints_.size() == 0)
94 <<
" has no associated joints.");
97 else if(transmissions[j].joints_.size() > 1)
100 <<
" has more than one joint. Currently the default robot hardware simulation " 101 <<
" interface only supports one.");
105 std::vector<std::string> joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_;
106 if (joint_interfaces.empty() &&
107 !(transmissions[j].actuators_.empty()) &&
108 !(transmissions[j].actuators_[0].hardware_interfaces_.empty()))
111 joint_interfaces = transmissions[j].actuators_[0].hardware_interfaces_;
113 transmissions[j].name_ <<
" should be nested inside the <joint> element, not <actuator>. " <<
114 "The transmission will be properly loaded, but please update " <<
115 "your robot model to remain compatible with future versions of the plugin.");
117 if (joint_interfaces.empty())
120 " of transmission " << transmissions[j].name_ <<
" does not specify any hardware interface. " <<
121 "Not adding it to the robot hardware simulation.");
124 else if (joint_interfaces.size() > 1)
127 " of transmission " << transmissions[j].name_ <<
" specifies multiple hardware interfaces. " <<
128 "Currently the default robot hardware simulation interface only supports one. Using the first entry");
145 <<
"' of type '" << hardware_interface <<
"'");
153 if(hardware_interface ==
"EffortJointInterface" || hardware_interface ==
"hardware_interface/EffortJointInterface")
161 else if(hardware_interface ==
"PositionJointInterface" || hardware_interface ==
"hardware_interface/PositionJointInterface")
169 else if(hardware_interface ==
"VelocityJointInterface" || hardware_interface ==
"hardware_interface/VelocityJointInterface")
180 << hardware_interface <<
"' while loading interfaces for " <<
joint_names_[j] );
184 if(hardware_interface ==
"EffortJointInterface" || hardware_interface ==
"PositionJointInterface" || hardware_interface ==
"VelocityJointInterface") {
185 ROS_WARN_STREAM(
"Deprecated syntax, please prepend 'hardware_interface/' to '" << hardware_interface <<
"' within the <hardwareInterface> tag in joint '" <<
joint_names_[j] <<
"'.");
191 gazebo::physics::JointPtr joint = parent_model->GetJoint(
joint_names_[j]);
195 <<
"\" which is not in the gazebo model.");
201 #if GAZEBO_MAJOR_VERSION >= 8 202 gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics();
204 gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->GetPhysicsEngine();
213 joint_limit_nh, urdf_model,
220 const ros::NodeHandle nh(robot_namespace +
"/gazebo_ros_control/pid_gains/" +
239 #if GAZEBO_MAJOR_VERSION > 2 263 for(
unsigned int j=0; j <
n_dof_; j++)
266 #if GAZEBO_MAJOR_VERSION >= 8 269 double position =
sim_joints_[j]->GetAngle(0).Radian();
309 for(
unsigned int j=0; j <
n_dof_; j++)
321 #if GAZEBO_MAJOR_VERSION >= 9 324 ROS_WARN_ONCE(
"The default_robot_hw_sim plugin is using the Joint::SetPosition method without preserving the link velocity.");
325 ROS_WARN_ONCE(
"As a result, gravity will not be simulated correctly for your model.");
326 ROS_WARN_ONCE(
"Please set gazebo_pid parameters, switch to the VelocityJointInterface or EffortJointInterface, or upgrade to Gazebo 9.");
327 ROS_WARN_ONCE(
"For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612");
337 case urdf::Joint::REVOLUTE:
344 case urdf::Joint::CONTINUOUS:
353 const double effort = clamp(
pid_controllers_[j].computeCommand(error, period),
354 -effort_limit, effort_limit);
360 #if GAZEBO_MAJOR_VERSION > 2 381 const double effort = clamp(
pid_controllers_[j].computeCommand(error, period),
382 -effort_limit, effort_limit);
402 int *
const joint_type,
double *
const lower_limit,
403 double *
const upper_limit,
double *
const effort_limit)
405 *joint_type = urdf::Joint::UNKNOWN;
406 *lower_limit = -std::numeric_limits<double>::max();
407 *upper_limit = std::numeric_limits<double>::max();
408 *effort_limit = std::numeric_limits<double>::max();
411 bool has_limits =
false;
413 bool has_soft_limits =
false;
415 if (urdf_model != NULL)
417 const urdf::JointConstSharedPtr urdf_joint = urdf_model->getJoint(joint_name);
418 if (urdf_joint != NULL)
420 *joint_type = urdf_joint->type;
425 has_soft_limits =
true;
435 if (*joint_type == urdf::Joint::UNKNOWN)
441 *joint_type = urdf::Joint::REVOLUTE;
446 *joint_type = urdf::Joint::CONTINUOUS;
448 *joint_type = urdf::Joint::PRISMATIC;
467 limits_handle(joint_handle, limits, soft_limits);
474 limits_handle(joint_handle, limits, soft_limits);
481 limits_handle(joint_handle, limits, soft_limits);
494 sat_handle(joint_handle, limits);
501 sat_handle(joint_handle, limits);
508 sat_handle(joint_handle, limits);
void registerInterface(T *iface)
std::vector< double > joint_upper_limits_
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
std::vector< double > joint_position_command_
std::vector< double > joint_lower_limits_
virtual void readSim(ros::Time time, ros::Duration period)
Read state data from the simulated robot hardware.
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
std::string physics_type_
std::vector< double > joint_position_
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
hardware_interface::VelocityJointInterface vj_interface_
std::vector< control_toolbox::Pid > pid_controllers_
void enforceLimits(const ros::Duration &period)
virtual void eStopActive(const bool active)
Set the emergency stop state.
hardware_interface::JointStateInterface js_interface_
hardware_interface::EffortJointInterface ej_interface_
std::vector< double > joint_velocity_
std::vector< std::string > joint_names_
std::vector< gazebo::physics::JointPtr > sim_joints_
virtual void writeSim(ros::Time time, ros::Duration period)
Write commands to the simulated robot hardware.
std::vector< ControlMethod > joint_control_methods_
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
#define ROS_FATAL_STREAM_NAMED(name, args)
#define ROS_WARN_ONCE(...)
std::vector< int > joint_types_
std::vector< double > joint_effort_
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)
std::vector< double > joint_effort_command_
#define ROS_WARN_STREAM(args)
void registerHandle(const JointStateHandle &handle)
std::vector< double > last_joint_position_command_
def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit)
JointStateHandle getHandle(const std::string &name)
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.
Gazebo plugin version of RobotHW.
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_
Plugin template for hardware interfaces for ros_control and Gazebo.
PLUGINLIB_EXPORT_CLASS(transmission_interface::BiDirectionalEffortJointInterfaceProvider, transmission_interface::RequisiteProvider)
std::vector< double > joint_velocity_command_
std::vector< double > joint_effort_limits_
def shortest_angular_distance(from_angle, to_angle)
#define ROS_WARN_STREAM_NAMED(name, args)
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_