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");
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
333 case urdf::Joint::REVOLUTE:
340 case urdf::Joint::CONTINUOUS:
349 const double effort = clamp(
pid_controllers_[j].computeCommand(error, period),
350 -effort_limit, effort_limit);
356 #if GAZEBO_MAJOR_VERSION > 2
377 const double effort = clamp(
pid_controllers_[j].computeCommand(error, period),
378 -effort_limit, effort_limit);
398 int *
const joint_type,
double *
const lower_limit,
399 double *
const upper_limit,
double *
const effort_limit)
401 *joint_type = urdf::Joint::UNKNOWN;
402 *lower_limit = -std::numeric_limits<double>::max();
403 *upper_limit = std::numeric_limits<double>::max();
404 *effort_limit = std::numeric_limits<double>::max();
407 bool has_limits =
false;
409 bool has_soft_limits =
false;
411 if (urdf_model != NULL)
413 const urdf::JointConstSharedPtr urdf_joint = urdf_model->getJoint(joint_name);
414 if (urdf_joint != NULL)
416 *joint_type = urdf_joint->type;
421 has_soft_limits =
true;
431 if (*joint_type == urdf::Joint::UNKNOWN)
437 *joint_type = urdf::Joint::REVOLUTE;
442 *joint_type = urdf::Joint::CONTINUOUS;
444 *joint_type = urdf::Joint::PRISMATIC;
463 limits_handle(joint_handle, limits, soft_limits);
470 limits_handle(joint_handle, limits, soft_limits);
477 limits_handle(joint_handle, limits, soft_limits);
490 sat_handle(joint_handle, limits);
497 sat_handle(joint_handle, limits);
504 sat_handle(joint_handle, limits);