30 #ifndef _ETHERCAT_COMPATIBILITY_HAND_HPP_ 31 # define _ETHERCAT_COMPATIBILITY_HAND_HPP_ 34 #include <sensor_msgs/JointState.h> 67 virtual int16_t
sendupdate(std::string joint_name,
double target);
83 virtual int16_t
setConfig(std::vector<std::string> myConfig);
85 virtual void getConfig(std::string joint_name);
136 #endif // _ETHERCAT_COMPATIBILITY_HAND_HPP_ virtual JointData getJointData(std::string joint_name)
std::vector< ros::Publisher > etherCAT_publishers
virtual ~EtherCATCompatibilityHand()
std::map< std::string, JointData > JointsMap
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.
EtherCATCompatibilityHand()
std::string findControllerTopicName(std::string joint_name)
virtual std::vector< DiagnosticData > getDiagnostics()
virtual JointControllerData getContrl(std::string ctrlr_name)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
virtual int16_t sendupdate(std::string joint_name, double target)
virtual JointsMap getAllJointsData()
virtual void getConfig(std::string joint_name)
void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg)
virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
virtual int16_t setConfig(std::vector< std::string > myConfig)
ros::Subscriber joint_state_subscriber
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...