Public Member Functions | Protected Member Functions | Protected Attributes
shadowrobot::EtherCATCompatibilityHand Class Reference

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>

Inheritance diagram for shadowrobot::EtherCATCompatibilityHand:
Inheritance graph
[legend]

List of all members.

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 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)
virtual ~EtherCATCompatibilityHand ()

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::PublisheretherCAT_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

Detailed Description

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 45 of file etherCAT_compatibility_hand.hpp.


Constructor & Destructor Documentation

Initializes the necessary mappings with a static list of names.

Definition at line 39 of file etherCAT_compatibility_hand.cpp.

Definition at line 50 of file etherCAT_compatibility_hand.cpp.


Member Function Documentation

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.

Get the data for all the joints.

Returns:
a mapping between the joints names and the information for each joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 306 of file etherCAT_compatibility_hand.cpp.

Get the config of the palm

Todo:
Not implemented yet
Parameters:
joint_name

Implements shadowrobot::SRArticulatedRobot.

Definition at line 330 of file etherCAT_compatibility_hand.cpp.

Get the controller parameters for a given controller name.

Parameters:
contrlr_namethe name of the controller.
Returns:
The parameters of this controller

Implements shadowrobot::SRArticulatedRobot.

Definition at line 317 of file etherCAT_compatibility_hand.cpp.

Not used in this interface: the diagnostics are published directly by the EtherCAT hand driver.

Returns:
A vector containing all the diagnostics for the hand (motor information, etc...)

Implements shadowrobot::SRArticulatedRobot.

Definition at line 335 of file etherCAT_compatibility_hand.cpp.

Returns the last data we received for the given joint.

Parameters:
joint_nameThe name of the joint, as specified in joints_map.
Returns:
The information regarding this joint.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 284 of file etherCAT_compatibility_hand.cpp.

Initialize a mapping for the joints and the publishers.

Definition at line 54 of file etherCAT_compatibility_hand.cpp.

This callback is called each time a joint state message is received. We Update the internal joint map when we receive this message.

Parameters:
msgthe joint state message.

Definition at line 341 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.

Parameters:
joint_nameThe Joint in joints_map you wish to send the target to.
targetThe target in degree
Returns:
0 if success ; -1 if error

Implements shadowrobot::SRArticulatedRobot.

Definition at line 247 of file etherCAT_compatibility_hand.cpp.

short shadowrobot::EtherCATCompatibilityHand::setConfig ( std::vector< std::string myConfig) [virtual]

Set the config of the palm

Todo:
Not implemented yet
Parameters:
myConfig
Returns:

Implements shadowrobot::SRArticulatedRobot.

Definition at line 324 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.

Parameters:
contrlr_nameThe name of the controller to setup.
ctrlr_dataThe data to pass to this controller.
Returns:
0 if success.

Implements shadowrobot::SRArticulatedRobot.

Definition at line 311 of file etherCAT_compatibility_hand.cpp.


Member Data Documentation

This vector stores publishers to each joint controller.

Definition at line 113 of file etherCAT_compatibility_hand.hpp.

a subscriber for the /joint_states topic.

Definition at line 116 of file etherCAT_compatibility_hand.hpp.

Definition at line 87 of file etherCAT_compatibility_hand.hpp.

Definition at line 87 of file etherCAT_compatibility_hand.hpp.


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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:24:55