CAN_compatibility_arm.hpp
Go to the documentation of this file.
1 
31 #ifndef _CAN_COMPATIBILITY_ARM_HPP_
32 # define _CAN_COMPATIBILITY_ARM_HPP_
33 
35 #include <sensor_msgs/JointState.h>
36 
37 #include <string>
38 #include <vector>
39 
40 namespace shadowrobot
41 {
48  public SRArticulatedRobot
49 {
50 public:
55 
56  virtual ~CANCompatibilityArm();
57 
58  // virtual classes defined in Shadowhand
66  virtual int16_t sendupdate(std::string joint_name, double target);
67 
74  virtual JointData getJointData(std::string joint_name);
75 
76  virtual JointsMap getAllJointsData();
77 
78  virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data);
79 
80  virtual JointControllerData getContrl(std::string ctrlr_name);
81 
82  virtual int16_t setConfig(std::vector <std::string> myConfig);
83 
84  virtual void getConfig(std::string joint_name);
85 
92  virtual std::vector <DiagnosticData> getDiagnostics();
93 
94 protected:
96 
103  void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg);
104 
108  void initializeMap();
109 
110  // This vector stores publishers to each joint controller.
111  std::vector <ros::Publisher> CAN_publishers;
112 
113  // a subscriber for the /joint_states topic.
115 }; // end class
116 } // namespace shadowrobot
117 
118 /* For the emacs weenies in the crowd.
119 Local Variables:
120  c-basic-offset: 2
121 End:
122 */
123 
124 
125 #endif // _ETHERCAT_COMPATIBILITY_HAND_HPP_
virtual JointControllerData getContrl(std::string ctrlr_name)
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 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...
#define ROS_DEPRECATED
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
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...


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