virtual_shadowhand.h
Go to the documentation of this file.
1 
29 #ifndef SR_HAND_HAND_VIRTUAL_SHADOWHAND_H
30 #define SR_HAND_HAND_VIRTUAL_SHADOWHAND_H
31 
33 #include <string>
34 #include <vector>
35 #include <map>
36 
37 namespace shadowrobot
38 {
47  public SRArticulatedRobot
48 {
49 public:
54 
55  virtual ~VirtualShadowhand();
56 
57  // virtual classes defined in Shadowhand
68  virtual int16_t sendupdate(std::string joint_name, double target);
69 
78  virtual JointData getJointData(std::string joint_name);
79 
80  virtual JointsMap getAllJointsData();
81 
82  virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data);
83 
84  virtual JointControllerData getContrl(std::string ctrlr_name);
85 
86  virtual int16_t setConfig(std::vector<std::string> myConfig);
87 
88  virtual void getConfig(std::string joint_name);
89 
95  virtual std::vector<DiagnosticData> getDiagnostics();
96 
97 protected:
100 
101 #ifdef GAZEBO
102 
108  void gazeboCallback(const sensor_msgs::JointStateConstPtr& msg);
109 #endif
110 
114  void initializeMap();
115 
117  typedef std::map<std::string, JointControllerData> ControllersMap;
119  ControllersMap controllers_map;
120 
126  inline double toRad(double deg)
127  {
128  return deg * 3.14159265 / 180.0;
129  }
130 
136  inline double toDegrees(double rad)
137  {
138  return rad * 180.0 / 3.14159265;
139  }
140 }; // end class
141 } // namespace shadowrobot
142 
143 #endif // SR_HAND_HAND_VIRTUAL_SHADOWHAND_H
virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
virtual JointControllerData getContrl(std::string ctrlr_name)
ros::NodeHandle node
ROS Node handles.
virtual int16_t setConfig(std::vector< std::string > myConfig)
std::map< std::string, JointData > JointsMap
virtual std::vector< DiagnosticData > getDiagnostics()
virtual void getConfig(std::string joint_name)
ControllersMap controllers_map
Contains the mapping between the controller names and their data.
The Virtual Shadowhand can be used as a simulator. As both the real hand and the virtual hand are chi...
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)
std::map< std::string, JointControllerData > ControllersMap
virtual JointData getJointData(std::string joint_name)
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