hardware_interface.hpp
Go to the documentation of this file.
1 #ifndef dynamixel_hardware_interface
2 #define dynamixel_hardware_interface
3 
4 #include <limits>
5 #include <math.h>
6 #include <stdexcept>
7 #include <unordered_map>
8 
9 // ROS
10 #include <ros/ros.h>
11 #include <urdf/model.h>
12 // ROS-related: to parse parameters
13 #include <XmlRpcException.h>
14 #include <XmlRpcValue.h>
15 
16 // ROS control
20 #include <joint_limits_interface/joint_limits.h>
21 #include <joint_limits_interface/joint_limits_interface.h>
22 #include <joint_limits_interface/joint_limits_rosparam.h>
23 #include <joint_limits_interface/joint_limits_urdf.h>
24 
25 // Library for access to the dynamixels
26 #include <dynamixel/dynamixel.hpp>
27 
28 namespace dynamixel {
35  template <class Protocol>
37  public:
38  // Actuator's id type
39  using id_t = typename Protocol::id_t;
40 
43 
50  bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh);
51 
59  virtual void read(const ros::Time& time, const ros::Duration& elapsed_time);
60 
66  virtual void write(const ros::Time& time, const ros::Duration& elapsed_time);
67 
68  private:
69  using dynamixel_servo = std::shared_ptr<dynamixel::servos::BaseServo<Protocol>>;
70 
73 
74  // Methods used for initialisation
76  ros::NodeHandle& robot_hw_nh);
77  dynamixel::OperatingMode _str2mode(const std::string& mode_string,
78  std::string name);
79  bool _load_urdf(ros::NodeHandle& nh, std::string param_name);
80  bool _find_servos();
81  void _enable_and_configure_servo(dynamixel_servo servo, OperatingMode mode);
83  id_t id);
84 
85  void _enforce_limits(const ros::Duration& loop_period);
86 
87  // ROS's hardware interface instances
91 
92  // Joint limits (hard and soft)
93  joint_limits_interface::PositionJointSoftLimitsInterface _jnt_pos_lim_interface;
94  joint_limits_interface::VelocityJointSoftLimitsInterface _jnt_vel_lim_interface;
95  joint_limits_interface::PositionJointSaturationInterface _jnt_pos_sat_interface;
96  joint_limits_interface::VelocityJointSaturationInterface _jnt_vel_sat_interface;
97 
98  // Memory space shared with the controller
99  // It reads here the latest robot's state and put here the next desired values
100  std::vector<double> _prev_commands;
101  std::vector<double> _joint_commands; // target joint angle or speed
102  std::vector<double> _joint_angles; // actual joint angle
103  std::vector<double> _joint_velocities; // actual joint velocity
104  std::vector<double> _joint_efforts; // compulsory but not used
105 
106  // USB to serial connection settings
109  float _read_timeout, _scan_timeout; // in seconds
110  // Dynamixel's low level controller
111  dynamixel::controllers::Usb2Dynamixel _dynamixel_controller;
112 
113  // List of actuators (collected at init. from the actuators)
114  std::vector<dynamixel_servo> _servos;
115  // Map from dynamixel ID to actuator's name
116  std::unordered_map<id_t, std::string> _dynamixel_map;
117  // Map from dynamixel ID to actuator's command interface (ID: velocity/position)
118  std::unordered_map<id_t, OperatingMode> _c_mode_map;
119  // Map for servos in velocity mode which speed needs to be inverted
120  std::unordered_map<id_t, bool> _invert;
121  // Map for max speed (ID: max speed)
122  std::unordered_map<id_t, double> _dynamixel_max_speed;
123  // Map for angle offsets (ID: correction in radians)
124  std::unordered_map<id_t, double> _dynamixel_corrections;
125 
126  // To get joint limits from the parameter server
128 
129  // URDF model of the robot, for joint limits
130  std::shared_ptr<urdf::Model> _urdf_model;
131  };
132 
133  template <class Protocol>
135  {
136  // stop all actuators
137  try {
138  for (auto dynamixel_servo : _servos) {
139  dynamixel::StatusPacket<Protocol> status;
140  _dynamixel_controller.send(dynamixel_servo->set_torque_enable(0));
141  _dynamixel_controller.recv(status);
142  }
143  }
144  catch (dynamixel::errors::Error& e) {
145  ROS_ERROR_STREAM("Caught a Dynamixel exception while trying to "
146  << "power them off:\n"
147  << e.msg());
148  }
149  }
150 
151  template <class Protocol>
153  ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh)
154  {
155  // Get the relevant parameters from rosparam
156  // Search for the servos declared bu the user, in the parameters
157  if (!_get_ros_parameters(root_nh, robot_hw_nh) || !_find_servos())
158  return false;
159 
160  // declare all available actuators to the control manager, provided a
161  // name has been given for them
162  // also enable the torque output on the actuators (sort of power up)
163  try {
164  for (unsigned i = 0; i < _servos.size(); i++) {
165  id_t id = _servos[i]->id();
166 
167  // check that the actuator's name is in the map
168  typename std::unordered_map<id_t, std::string>::iterator dynamixel_iterator
169  = _dynamixel_map.find(id);
170  if (dynamixel_iterator != _dynamixel_map.end()) {
171  // tell ros_control the in-memory addresses where to read the
172  // information on joint angle, velocity and effort
174  dynamixel_iterator->second,
175  &_joint_angles[i],
176  &_joint_velocities[i],
177  &_joint_efforts[i]);
178  _jnt_state_interface.registerHandle(state_handle);
179 
180  // check that the actuator control mode matches the declared
181  // command interface (position/velocity)
182  OperatingMode hardware_mode
183  = operating_mode<Protocol>(_dynamixel_controller, id);
184  typename std::unordered_map<id_t, OperatingMode>::iterator c_mode_map_i
185  = _c_mode_map.find(id);
186  if (c_mode_map_i != _c_mode_map.end()) {
187  if (c_mode_map_i->second != hardware_mode) {
188  ROS_ERROR_STREAM("The command interface declared "
189  << mode2str(c_mode_map_i->second)
190  << " for joint " << dynamixel_iterator->second
191  << " but is set to " << mode2str(hardware_mode)
192  << " in hardware. Disabling this joint.");
193  _c_mode_map[id] = OperatingMode::unknown;
194  }
195  }
196  else {
197  ROS_ERROR_STREAM("The command interface was not defined "
198  << "for joint " << dynamixel_iterator->second
199  << ". Disabling this joint.");
200  _c_mode_map[id] = OperatingMode::unknown;
201  }
202 
203  // tell ros_control the in-memory address to change to set new
204  // position or velocity goal for the actuator (depending on
205  // hardware_mode)
207  _jnt_state_interface.getHandle(dynamixel_iterator->second),
208  &_joint_commands[i]);
209  if (OperatingMode::joint == hardware_mode) {
211  }
212  else if (OperatingMode::wheel == hardware_mode) {
214  }
215  else if (OperatingMode::unknown != hardware_mode) {
216  ROS_ERROR_STREAM("Servo " << id << " was not initialised "
217  << "(operating mode "
218  << mode2str(hardware_mode)
219  << " is not supported)");
220  _c_mode_map[id] = OperatingMode::unknown;
221  }
222 
223  // Enable servos that were properly configured
224  if (OperatingMode::unknown != _c_mode_map[id]) {
225  // Set joint limits (saturation or soft for the joint)
226  _register_joint_limits(cmd_handle, id);
227  // enable torque output on the servo and set its configuration
228  // including max speed
229  _enable_and_configure_servo(_servos[i], hardware_mode);
230  }
231  else {
232  // remove this servo
233  _servos.erase(_servos.begin() + i);
234  --i;
235  }
236  }
237  else {
238  ROS_WARN_STREAM("Servo " << id << " was not initialised "
239  << "(not found in the parameters)");
240  // remove this servo
241  _servos.erase(_servos.begin() + i);
242  --i;
243  }
244  }
245 
246  // register the hardware interfaces
250  }
251  catch (const ros::Exception& e) {
252  // TODO: disable actuators that were enabled ?
253  ROS_FATAL_STREAM("Error during initialisation. BEWARE: some "
254  << "actuators might have already been started.");
255  return false;
256  }
257 
258  // At startup robot should keep the pose it has
259  ros::Duration period(0);
260  read(ros::Time::now(), period);
261 
262  for (unsigned i = 0; i < _servos.size(); i++) {
263  OperatingMode mode = _c_mode_map[_servos[i]->id()];
264  if (OperatingMode::joint == mode)
266  else if (OperatingMode::wheel == mode)
267  _joint_commands[i] = 0;
268  }
269 
270  return true;
271  }
272 
273  template <class Protocol>
275  const ros::Duration& elapsed_time)
276  {
277  for (unsigned i = 0; i < _servos.size(); i++) {
278  dynamixel::StatusPacket<Protocol> status;
279  try {
280  // current position
281  _dynamixel_controller.send(_servos[i]->get_present_position_angle());
282  _dynamixel_controller.recv(status);
283  }
284  catch (dynamixel::errors::Error& e) {
285  ROS_ERROR_STREAM("Caught a Dynamixel exception while getting "
286  << _dynamixel_map[_servos[i]->id()] << "'s position\n"
287  << e.msg());
288  }
289  if (status.valid()) {
290  try {
291  _joint_angles[i] = _servos[i]->parse_present_position_angle(status);
292  }
293  catch (dynamixel::errors::Error& e) {
294  ROS_ERROR_STREAM("Unpack exception while getting "
295  << _dynamixel_map[_servos[i]->id()] << "'s position\n"
296  << e.msg());
297  }
298 
299  // Invert the orientation, if configured
300  typename std::unordered_map<id_t, bool>::iterator
301  invert_iterator
302  = _invert.find(_servos[i]->id());
303  if (invert_iterator != _invert.end()) {
304  _joint_angles[i] = 2 * M_PI - _joint_angles[i];
305  }
306 
307  // Apply angle correction to joint, if any
308  typename std::unordered_map<id_t, double>::iterator
309  dynamixel_corrections_iterator
310  = _dynamixel_corrections.find(_servos[i]->id());
311  if (dynamixel_corrections_iterator != _dynamixel_corrections.end()) {
312  _joint_angles[i] -= dynamixel_corrections_iterator->second;
313  }
314  }
315  else {
316  ROS_WARN_STREAM("Did not receive any data when reading "
317  << _dynamixel_map[_servos[i]->id()] << "'s position");
318  }
319 
320  dynamixel::StatusPacket<Protocol> status_speed;
321  try {
322  // current speed
323  _dynamixel_controller.send(_servos[i]->get_present_speed());
324  _dynamixel_controller.recv(status_speed);
325  }
326  catch (dynamixel::errors::Error& e) {
327  ROS_ERROR_STREAM("Caught a Dynamixel exception while getting "
328  << _dynamixel_map[_servos[i]->id()] << "'s velocity\n"
329  << e.msg());
330  }
331  if (status_speed.valid()) {
332  try {
334  = _servos[i]->parse_joint_speed(status_speed);
335 
336  typename std::unordered_map<id_t, bool>::iterator
337  invert_iterator
338  = _invert.find(_servos[i]->id());
339  if (invert_iterator != _invert.end()
340  && invert_iterator->second)
342  }
343  catch (dynamixel::errors::Error& e) {
344  ROS_ERROR_STREAM("Unpack exception while getting "
345  << _dynamixel_map[_servos[i]->id()] << "'s velocity\n"
346  << e.msg());
347  }
348  }
349  else {
350  ROS_WARN_STREAM("Did not receive any data when reading "
351  << _dynamixel_map[_servos[i]->id()] << "'s velocity");
352  }
353  }
354  }
355 
356  template <class Protocol>
358  const ros::Duration& loop_period)
359  {
360  // ensure that the joints limits are respected
361  _enforce_limits(loop_period);
362 
363  for (unsigned int i = 0; i < _servos.size(); i++) {
364  // Sending commands only when needed
365  if (std::abs(_joint_commands[i] - _prev_commands[i]) < std::numeric_limits<double>::epsilon())
366  continue;
368  try {
369  dynamixel::StatusPacket<Protocol> status;
370 
371  double command = _joint_commands[i];
372 
373  OperatingMode mode = _c_mode_map[_servos[i]->id()];
374  if (OperatingMode::joint == mode) {
375  typename std::unordered_map<id_t, double>::iterator
376  dynamixel_corrections_iterator
377  = _dynamixel_corrections.find(_servos[i]->id());
378  if (dynamixel_corrections_iterator != _dynamixel_corrections.end()) {
379  command += dynamixel_corrections_iterator->second;
380  }
381 
382  // Invert the orientation, if configured
383  typename std::unordered_map<id_t, bool>::iterator
384  invert_iterator
385  = _invert.find(_servos[i]->id());
386  if (invert_iterator != _invert.end()) {
387  command = 2 * M_PI - command;
388  }
389 
390  ROS_DEBUG_STREAM("Setting position for joint "
391  << _dynamixel_map[_servos[i]->id()] << " to " << command
392  << " rad.");
394  _servos[i]->reg_goal_position_angle(command));
395  _dynamixel_controller.recv(status);
396  }
397  else if (OperatingMode::wheel == mode) {
398  // Invert the orientation, if configured
399  const short sign = 1; // formerly: _invert[_servos[i]->id()] ? -1 : 1;
400  typename std::unordered_map<id_t, bool>::iterator
401  invert_iterator
402  = _invert.find(_servos[i]->id());
403  if (invert_iterator != _invert.end()
404  && invert_iterator->second) {
405  command = -command;
406  }
407  ROS_DEBUG_STREAM("Setting velocity for joint "
408  << _servos[i]->id() << " to " << command);
410  _servos[i]->reg_moving_speed_angle(command, mode));
411  _dynamixel_controller.recv(status);
412  }
413  }
414  catch (dynamixel::errors::Error& e) {
415  ROS_ERROR_STREAM("Caught a Dynamixel exception while sending "
416  << "new commands:\n"
417  << e.msg());
418  }
419  }
420 
421  try {
422  _dynamixel_controller.send(dynamixel::instructions::Action<Protocol>(Protocol::broadcast_id));
423  }
424  catch (dynamixel::errors::Error& e) {
425  ROS_ERROR_STREAM("Caught a Dynamixel exception while sending "
426  << "new commands:\n"
427  << e.msg());
428  }
429  }
430 
434  template <class Protocol>
436  {
437  bool got_all_params = true;
438 
439  got_all_params &= robot_hw_nh.getParam("serial_interface", _usb_serial_interface); // path to the device
440  int baudrate;
441  got_all_params &= robot_hw_nh.getParam("baudrate", baudrate); // in bauds
442  _baudrate = get_baudrate(baudrate); // convert to OS-defined values
443  got_all_params &= robot_hw_nh.getParam("read_timeout", _read_timeout); // in seconds
444  bool dyn_scan = robot_hw_nh.getParam("scan_timeout", _scan_timeout); // in seconds
445  if (!dyn_scan) {
446  ROS_WARN_STREAM("Dynamixel scanning timeout parameter was not found. "
447  << "Setting to default: 0.05s.");
448  _scan_timeout = 0.05;
449  }
450  std::string default_command_interface;
451  bool has_default_command_interface = robot_hw_nh.getParam(
452  "default_command_interface", default_command_interface);
453 
454  // Retrieve the servo parameter and fill maps above with its content.
455  XmlRpc::XmlRpcValue servos_param; // temporary map, from parameter server
456  if (got_all_params &= robot_hw_nh.getParam("servos", servos_param)) {
458  try {
459  for (XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = servos_param.begin(); it != servos_param.end(); ++it) {
460  ROS_DEBUG_STREAM("servo: " << (std::string)(it->first));
461 
462  id_t id;
463  if (it->second.hasMember("id")) {
464  id = static_cast<int>(servos_param[it->first]["id"]);
465  ROS_DEBUG_STREAM("\tid: " << (int)id);
466  _dynamixel_map[id] = it->first;
467  }
468  else {
469  ROS_ERROR_STREAM("Actuator " << it->first
470  << " has no associated servo ID.");
471  continue;
472  }
473 
474  if (it->second.hasMember("offset")) {
476  = static_cast<double>(servos_param[it->first]["offset"]);
477  ROS_DEBUG_STREAM("\toffset: "
478  << _dynamixel_corrections[id]);
479  }
480 
481  if (it->second.hasMember("command_interface")) {
482  std::string mode_string
483  = static_cast<std::string>(
484  servos_param[it->first]["command_interface"]);
485  ROS_DEBUG_STREAM("\tcommand_interface: " << mode_string);
486 
487  _c_mode_map[id] = _str2mode(mode_string, it->first);
488  }
489  else if (has_default_command_interface) {
490  _c_mode_map[id]
491  = _str2mode(default_command_interface, it->first);
492  ROS_DEBUG_STREAM("\tcommand_interface: "
493  << default_command_interface << " (default)");
494  }
495  else {
496  ROS_ERROR_STREAM("A command interface (speed or position) "
497  << "should be declared for the actuator " << it->first
498  << " or a default one should be defined with the parameter "
499  << "'default_command_interface'.");
500  }
501 
502  if (it->second.hasMember("reverse")) {
503  _invert[id] = servos_param[it->first]["reverse"];
504  }
505  }
506  }
507  catch (XmlRpc::XmlRpcException& e) {
508  ROS_FATAL_STREAM("Exception raised by XmlRpc while reading the "
509  << "configuration: " << e.getMessage() << ".\n"
510  << "Please check the configuration, particularly parameter types.");
511  return false;
512  }
513  }
514 
515  if (!got_all_params) {
516  std::string sub_namespace = robot_hw_nh.getNamespace();
517  std::string error_message = "One or more of the following parameters "
518  "were not set:\n"
519  + sub_namespace + "/serial_interface\n"
520  + sub_namespace + "/baudrate\n"
521  + sub_namespace + "/read_timeout\n"
522  + sub_namespace + "/servos";
523  ROS_FATAL_STREAM(error_message);
524  return false;
525  }
526 
527  // Get joint limits from the URDF or the parameter server
528  // ------------------------------------------------------
529 
530  std::string urdf_param_name("robot_description");
531  // TODO: document this feature
532  if (robot_hw_nh.hasParam("urdf_param_name"))
533  robot_hw_nh.getParam("urdf_param_name", urdf_param_name);
534 
535  if (!_load_urdf(root_nh, urdf_param_name))
536  ROS_INFO_STREAM("Unable to find a URDF model.");
537  else
538  ROS_DEBUG_STREAM("Received the URDF from param server.");
539 
540  return true;
541  }
542 
549  template <class Protocol>
551  const std::string& mode_string, std::string name)
552  {
553  dynamixel::OperatingMode mode;
554  if ("velocity" == mode_string)
555  mode = dynamixel::OperatingMode::wheel;
556  else if ("position" == mode_string)
557  mode = dynamixel::OperatingMode::joint;
558  else {
559  mode = dynamixel::OperatingMode::unknown;
560  ROS_ERROR_STREAM("The command mode " << mode_string
561  << " is not available (actuator "
562  << name << ")");
563  }
564 
565  return mode;
566  }
567 
574  template <class Protocol>
576  std::string param_name)
577  {
578  std::string urdf_string;
579  if (_urdf_model == nullptr)
580  _urdf_model = std::make_shared<urdf::Model>();
581 
582  // get the urdf param on param server
583  nh.getParam(param_name, urdf_string);
584 
585  return !urdf_string.empty() && _urdf_model->initString(urdf_string);
586  }
587 
595  template <class Protocol>
597  {
598  // extract servo IDs from _dynamixel_map
599  std::vector<typename Protocol::id_t> ids(_dynamixel_map.size());
600  using dm_iter_t = typename std::unordered_map<id_t, std::string>::iterator;
601  for (dm_iter_t dm_iter = _dynamixel_map.begin(); dm_iter != _dynamixel_map.end(); ++dm_iter) {
602  ids.push_back(dm_iter->first);
603  }
604 
605  // get the list of available actuators using the vector of IDs
606  try {
607  // small recv timeout for auto_detect
608  _dynamixel_controller.set_recv_timeout(_scan_timeout);
610  _servos = dynamixel::auto_detect<Protocol>(_dynamixel_controller, ids);
611  // restore recv timeout
612  _dynamixel_controller.set_recv_timeout(_read_timeout);
613  }
614  catch (dynamixel::errors::Error& e) {
615  ROS_FATAL_STREAM("Caught a Dynamixel exception while trying to "
616  << "initialise them:\n"
617  << e.msg());
618  return false;
619  }
620 
621  // remove servos that are not in the _dynamixel_map (i.e. that are not used)
623  typename std::vector<servo>::iterator servo_it;
624  for (servo_it = _servos.begin(); servo_it != _servos.end();) {
625  typename std::unordered_map<id_t, std::string>::iterator dynamixel_iterator
626  = _dynamixel_map.find((*servo_it)->id());
627  // the actuator's name is not in the map
628  if (dynamixel_iterator == _dynamixel_map.end())
629  servo_it = _servos.erase(servo_it);
630  else
631  ++servo_it;
632  }
633 
634  // Check that no actuator was declared by user but not found
635  int missing_servos = _dynamixel_map.size() - _servos.size();
636  if (missing_servos > 0) {
638  missing_servos
639  << " servo"
640  << (missing_servos > 1 ? "s were" : " was")
641  << " declared to the hardware interface but could not be found");
642  return false;
643  }
644 
645  _prev_commands.resize(_servos.size(), 0.0);
646  _joint_commands.resize(_servos.size(), 0.0);
647  _joint_angles.resize(_servos.size(), 0.0);
648  _joint_velocities.resize(_servos.size(), 0.0);
649  _joint_efforts.resize(_servos.size(), 0.0);
650 
651  return true;
652  }
653 
662  template <class Protocol>
664  dynamixel_servo servo, OperatingMode mode)
665  {
666  try {
667  // Enable the actuator
668 
669  dynamixel::StatusPacket<Protocol> status;
670  ROS_DEBUG_STREAM("Enabling servo " << servo->id());
671  _dynamixel_controller.send(servo->set_torque_enable(1));
672  _dynamixel_controller.recv(status);
673 
674  // Set max speed for actuators in position mode
675 
676  typename std::unordered_map<id_t, double>::iterator
677  dynamixel_max_speed_iterator
678  = _dynamixel_max_speed.find(servo->id());
679  if (dynamixel_max_speed_iterator != _dynamixel_max_speed.end()) {
680  if (OperatingMode::joint == mode) {
681  ROS_DEBUG_STREAM("Setting velocity limit of servo "
682  << _dynamixel_map[servo->id()] << " to "
683  << dynamixel_max_speed_iterator->second << " rad/s.");
685  servo->set_moving_speed_angle(
686  dynamixel_max_speed_iterator->second));
687  _dynamixel_controller.recv(status);
688  }
689  else {
690  ROS_WARN_STREAM("A \"max speed\" was defined for servo "
691  << servo->id() << " but it is currently only supported for "
692  << "servos in position mode. Ignoring the speed limit.");
693  }
694  }
695  else if (OperatingMode::joint == mode) {
696  ROS_DEBUG_STREAM("Resetting velocity limit of servo "
697  << _dynamixel_map[servo->id()] << ".");
698  _dynamixel_controller.send(servo->set_moving_speed_angle(0));
699  _dynamixel_controller.recv(status);
700  }
701  }
702  catch (dynamixel::errors::Error& e) {
703  ROS_ERROR_STREAM("Caught a Dynamixel exception while "
704  << "initializing:\n"
705  << e.msg());
706  }
707  }
708 
709  template <class Protocol>
711  const hardware_interface::JointHandle& cmd_handle,
712  id_t id)
713  {
714  // Limits datastructures
715  joint_limits_interface::JointLimits joint_limits; // Position
716  joint_limits_interface::SoftJointLimits soft_limits; // Soft Position
717  bool has_joint_limits = false;
718  bool has_soft_limits = false;
719 
720  // Get limits from URDF
721  if (_urdf_model == NULL) {
722  ROS_WARN_STREAM("No URDF model loaded, cannot be used to load joint"
723  " limits");
724  }
725  else {
726  // Get limits from URDF
727  urdf::JointConstSharedPtr urdf_joint
728  = _urdf_model->getJoint(cmd_handle.getName());
729 
730  // Get main joint limits
731  if (urdf_joint == nullptr) {
732  ROS_ERROR_STREAM("URDF joint not found "
733  << cmd_handle.getName());
734  return;
735  }
736 
737  // Get limits from URDF
738  if (joint_limits_interface::getJointLimits(urdf_joint, joint_limits)) {
739  has_joint_limits = true;
740  ROS_DEBUG_STREAM("Joint " << cmd_handle.getName()
741  << " has URDF position limits ["
742  << joint_limits.min_position << ", "
743  << joint_limits.max_position << "]");
744  if (joint_limits.has_velocity_limits)
745  ROS_DEBUG_STREAM("Joint " << cmd_handle.getName()
746  << " has URDF velocity limit ["
747  << joint_limits.max_velocity << "]");
748  }
749  else {
750  if (urdf_joint->type != urdf::Joint::CONTINUOUS)
751  ROS_WARN_STREAM("Joint " << cmd_handle.getName()
752  << " does not have a URDF "
753  "position limit");
754  }
755 
756  // Get soft limits from URDF
757  if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) {
758  has_soft_limits = true;
759  ROS_DEBUG_STREAM("Joint " << cmd_handle.getName()
760  << " has soft joint limits.");
761  }
762  else {
763  ROS_DEBUG_STREAM("Joint " << cmd_handle.getName()
764  << " does not have soft joint "
765  "limits");
766  }
767  }
768 
769  // Get limits from ROS param
770  if (joint_limits_interface::getJointLimits(cmd_handle.getName(), _nh, joint_limits)) {
771  has_joint_limits = true;
772  ROS_DEBUG_STREAM("Joint " << cmd_handle.getName()
773  << " has rosparam position limits ["
774  << joint_limits.min_position << ", "
775  << joint_limits.max_position << "]");
776  if (joint_limits.has_velocity_limits)
777  ROS_DEBUG_STREAM("Joint " << cmd_handle.getName()
778  << " has rosparam velocity limit ["
779  << joint_limits.max_velocity << "]");
780  } // the else debug message provided internally by joint_limits_interface
781 
782  // Slightly reduce the joint limits to prevent floating point errors
783  if (joint_limits.has_position_limits) {
784  joint_limits.min_position += std::numeric_limits<double>::epsilon();
785  joint_limits.max_position -= std::numeric_limits<double>::epsilon();
786  }
787 
788  // Save the velocity limit for later if the joint is in position mode
789  // it is going to be sent to the servo-motor which will enforce it.
790  if (joint_limits.has_velocity_limits
791  && OperatingMode::joint == _c_mode_map[id]) {
792  _dynamixel_max_speed[id] = joint_limits.max_velocity;
793  }
794 
795  if (has_soft_limits) // Use soft limits
796  {
797  ROS_DEBUG_STREAM("Using soft saturation limits");
798 
799  if (OperatingMode::joint == _c_mode_map[id]) {
800  const joint_limits_interface::PositionJointSoftLimitsHandle
801  soft_handle_position(
802  cmd_handle, joint_limits, soft_limits);
803  _jnt_pos_lim_interface.registerHandle(soft_handle_position);
804  }
805  else if (OperatingMode::wheel == _c_mode_map[id]) {
806  const joint_limits_interface::VelocityJointSoftLimitsHandle
807  soft_handle_velocity(
808  cmd_handle, joint_limits, soft_limits);
809  _jnt_vel_lim_interface.registerHandle(soft_handle_velocity);
810  }
811  }
812  else if (has_joint_limits) // Use saturation limits
813  {
814  ROS_DEBUG_STREAM("Using saturation limits (not soft limits)");
815  if (OperatingMode::joint == _c_mode_map[id]) {
816  const joint_limits_interface::PositionJointSaturationHandle
817  sat_handle_position(cmd_handle, joint_limits);
818  _jnt_pos_sat_interface.registerHandle(sat_handle_position);
819  }
820  else if (OperatingMode::wheel == _c_mode_map[id]) {
821  const joint_limits_interface::VelocityJointSaturationHandle
822  sat_handle_velocity(cmd_handle, joint_limits);
823  _jnt_vel_sat_interface.registerHandle(sat_handle_velocity);
824  }
825  }
826  } // namespace dynamixel
827 
828  template <class Protocol>
830  {
831  // enforce joint limits
832  _jnt_pos_lim_interface.enforceLimits(loop_period);
833  _jnt_vel_lim_interface.enforceLimits(loop_period);
834  _jnt_pos_sat_interface.enforceLimits(loop_period);
835  _jnt_vel_sat_interface.enforceLimits(loop_period);
836  }
837 } // namespace dynamixel
838 
839 #endif
const std::string & getMessage() const
hardware_interface::JointStateInterface _jnt_state_interface
std::unordered_map< id_t, OperatingMode > _c_mode_map
hardware_interface::VelocityJointInterface _jnt_vel_interface
bool _get_ros_parameters(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
joint_limits_interface::VelocityJointSoftLimitsInterface _jnt_vel_lim_interface
void _register_joint_limits(const hardware_interface::JointHandle &cmd_handle, id_t id)
joint_limits_interface::VelocityJointSaturationInterface _jnt_vel_sat_interface
bool _load_urdf(ros::NodeHandle &nh, std::string param_name)
virtual void read(const ros::Time &time, const ros::Duration &elapsed_time)
Type const & getType() const
std::unordered_map< id_t, bool > _invert
std::vector< dynamixel_servo > _servos
std::unordered_map< id_t, double > _dynamixel_max_speed
ROSLIB_DECL std::string command(const std::string &cmd)
#define ROS_FATAL_STREAM(args)
virtual void write(const ros::Time &time, const ros::Duration &elapsed_time)
dynamixel::controllers::Usb2Dynamixel _dynamixel_controller
std::unordered_map< id_t, double > _dynamixel_corrections
const std::string & getNamespace() const
joint_limits_interface::PositionJointSaturationInterface _jnt_pos_sat_interface
#define ROS_WARN_STREAM(args)
std::shared_ptr< dynamixel::servos::BaseServo< Protocol >> dynamixel_servo
#define ROS_DEBUG_STREAM(args)
void registerHandle(const JointStateHandle &handle)
std::shared_ptr< urdf::Model > _urdf_model
std::unordered_map< id_t, std::string > _dynamixel_map
JointStateHandle getHandle(const std::string &name)
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
#define ROS_INFO_STREAM(args)
void _enforce_limits(const ros::Duration &loop_period)
bool getParam(const std::string &key, std::string &s) const
hardware_interface::PositionJointInterface _jnt_pos_interface
static Time now()
dynamixel::OperatingMode _str2mode(const std::string &mode_string, std::string name)
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
void _enable_and_configure_servo(dynamixel_servo servo, OperatingMode mode)
DynamixelHardwareInterface & operator=(DynamixelHardwareInterface< Protocol > const &)=delete
joint_limits_interface::PositionJointSoftLimitsInterface _jnt_pos_lim_interface


dynamixel_control_hw
Author(s):
autogenerated on Mon Jun 10 2019 13:04:02