This compatibility interface is a wrapper around the new etherCAT Hand ROS driver. It is used to present the same interface as the CAN hand. More...
#include <etherCAT_compatibility_hand.hpp>

Public Member Functions | |
| EtherCATCompatibilityHand () | |
| virtual JointsMap | getAllJointsData () |
| virtual void | getConfig (std::string joint_name) |
| virtual JointControllerData | getContrl (std::string ctrlr_name) |
| virtual std::vector< DiagnosticData > | getDiagnostics () |
| virtual JointData | getJointData (std::string joint_name) |
| virtual int16_t | sendupdate (std::string joint_name, double target) |
| virtual int16_t | setConfig (std::vector< std::string > myConfig) |
| virtual int16_t | setContrl (std::string contrlr_name, JointControllerData ctrlr_data) |
| virtual | ~EtherCATCompatibilityHand () |
Public Member Functions inherited from shadowrobot::SRArticulatedRobot | |
| SRArticulatedRobot () | |
| virtual | ~SRArticulatedRobot () |
Protected Member Functions | |
| std::string | findControllerTopicName (std::string joint_name) |
| void | initializeMap () |
| void | joint_states_callback (const sensor_msgs::JointStateConstPtr &msg) |
Protected Attributes | |
| std::vector< ros::Publisher > | etherCAT_publishers |
| ros::Subscriber | joint_state_subscriber |
| ros::NodeHandle | n_tilde |
| ros::NodeHandle | node |
Protected Attributes inherited from shadowrobot::SRArticulatedRobot | |
| boost::shared_ptr< self_test::TestRunner > | self_test |
| this is the handle for the self tests. More... | |
Additional Inherited Members | |
Public Types inherited from shadowrobot::SRArticulatedRobot | |
| typedef std::map< std::string, JointData > | JointsMap |
| typedef std::map< std::string, enum controller_parameters > | ParametersMap |
Public Attributes inherited from shadowrobot::SRArticulatedRobot | |
| boost::mutex | controllers_map_mutex |
| JointsMap | joints_map |
| A mapping between the joint names and the information regarding those joints. More... | |
| boost::mutex | joints_map_mutex |
| ParametersMap | parameters_map |
| A mapping between the parameter names and their values. More... | |
| boost::mutex | parameters_map_mutex |
This compatibility interface is a wrapper around the new etherCAT Hand ROS driver. It is used to present the same interface as the CAN hand.
Definition at line 48 of file etherCAT_compatibility_hand.hpp.
| ROS_DEPRECATED shadowrobot::EtherCATCompatibilityHand::EtherCATCompatibilityHand | ( | ) |
Initializes the necessary mappings with a static list of names.
Definition at line 41 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Definition at line 54 of file etherCAT_compatibility_hand.cpp.
|
protected |
Finds the controller suffix to use for a certain joint based on listening to the controller state for that joint. mixed_position_velocity_controller and position_controller are checked. If none of them is sending messages, the "controller_suffix" parameter is used
Full controller command topic name is returned
Definition at line 232 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Get the data for all the joints.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 317 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Get the config of the palm
| joint_name |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 345 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Get the controller parameters for a given controller name.
| contrlr_name | the name of the controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 330 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Not used in this interface: the diagnostics are published directly by the EtherCAT hand driver.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 350 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Returns the last data we received for the given joint.
| joint_name | The name of the joint, as specified in joints_map. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 293 of file etherCAT_compatibility_hand.cpp.
|
protected |
Initialize a mapping for the joints and the publishers.
Definition at line 58 of file etherCAT_compatibility_hand.cpp.
|
protected |
This callback is called each time a joint state message is received. We Update the internal joint map when we receive this message.
| msg | the joint state message. |
Definition at line 356 of file etherCAT_compatibility_hand.cpp.
|
virtual |
This function will send the targets to the correct controllers.
| joint_name | The Joint in joints_map you wish to send the target to. |
| target | The target in degree |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 251 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Set the config of the palm
| myConfig |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 339 of file etherCAT_compatibility_hand.cpp.
|
virtual |
Set the controller parameters for a given controller name.
| contrlr_name | The name of the controller to setup. |
| ctrlr_data | The data to pass to this controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 322 of file etherCAT_compatibility_hand.cpp.
|
protected |
Definition at line 122 of file etherCAT_compatibility_hand.hpp.
|
protected |
Definition at line 125 of file etherCAT_compatibility_hand.hpp.
|
protected |
Definition at line 96 of file etherCAT_compatibility_hand.hpp.
|
protected |
Definition at line 96 of file etherCAT_compatibility_hand.hpp.