31 #ifndef _CAN_COMPATIBILITY_ARM_HPP_ 32 # define _CAN_COMPATIBILITY_ARM_HPP_ 35 #include <sensor_msgs/JointState.h> 66 virtual int16_t
sendupdate(std::string joint_name,
double target);
82 virtual int16_t
setConfig(std::vector <std::string> myConfig);
84 virtual void getConfig(std::string joint_name);
125 #endif // _ETHERCAT_COMPATIBILITY_HAND_HPP_ virtual JointControllerData getContrl(std::string ctrlr_name)
ROS_DEPRECATED CANCompatibilityArm()
virtual JointsMap getAllJointsData()
std::map< std::string, JointData > JointsMap
virtual int16_t sendupdate(std::string joint_name, double target)
void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg)
virtual std::vector< DiagnosticData > getDiagnostics()
virtual JointData getJointData(std::string joint_name)
virtual ~CANCompatibilityArm()
virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
This compatibility interface is a wrapper around the new CAN Hand ROS driver. It is used to present t...
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
ros::Subscriber joint_state_subscriber
virtual void getConfig(std::string joint_name)
std::vector< ros::Publisher > CAN_publishers
virtual int16_t setConfig(std::vector< std::string > myConfig)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...