etherCAT_compatibility_hand.hpp
Go to the documentation of this file.
00001 
00030 #ifndef         _ETHERCAT_COMPATIBILITY_HAND_HPP_
00031 # define        _ETHERCAT_COMPATIBILITY_HAND_HPP_
00032 
00033 #include "sr_hand/hand/sr_articulated_robot.h"
00034 #include <sensor_msgs/JointState.h>
00035 
00036 namespace shadowrobot
00037 {
00038 // THIS CLASS IS CONSIDERED DEPRECATED AND SHOULD NOT BE USED FOR ANY NEW PACKAGE.
00039 // IT IS NOT MARKED AS DEPRECATED THOUGH, AS IT IS STILL USED IN SOME OLD NODES
00045   class EtherCATCompatibilityHand : public SRArticulatedRobot
00046   {
00047   public:
00051     EtherCATCompatibilityHand();
00052     virtual ~EtherCATCompatibilityHand();
00053 
00054     //virtual classes defined in Shadowhand
00062     virtual short sendupdate( std::string joint_name, double target );
00063 
00070     virtual JointData getJointData( std::string joint_name );
00071     virtual JointsMap getAllJointsData();
00072 
00073     virtual short setContrl( std::string contrlr_name, JointControllerData ctrlr_data );
00074     virtual JointControllerData getContrl( std::string ctrlr_name );
00075 
00076     virtual short setConfig( std::vector<std::string> myConfig );
00077     virtual void getConfig( std::string joint_name );
00078 
00085     virtual std::vector<DiagnosticData> getDiagnostics();
00086   protected:
00087     ros::NodeHandle node, n_tilde;
00088 
00095     void joint_states_callback(const sensor_msgs::JointStateConstPtr& msg);
00096 
00100     void initializeMap();
00101 
00110     std::string findControllerTopicName( std::string joint_name);
00111 
00113     std::vector< ros::Publisher > etherCAT_publishers;
00114 
00116     ros::Subscriber joint_state_subscriber;
00117   }; //end class
00118 }
00119 
00120 /* For the emacs weenies in the crowd.
00121 Local Variables:
00122    c-basic-offset: 2
00123 End:
00124 */
00125 
00126 
00127 #endif      /* !_ETHERCAT_COMPATIBILITY_HAND_HPP_ */


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