virtual_shadowhand.h
Go to the documentation of this file.
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 {
00043 class VirtualShadowhand : public SRArticulatedRobot
00044 {
00045 public:
00049     VirtualShadowhand();
00051     ~VirtualShadowhand();
00052 
00053     //virtual classes defined in Shadowhand
00064     virtual short sendupdate( std::string joint_name, double target );
00065 
00074     virtual JointData getJointData( std::string joint_name );
00075     virtual JointsMap getAllJointsData();
00076 
00077     virtual short setContrl( std::string contrlr_name, JointControllerData ctrlr_data );
00078     virtual JointControllerData getContrl( std::string ctrlr_name );
00079 
00080     virtual short setConfig( std::vector<std::string> myConfig );
00081     virtual void getConfig( std::string joint_name );
00082 
00088     virtual std::vector<DiagnosticData> getDiagnostics();
00089 protected:
00091     ros::NodeHandle node, n_tilde;
00092 
00093 #ifdef GAZEBO
00094 
00100     void gazeboCallback(const sensor_msgs::JointStateConstPtr& msg);
00101 #endif
00102 
00106     void initializeMap();
00107 
00109     typedef std::map<std::string, JointControllerData> ControllersMap;
00111     ControllersMap controllers_map;
00112 
00118     inline double toRad( double deg )
00119     {
00120         return deg * 3.14159265 / 180.0;
00121     }
00122 
00128     inline double toDegrees( double rad )
00129     {
00130         return rad * 180.0 / 3.14159265;
00131     }
00132 }; //end class
00133 }
00134 #endif      /* !VIRTUAL_SHADOWHAND_H_ */


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Fri Jan 3 2014 12:03:25