1 #ifndef dynamixel_hardware_interface 2 #define dynamixel_hardware_interface 7 #include <unordered_map> 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> 26 #include <dynamixel/dynamixel.hpp> 35 template <
class Protocol>
39 using id_t =
typename Protocol::id_t;
77 dynamixel::OperatingMode
_str2mode(
const std::string& mode_string,
133 template <
class Protocol>
139 dynamixel::StatusPacket<Protocol> status;
144 catch (dynamixel::errors::Error& e) {
146 <<
"power them off:\n" 151 template <
class Protocol>
164 for (
unsigned i = 0; i <
_servos.size(); i++) {
168 typename std::unordered_map<id_t, std::string>::iterator dynamixel_iterator
174 dynamixel_iterator->second,
182 OperatingMode hardware_mode
184 typename std::unordered_map<id_t, OperatingMode>::iterator c_mode_map_i
187 if (c_mode_map_i->second != hardware_mode) {
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.");
198 <<
"for joint " << dynamixel_iterator->second
199 <<
". Disabling this joint.");
209 if (OperatingMode::joint == hardware_mode) {
212 else if (OperatingMode::wheel == hardware_mode) {
215 else if (OperatingMode::unknown != hardware_mode) {
217 <<
"(operating mode " 218 << mode2str(hardware_mode)
219 <<
" is not supported)");
239 <<
"(not found in the parameters)");
254 <<
"actuators might have already been started.");
262 for (
unsigned i = 0; i <
_servos.size(); i++) {
264 if (OperatingMode::joint == mode)
266 else if (OperatingMode::wheel == mode)
273 template <
class Protocol>
277 for (
unsigned i = 0; i <
_servos.size(); i++) {
278 dynamixel::StatusPacket<Protocol> status;
284 catch (dynamixel::errors::Error& e) {
289 if (status.valid()) {
293 catch (dynamixel::errors::Error& e) {
300 typename std::unordered_map<id_t, bool>::iterator
303 if (invert_iterator !=
_invert.end()) {
308 typename std::unordered_map<id_t, double>::iterator
309 dynamixel_corrections_iterator
320 dynamixel::StatusPacket<Protocol> status_speed;
326 catch (dynamixel::errors::Error& e) {
331 if (status_speed.valid()) {
334 =
_servos[i]->parse_joint_speed(status_speed);
336 typename std::unordered_map<id_t, bool>::iterator
339 if (invert_iterator !=
_invert.end()
340 && invert_iterator->second)
343 catch (dynamixel::errors::Error& e) {
356 template <
class Protocol>
363 for (
unsigned int i = 0; i <
_servos.size(); i++) {
369 dynamixel::StatusPacket<Protocol> status;
374 if (OperatingMode::joint == mode) {
375 typename std::unordered_map<id_t, double>::iterator
376 dynamixel_corrections_iterator
379 command += dynamixel_corrections_iterator->second;
383 typename std::unordered_map<id_t, bool>::iterator
385 =
_invert.find(_servos[i]->
id());
386 if (invert_iterator !=
_invert.end()) {
387 command = 2 * M_PI - command;
394 _servos[i]->reg_goal_position_angle(command));
397 else if (OperatingMode::wheel == mode) {
399 const short sign = 1;
400 typename std::unordered_map<id_t, bool>::iterator
402 =
_invert.find(_servos[i]->
id());
403 if (invert_iterator !=
_invert.end()
404 && invert_iterator->second) {
408 << _servos[i]->
id() <<
" to " << command);
410 _servos[i]->reg_moving_speed_angle(command, mode));
414 catch (dynamixel::errors::Error& e) {
424 catch (dynamixel::errors::Error& e) {
434 template <
class Protocol>
437 bool got_all_params =
true;
441 got_all_params &= robot_hw_nh.
getParam(
"baudrate", baudrate);
447 <<
"Setting to default: 0.05s.");
450 std::string default_command_interface;
451 bool has_default_command_interface = robot_hw_nh.
getParam(
452 "default_command_interface", default_command_interface);
456 if (got_all_params &= robot_hw_nh.
getParam(
"servos", servos_param)) {
459 for (XmlRpc::XmlRpcValue::ValueStruct::const_iterator it = servos_param.
begin(); it != servos_param.
end(); ++it) {
463 if (it->second.hasMember(
"id")) {
464 id =
static_cast<int>(servos_param[it->first][
"id"]);
470 <<
" has no associated servo ID.");
474 if (it->second.hasMember(
"offset")) {
476 =
static_cast<double>(servos_param[it->first][
"offset"]);
481 if (it->second.hasMember(
"command_interface")) {
482 std::string mode_string
483 =
static_cast<std::string
>(
484 servos_param[it->first][
"command_interface"]);
489 else if (has_default_command_interface) {
491 =
_str2mode(default_command_interface, it->first);
493 << default_command_interface <<
" (default)");
497 <<
"should be declared for the actuator " << it->first
498 <<
" or a default one should be defined with the parameter " 499 <<
"'default_command_interface'.");
502 if (it->second.hasMember(
"reverse")) {
503 _invert[id] = servos_param[it->first][
"reverse"];
509 <<
"configuration: " << e.
getMessage() <<
".\n" 510 <<
"Please check the configuration, particularly parameter types.");
515 if (!got_all_params) {
517 std::string error_message =
"One or more of the following parameters " 519 + sub_namespace +
"/serial_interface\n" 520 + sub_namespace +
"/baudrate\n" 521 + sub_namespace +
"/read_timeout\n" 522 + sub_namespace +
"/servos";
530 std::string urdf_param_name(
"robot_description");
532 if (robot_hw_nh.
hasParam(
"urdf_param_name"))
533 robot_hw_nh.
getParam(
"urdf_param_name", urdf_param_name);
549 template <
class Protocol>
551 const std::string& mode_string, std::string name)
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;
559 mode = dynamixel::OperatingMode::unknown;
561 <<
" is not available (actuator " 574 template <
class Protocol>
576 std::string param_name)
578 std::string urdf_string;
583 nh.
getParam(param_name, urdf_string);
585 return !urdf_string.empty() &&
_urdf_model->initString(urdf_string);
595 template <
class Protocol>
600 using dm_iter_t =
typename std::unordered_map<id_t, std::string>::iterator;
602 ids.push_back(dm_iter->first);
614 catch (dynamixel::errors::Error& e) {
616 <<
"initialise them:\n" 623 typename std::vector<servo>::iterator servo_it;
625 typename std::unordered_map<id_t, std::string>::iterator dynamixel_iterator
629 servo_it =
_servos.erase(servo_it);
636 if (missing_servos > 0) {
640 << (missing_servos > 1 ?
"s were" :
" was")
641 <<
" declared to the hardware interface but could not be found");
662 template <
class Protocol>
669 dynamixel::StatusPacket<Protocol> status;
676 typename std::unordered_map<id_t, double>::iterator
677 dynamixel_max_speed_iterator
680 if (OperatingMode::joint == mode) {
683 << dynamixel_max_speed_iterator->second <<
" rad/s.");
685 servo->set_moving_speed_angle(
686 dynamixel_max_speed_iterator->second));
691 << servo->id() <<
" but it is currently only supported for " 692 <<
"servos in position mode. Ignoring the speed limit.");
695 else if (OperatingMode::joint == mode) {
702 catch (dynamixel::errors::Error& e) {
709 template <
class Protocol>
715 joint_limits_interface::JointLimits joint_limits;
716 joint_limits_interface::SoftJointLimits soft_limits;
717 bool has_joint_limits =
false;
718 bool has_soft_limits =
false;
727 urdf::JointConstSharedPtr urdf_joint
731 if (urdf_joint ==
nullptr) {
738 if (joint_limits_interface::getJointLimits(urdf_joint, joint_limits)) {
739 has_joint_limits =
true;
741 <<
" has URDF position limits [" 742 << joint_limits.min_position <<
", " 743 << joint_limits.max_position <<
"]");
744 if (joint_limits.has_velocity_limits)
746 <<
" has URDF velocity limit [" 747 << joint_limits.max_velocity <<
"]");
750 if (urdf_joint->type != urdf::Joint::CONTINUOUS)
752 <<
" does not have a URDF " 757 if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits)) {
758 has_soft_limits =
true;
760 <<
" has soft joint limits.");
764 <<
" does not have soft joint " 770 if (joint_limits_interface::getJointLimits(cmd_handle.
getName(),
_nh, joint_limits)) {
771 has_joint_limits =
true;
773 <<
" has rosparam position limits [" 774 << joint_limits.min_position <<
", " 775 << joint_limits.max_position <<
"]");
776 if (joint_limits.has_velocity_limits)
778 <<
" has rosparam velocity limit [" 779 << joint_limits.max_velocity <<
"]");
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();
790 if (joint_limits.has_velocity_limits
800 const joint_limits_interface::PositionJointSoftLimitsHandle
801 soft_handle_position(
802 cmd_handle, joint_limits, soft_limits);
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);
812 else if (has_joint_limits)
816 const joint_limits_interface::PositionJointSaturationHandle
817 sat_handle_position(cmd_handle, joint_limits);
820 else if (OperatingMode::wheel ==
_c_mode_map[
id]) {
821 const joint_limits_interface::VelocityJointSaturationHandle
822 sat_handle_velocity(cmd_handle, joint_limits);
828 template <
class Protocol>
void registerInterface(T *iface)
std::vector< double > _joint_efforts
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)
std::vector< double > _joint_commands
DynamixelHardwareInterface()
joint_limits_interface::VelocityJointSoftLimitsInterface _jnt_vel_lim_interface
void _register_joint_limits(const hardware_interface::JointHandle &cmd_handle, id_t id)
std::string getName() const
joint_limits_interface::VelocityJointSaturationInterface _jnt_vel_sat_interface
bool _load_urdf(ros::NodeHandle &nh, std::string param_name)
std::string _usb_serial_interface
virtual void read(const ros::Time &time, const ros::Duration &elapsed_time)
std::vector< double > _prev_commands
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
std::vector< double > _joint_angles
#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
dynamixel::OperatingMode _str2mode(const std::string &mode_string, std::string name)
std::vector< double > _joint_velocities
~DynamixelHardwareInterface()
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
void _enable_and_configure_servo(dynamixel_servo servo, OperatingMode mode)
DynamixelHardwareInterface & operator=(DynamixelHardwareInterface< Protocol > const &)=delete
joint_limits_interface::PositionJointSoftLimitsInterface _jnt_pos_lim_interface
typename Protocol::id_t id_t