etherCAT_compatibility_hand.hpp
Go to the documentation of this file.
1 
30 #ifndef _ETHERCAT_COMPATIBILITY_HAND_HPP_
31 # define _ETHERCAT_COMPATIBILITY_HAND_HPP_
32 
34 #include <sensor_msgs/JointState.h>
35 
36 #include <string>
37 #include <vector>
38 
39 namespace shadowrobot
40 {
41 // THIS CLASS IS CONSIDERED DEPRECATED AND SHOULD NOT BE USED FOR ANY NEW PACKAGE.
42 // IT IS NOT MARKED AS DEPRECATED THOUGH, AS IT IS STILL USED IN SOME OLD NODES
49  public SRArticulatedRobot
50 {
51 public:
56 
58 
59  // virtual classes defined in Shadowhand
67  virtual int16_t sendupdate(std::string joint_name, double target);
68 
75  virtual JointData getJointData(std::string joint_name);
76 
77  virtual JointsMap getAllJointsData();
78 
79  virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data);
80 
81  virtual JointControllerData getContrl(std::string ctrlr_name);
82 
83  virtual int16_t setConfig(std::vector<std::string> myConfig);
84 
85  virtual void getConfig(std::string joint_name);
86 
93  virtual std::vector<DiagnosticData> getDiagnostics();
94 
95 protected:
97 
104  void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg);
105 
109  void initializeMap();
110 
119  std::string findControllerTopicName(std::string joint_name);
120 
121  // This vector stores publishers to each joint controller.
122  std::vector<ros::Publisher> etherCAT_publishers;
123 
124  // a subscriber for the /joint_states topic.
126 }; // end class
127 } // namespace shadowrobot
128 
129 /* For the emacs weenies in the crowd.
130 Local Variables:
131  c-basic-offset: 2
132 End:
133 */
134 
135 
136 #endif // _ETHERCAT_COMPATIBILITY_HAND_HPP_
virtual JointData getJointData(std::string joint_name)
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.
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 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)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53