Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
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]

Public Member Functions

 EtherCATCompatibilityHand ()
 
virtual JointsMap getAllJointsData ()
 
virtual void getConfig (std::string joint_name)
 
virtual JointControllerData getContrl (std::string ctrlr_name)
 
virtual std::vector< DiagnosticDatagetDiagnostics ()
 
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::PublisheretherCAT_publishers
 
ros::Subscriber joint_state_subscriber
 
ros::NodeHandle n_tilde
 
ros::NodeHandle node
 
- Protected Attributes inherited from shadowrobot::SRArticulatedRobot
boost::shared_ptr< self_test::TestRunnerself_test
 this is the handle for the self tests. More...
 

Additional Inherited Members

- Public Types inherited from shadowrobot::SRArticulatedRobot
typedef std::map< std::string, JointDataJointsMap
 
typedef std::map< std::string, enum controller_parametersParametersMap
 
- 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
 

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

Constructor & Destructor Documentation

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.

shadowrobot::EtherCATCompatibilityHand::~EtherCATCompatibilityHand ( )
virtual

Definition at line 54 of file etherCAT_compatibility_hand.cpp.

Member Function Documentation

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 232 of file etherCAT_compatibility_hand.cpp.

SRArticulatedRobot::JointsMap shadowrobot::EtherCATCompatibilityHand::getAllJointsData ( )
virtual

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 317 of file etherCAT_compatibility_hand.cpp.

void shadowrobot::EtherCATCompatibilityHand::getConfig ( std::string  joint_name)
virtual

Get the config of the palm

Todo:
Not implemented yet
Parameters
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.

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

Implements shadowrobot::SRArticulatedRobot.

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

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

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.

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

Implements shadowrobot::SRArticulatedRobot.

Definition at line 293 of file etherCAT_compatibility_hand.cpp.

void shadowrobot::EtherCATCompatibilityHand::initializeMap ( )
protected

Initialize a mapping for the joints and the publishers.

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

Parameters
msgthe joint state message.

Definition at line 356 of file etherCAT_compatibility_hand.cpp.

int16_t 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 251 of file etherCAT_compatibility_hand.cpp.

int16_t 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 339 of file etherCAT_compatibility_hand.cpp.

int16_t 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 322 of file etherCAT_compatibility_hand.cpp.

Member Data Documentation

std::vector<ros::Publisher> shadowrobot::EtherCATCompatibilityHand::etherCAT_publishers
protected

Definition at line 122 of file etherCAT_compatibility_hand.hpp.

ros::Subscriber shadowrobot::EtherCATCompatibilityHand::joint_state_subscriber
protected

Definition at line 125 of file etherCAT_compatibility_hand.hpp.

ros::NodeHandle shadowrobot::EtherCATCompatibilityHand::n_tilde
protected

Definition at line 96 of file etherCAT_compatibility_hand.hpp.

ros::NodeHandle shadowrobot::EtherCATCompatibilityHand::node
protected

Definition at line 96 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 Tue Oct 13 2020 03:55:53