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();
00050     virtual ~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:
00090     ros::NodeHandle node, n_tilde;
00091 
00092 #ifdef GAZEBO
00093 
00099     void gazeboCallback(const sensor_msgs::JointStateConstPtr& msg);
00100 #endif
00101 
00105     void initializeMap();
00106 
00108     typedef std::map<std::string, JointControllerData> ControllersMap;
00110     ControllersMap controllers_map;
00111 
00117     inline double toRad( double deg )
00118     {
00119         return deg * 3.14159265 / 180.0;
00120     }
00121 
00127     inline double toDegrees( double rad )
00128     {
00129         return rad * 180.0 / 3.14159265;
00130     }
00131 }; //end class
00132 }
00133 #endif      /* !VIRTUAL_SHADOWHAND_H_ */


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:08:52