Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
dynamixel::DynamixelHardwareInterface< Protocol > Class Template Reference

#include <hardware_interface.hpp>

Inheritance diagram for dynamixel::DynamixelHardwareInterface< Protocol >:
Inheritance graph
[legend]

Public Types

using id_t = typename Protocol::id_t
 

Public Member Functions

 DynamixelHardwareInterface ()
 
bool init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
virtual void read (const ros::Time &time, const ros::Duration &elapsed_time)
 
virtual void write (const ros::Time &time, const ros::Duration &elapsed_time)
 
 ~DynamixelHardwareInterface ()
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
 RobotHW ()
 
virtual ~RobotHW ()
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Private Types

using dynamixel_servo = std::shared_ptr< dynamixel::servos::BaseServo< Protocol >>
 

Private Member Functions

void _enable_and_configure_servo (dynamixel_servo servo, OperatingMode mode)
 
void _enforce_limits (const ros::Duration &loop_period)
 
bool _find_servos ()
 
bool _get_ros_parameters (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
 
bool _load_urdf (ros::NodeHandle &nh, std::string param_name)
 
void _register_joint_limits (const hardware_interface::JointHandle &cmd_handle, id_t id)
 
dynamixel::OperatingMode _str2mode (const std::string &mode_string, std::string name)
 
 DynamixelHardwareInterface (DynamixelHardwareInterface< Protocol > const &)=delete
 
DynamixelHardwareInterfaceoperator= (DynamixelHardwareInterface< Protocol > const &)=delete
 

Private Attributes

int _baudrate
 
std::unordered_map< id_t, OperatingMode > _c_mode_map
 
dynamixel::controllers::Usb2Dynamixel _dynamixel_controller
 
std::unordered_map< id_t, double > _dynamixel_corrections
 
std::unordered_map< id_t, std::string > _dynamixel_map
 
std::unordered_map< id_t, double > _dynamixel_max_speed
 
std::unordered_map< id_t, bool > _invert
 
hardware_interface::PositionJointInterface _jnt_pos_interface
 
joint_limits_interface::PositionJointSoftLimitsInterface _jnt_pos_lim_interface
 
joint_limits_interface::PositionJointSaturationInterface _jnt_pos_sat_interface
 
hardware_interface::JointStateInterface _jnt_state_interface
 
hardware_interface::VelocityJointInterface _jnt_vel_interface
 
joint_limits_interface::VelocityJointSoftLimitsInterface _jnt_vel_lim_interface
 
joint_limits_interface::VelocityJointSaturationInterface _jnt_vel_sat_interface
 
std::vector< double > _joint_angles
 
std::vector< double > _joint_commands
 
std::vector< double > _joint_efforts
 
std::vector< double > _joint_velocities
 
ros::NodeHandle _nh
 
std::vector< double > _prev_commands
 
float _read_timeout
 
float _scan_timeout
 
std::vector< dynamixel_servo_servos
 
std::shared_ptr< urdf::Model_urdf_model
 
std::string _usb_serial_interface
 

Additional Inherited Members

- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
boost::ptr_vector< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

template<class Protocol>
class dynamixel::DynamixelHardwareInterface< Protocol >

Hardware interface for a set of dynamixel actuators.

This class fits in the ros_control framework for robot control.

Warning: this code is currently limited to joint-mode dynamixel actuators

Definition at line 36 of file hardware_interface.hpp.

Member Typedef Documentation

template<class Protocol>
using dynamixel::DynamixelHardwareInterface< Protocol >::dynamixel_servo = std::shared_ptr<dynamixel::servos::BaseServo<Protocol>>
private

Definition at line 69 of file hardware_interface.hpp.

template<class Protocol>
using dynamixel::DynamixelHardwareInterface< Protocol >::id_t = typename Protocol::id_t

Definition at line 39 of file hardware_interface.hpp.

Constructor & Destructor Documentation

template<class Protocol>
dynamixel::DynamixelHardwareInterface< Protocol >::DynamixelHardwareInterface ( )
inline

Definition at line 41 of file hardware_interface.hpp.

template<class Protocol >
dynamixel::DynamixelHardwareInterface< Protocol >::~DynamixelHardwareInterface ( )

Definition at line 134 of file hardware_interface.hpp.

template<class Protocol>
dynamixel::DynamixelHardwareInterface< Protocol >::DynamixelHardwareInterface ( DynamixelHardwareInterface< Protocol > const &  )
privatedelete

Member Function Documentation

template<class Protocol >
void dynamixel::DynamixelHardwareInterface< Protocol >::_enable_and_configure_servo ( dynamixel_servo  servo,
OperatingMode  mode 
)
private

Enable torque output for a joint and send it the relevant settings.

For now, these settings are only the speed limit.

Parameters
servothe actuator concerned
modeoperating mode of the actuator (e.g. position or velocity, in dynamixel speech, joint, wheel, etc.)

Definition at line 663 of file hardware_interface.hpp.

template<class Protocol >
void dynamixel::DynamixelHardwareInterface< Protocol >::_enforce_limits ( const ros::Duration loop_period)
private

Definition at line 829 of file hardware_interface.hpp.

template<class Protocol >
bool dynamixel::DynamixelHardwareInterface< Protocol >::_find_servos ( )
private

Search for the requested servos

Servos that were not requested are ignored and the software complain if any required one misses.

Returns
true if and only if there was no error

Definition at line 596 of file hardware_interface.hpp.

template<class Protocol >
bool dynamixel::DynamixelHardwareInterface< Protocol >::_get_ros_parameters ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
private

Retrieve all needed ROS parameters

Returns
true if and only if all went well

Definition at line 435 of file hardware_interface.hpp.

template<class Protocol >
bool dynamixel::DynamixelHardwareInterface< Protocol >::_load_urdf ( ros::NodeHandle nh,
std::string  param_name 
)
private

Search for the robot's URDF model on the parameter server and parse it

Parameters
nhNodeHandle used to query for the URDF
param_namename of the ROS parameter holding the robot model
urdf_modelpointer to be populated by this function

Definition at line 575 of file hardware_interface.hpp.

template<class Protocol >
void dynamixel::DynamixelHardwareInterface< Protocol >::_register_joint_limits ( const hardware_interface::JointHandle cmd_handle,
id_t  id 
)
private

Definition at line 710 of file hardware_interface.hpp.

template<class Protocol >
dynamixel::OperatingMode dynamixel::DynamixelHardwareInterface< Protocol >::_str2mode ( const std::string &  mode_string,
std::string  name 
)
private

Convert a string to an operating mode for a Dynamixel servo

Parameters
mode_stringname of the operating mode (either velocity or position)
namname of the joint
Returns
dynamixel::OperatingMode::unknown if mode_string is not recognized

Definition at line 550 of file hardware_interface.hpp.

template<class Protocol >
bool dynamixel::DynamixelHardwareInterface< Protocol >::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
virtual

Initialise the whole hardware interface.

Set the essential parameters for communication with the hardware and find all connected devices and register those referred in dynamixel_map in the hardware interface.

Reimplemented from hardware_interface::RobotHW.

Definition at line 152 of file hardware_interface.hpp.

template<class Protocol>
DynamixelHardwareInterface& dynamixel::DynamixelHardwareInterface< Protocol >::operator= ( DynamixelHardwareInterface< Protocol > const &  )
privatedelete
template<class Protocol >
void dynamixel::DynamixelHardwareInterface< Protocol >::read ( const ros::Time time,
const ros::Duration elapsed_time 
)
virtual

Copy joint's information to memory

firstly queries the information from the dynamixels, then put it in private attributes, for use by a controller.

Warning: do not get any information on torque

Reimplemented from hardware_interface::RobotHW.

Definition at line 274 of file hardware_interface.hpp.

template<class Protocol >
void dynamixel::DynamixelHardwareInterface< Protocol >::write ( const ros::Time time,
const ros::Duration elapsed_time 
)
virtual

Send new joint's target position to dynamixels

takes the target position from memory (given by a controller) and sends them to the dynamixels.

Reimplemented from hardware_interface::RobotHW.

Definition at line 357 of file hardware_interface.hpp.

Member Data Documentation

template<class Protocol>
int dynamixel::DynamixelHardwareInterface< Protocol >::_baudrate
private

Definition at line 108 of file hardware_interface.hpp.

template<class Protocol>
std::unordered_map<id_t, OperatingMode> dynamixel::DynamixelHardwareInterface< Protocol >::_c_mode_map
private

Definition at line 118 of file hardware_interface.hpp.

template<class Protocol>
dynamixel::controllers::Usb2Dynamixel dynamixel::DynamixelHardwareInterface< Protocol >::_dynamixel_controller
private

Definition at line 111 of file hardware_interface.hpp.

template<class Protocol>
std::unordered_map<id_t, double> dynamixel::DynamixelHardwareInterface< Protocol >::_dynamixel_corrections
private

Definition at line 124 of file hardware_interface.hpp.

template<class Protocol>
std::unordered_map<id_t, std::string> dynamixel::DynamixelHardwareInterface< Protocol >::_dynamixel_map
private

Definition at line 116 of file hardware_interface.hpp.

template<class Protocol>
std::unordered_map<id_t, double> dynamixel::DynamixelHardwareInterface< Protocol >::_dynamixel_max_speed
private

Definition at line 122 of file hardware_interface.hpp.

template<class Protocol>
std::unordered_map<id_t, bool> dynamixel::DynamixelHardwareInterface< Protocol >::_invert
private

Definition at line 120 of file hardware_interface.hpp.

template<class Protocol>
hardware_interface::PositionJointInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_pos_interface
private

Definition at line 89 of file hardware_interface.hpp.

template<class Protocol>
joint_limits_interface::PositionJointSoftLimitsInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_pos_lim_interface
private

Definition at line 93 of file hardware_interface.hpp.

template<class Protocol>
joint_limits_interface::PositionJointSaturationInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_pos_sat_interface
private

Definition at line 95 of file hardware_interface.hpp.

template<class Protocol>
hardware_interface::JointStateInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_state_interface
private

Definition at line 88 of file hardware_interface.hpp.

template<class Protocol>
hardware_interface::VelocityJointInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_vel_interface
private

Definition at line 90 of file hardware_interface.hpp.

template<class Protocol>
joint_limits_interface::VelocityJointSoftLimitsInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_vel_lim_interface
private

Definition at line 94 of file hardware_interface.hpp.

template<class Protocol>
joint_limits_interface::VelocityJointSaturationInterface dynamixel::DynamixelHardwareInterface< Protocol >::_jnt_vel_sat_interface
private

Definition at line 96 of file hardware_interface.hpp.

template<class Protocol>
std::vector<double> dynamixel::DynamixelHardwareInterface< Protocol >::_joint_angles
private

Definition at line 102 of file hardware_interface.hpp.

template<class Protocol>
std::vector<double> dynamixel::DynamixelHardwareInterface< Protocol >::_joint_commands
private

Definition at line 101 of file hardware_interface.hpp.

template<class Protocol>
std::vector<double> dynamixel::DynamixelHardwareInterface< Protocol >::_joint_efforts
private

Definition at line 104 of file hardware_interface.hpp.

template<class Protocol>
std::vector<double> dynamixel::DynamixelHardwareInterface< Protocol >::_joint_velocities
private

Definition at line 103 of file hardware_interface.hpp.

template<class Protocol>
ros::NodeHandle dynamixel::DynamixelHardwareInterface< Protocol >::_nh
private

Definition at line 127 of file hardware_interface.hpp.

template<class Protocol>
std::vector<double> dynamixel::DynamixelHardwareInterface< Protocol >::_prev_commands
private

Definition at line 100 of file hardware_interface.hpp.

template<class Protocol>
float dynamixel::DynamixelHardwareInterface< Protocol >::_read_timeout
private

Definition at line 109 of file hardware_interface.hpp.

template<class Protocol>
float dynamixel::DynamixelHardwareInterface< Protocol >::_scan_timeout
private

Definition at line 109 of file hardware_interface.hpp.

template<class Protocol>
std::vector<dynamixel_servo> dynamixel::DynamixelHardwareInterface< Protocol >::_servos
private

Definition at line 114 of file hardware_interface.hpp.

template<class Protocol>
std::shared_ptr<urdf::Model> dynamixel::DynamixelHardwareInterface< Protocol >::_urdf_model
private

Definition at line 130 of file hardware_interface.hpp.

template<class Protocol>
std::string dynamixel::DynamixelHardwareInterface< Protocol >::_usb_serial_interface
private

Definition at line 107 of file hardware_interface.hpp.


The documentation for this class was generated from the following file:


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