virtual_arm.h
Go to the documentation of this file.
1 
26 #ifndef SR_HAND_HAND_VIRTUAL_ARM_H
27 #define SR_HAND_HAND_VIRTUAL_ARM_H
28 
30 #include <string>
31 #include <vector>
32 
33 namespace shadowrobot
34 {
35 class VirtualArm :
36  public SRArticulatedRobot
37 {
38 public:
42  VirtualArm();
43 
44  virtual ~VirtualArm();
45 
46  // virtual classes defined in SRArticulatedRobot
57  virtual int16_t sendupdate(std::string joint_name, double target);
58 
67  virtual JointData getJointData(std::string joint_name);
68 
69  virtual JointsMap getAllJointsData();
70 
71  virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data);
72 
73  virtual JointControllerData getContrl(std::string ctrlr_name);
74 
75  virtual int16_t setConfig(std::vector<std::string> myConfig);
76 
77  virtual void getConfig(std::string joint_name);
78 
84  virtual std::vector<DiagnosticData> getDiagnostics();
85 
86 protected:
87 #ifdef GAZEBO
88 
92  ros::NodeHandle node, n_tilde;
93 
94  void gazeboCallback(const sensor_msgs::JointStateConstPtr& msg);
95 #endif
96 
100  void initializeMap();
101 
107  inline double toRad(double deg)
108  {
109  return deg * 3.14159265 / 180.0;
110  }
111 
117  inline double toDegrees(double rad)
118  {
119  return rad * 180.0 / 3.14159265;
120  }
121 };
122 
123 } // namespace shadowrobot
124 
125 #endif // SR_HAND_HAND_VIRTUAL_ARM_H
msg
virtual int16_t sendupdate(std::string joint_name, double target)
virtual JointData getJointData(std::string joint_name)
virtual std::vector< DiagnosticData > getDiagnostics()
double toRad(double deg)
Definition: virtual_arm.h:107
std::map< std::string, JointData > JointsMap
virtual JointsMap getAllJointsData()
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...
virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
virtual void getConfig(std::string joint_name)
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...
double toDegrees(double rad)
Definition: virtual_arm.h:117


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