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 | |
ROS_DEPRECATED | 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 short | sendupdate (std::string joint_name, double target) |
virtual short | setConfig (std::vector< std::string > myConfig) |
virtual short | setContrl (std::string contrlr_name, JointControllerData ctrlr_data) |
~EtherCATCompatibilityHand () | |
destructor | |
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 |
This vector stores publishers to each joint controller. | |
ros::Subscriber | joint_state_subscriber |
a subscriber for the /joint_states topic. | |
ros::NodeHandle | n_tilde |
ros::NodeHandle | node |
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 43 of file etherCAT_compatibility_hand.hpp.
Initializes the necessary mappings with a static list of names.
Definition at line 39 of file etherCAT_compatibility_hand.cpp.
destructor
Definition at line 50 of file etherCAT_compatibility_hand.cpp.
std::string shadowrobot::EtherCATCompatibilityHand::findControllerTopicName | ( | std::string | joint_name | ) | [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 228 of file etherCAT_compatibility_hand.cpp.
SRArticulatedRobot::JointsMap shadowrobot::EtherCATCompatibilityHand::getAllJointsData | ( | ) | [virtual] |
Get the data for all the joints.
Implements shadowrobot::SRArticulatedRobot.
Definition at line 321 of file etherCAT_compatibility_hand.cpp.
void shadowrobot::EtherCATCompatibilityHand::getConfig | ( | std::string | joint_name | ) | [virtual] |
Get the config of the palm
joint_name |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 345 of file etherCAT_compatibility_hand.cpp.
JointControllerData shadowrobot::EtherCATCompatibilityHand::getContrl | ( | std::string | contrlr_name | ) | [virtual] |
Get the controller parameters for a given controller name.
contrlr_name | the name of the controller. |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 332 of file etherCAT_compatibility_hand.cpp.
std::vector< DiagnosticData > shadowrobot::EtherCATCompatibilityHand::getDiagnostics | ( | ) | [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.
JointData shadowrobot::EtherCATCompatibilityHand::getJointData | ( | std::string | joint_name | ) | [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 299 of file etherCAT_compatibility_hand.cpp.
void shadowrobot::EtherCATCompatibilityHand::initializeMap | ( | ) | [protected] |
Initialize a mapping for the joints and the publishers.
Definition at line 54 of file etherCAT_compatibility_hand.cpp.
void shadowrobot::EtherCATCompatibilityHand::joint_states_callback | ( | const sensor_msgs::JointStateConstPtr & | msg | ) | [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.
short shadowrobot::EtherCATCompatibilityHand::sendupdate | ( | std::string | joint_name, |
double | target | ||
) | [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 262 of file etherCAT_compatibility_hand.cpp.
short shadowrobot::EtherCATCompatibilityHand::setConfig | ( | std::vector< std::string > | myConfig | ) | [virtual] |
Set the config of the palm
myConfig |
Implements shadowrobot::SRArticulatedRobot.
Definition at line 339 of file etherCAT_compatibility_hand.cpp.
short shadowrobot::EtherCATCompatibilityHand::setContrl | ( | std::string | contrlr_name, |
JointControllerData | ctrlr_data | ||
) | [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 326 of file etherCAT_compatibility_hand.cpp.
std::vector< ros::Publisher > shadowrobot::EtherCATCompatibilityHand::etherCAT_publishers [protected] |
This vector stores publishers to each joint controller.
Definition at line 112 of file etherCAT_compatibility_hand.hpp.
a subscriber for the /joint_states topic.
Definition at line 115 of file etherCAT_compatibility_hand.hpp.
Definition at line 86 of file etherCAT_compatibility_hand.hpp.
Definition at line 86 of file etherCAT_compatibility_hand.hpp.