00001 00029 #ifndef VIRTUAL_SHADOWHAND_H_ 00030 # define VIRTUAL_SHADOWHAND_H_ 00031 00032 #include "sr_hand/hand/sr_articulated_robot.h" 00033 00034 namespace shadowrobot 00035 { 00042 class VirtualShadowhand : public SRArticulatedRobot 00043 { 00044 public: 00048 VirtualShadowhand(); 00050 ~VirtualShadowhand(); 00051 00052 //virtual classes defined in Shadowhand 00063 virtual short sendupdate( std::string joint_name, double target ); 00064 00073 virtual JointData getJointData( std::string joint_name ); 00074 virtual JointsMap getAllJointsData(); 00075 00076 virtual short setContrl( std::string contrlr_name, JointControllerData ctrlr_data ); 00077 virtual JointControllerData getContrl( std::string ctrlr_name ); 00078 00079 virtual short setConfig( std::vector<std::string> myConfig ); 00080 virtual void getConfig( std::string joint_name ); 00081 00087 virtual std::vector<DiagnosticData> getDiagnostics(); 00088 protected: 00089 #ifdef GAZEBO 00090 00094 ros::NodeHandle node, n_tilde; 00095 00096 void gazeboCallback(const sensor_msgs::JointStateConstPtr& msg); 00097 #endif 00098 00102 void initializeMap(); 00103 00105 typedef std::map<std::string, JointControllerData> ControllersMap; 00107 ControllersMap controllers_map; 00108 00114 inline double toRad( double deg ) 00115 { 00116 return deg * 3.14159265 / 180.0; 00117 } 00118 00124 inline double toDegrees( double rad ) 00125 { 00126 return rad * 180.0 / 3.14159265; 00127 } 00128 }; //end class 00129 } 00130 #endif /* !VIRTUAL_SHADOWHAND_H_ */