00001 00026 #ifndef VIRTUAL_ARM_H_ 00027 #define VIRTUAL_ARM_H_ 00028 00029 #include "sr_hand/hand/sr_articulated_robot.h" 00030 00031 namespace shadowrobot 00032 { 00033 00034 class VirtualArm : public SRArticulatedRobot 00035 { 00036 public: 00040 VirtualArm(); 00041 virtual ~VirtualArm(); 00042 00043 //virtual classes defined in SRArticulatedRobot 00054 virtual short sendupdate( std::string joint_name, double target ); 00055 00064 virtual JointData getJointData( std::string joint_name ); 00065 virtual JointsMap getAllJointsData(); 00066 00067 virtual short setContrl( std::string contrlr_name, JointControllerData ctrlr_data ); 00068 virtual JointControllerData getContrl( std::string ctrlr_name ); 00069 00070 virtual short setConfig( std::vector<std::string> myConfig ); 00071 virtual void getConfig( std::string joint_name ); 00072 00078 virtual std::vector<DiagnosticData> getDiagnostics(); 00079 protected: 00080 #ifdef GAZEBO 00081 00085 ros::NodeHandle node, n_tilde; 00086 00087 void gazeboCallback(const sensor_msgs::JointStateConstPtr& msg); 00088 #endif 00089 00092 void initializeMap(); 00093 00099 inline double toRad( double deg ) 00100 { 00101 return deg * 3.14159265 / 180.0; 00102 } 00103 00109 inline double toDegrees( double rad ) 00110 { 00111 return rad * 180.0 / 3.14159265; 00112 } 00113 }; 00114 00115 }//end namespace 00116 00117 #endif /* VIRTUAL_ARM_H_ */