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 {
00043   class EtherCATCompatibilityHand : public SRArticulatedRobot
00044   {
00045   public:
00049     ROS_DEPRECATED EtherCATCompatibilityHand();
00051     ~EtherCATCompatibilityHand();
00052 
00053     //virtual classes defined in Shadowhand
00061     virtual short sendupdate( std::string joint_name, double target );
00062 
00069     virtual JointData getJointData( std::string joint_name );
00070     virtual JointsMap getAllJointsData();
00071 
00072     virtual short setContrl( std::string contrlr_name, JointControllerData ctrlr_data );
00073     virtual JointControllerData getContrl( std::string ctrlr_name );
00074 
00075     virtual short setConfig( std::vector<std::string> myConfig );
00076     virtual void getConfig( std::string joint_name );
00077 
00084     virtual std::vector<DiagnosticData> getDiagnostics();
00085   protected:
00086     ros::NodeHandle node, n_tilde;
00087 
00094     void joint_states_callback(const sensor_msgs::JointStateConstPtr& msg);
00095 
00099     void initializeMap();
00100 
00109     std::string findControllerTopicName( std::string joint_name);
00110 
00112     std::vector< ros::Publisher > etherCAT_publishers;
00113 
00115     ros::Subscriber joint_state_subscriber;
00116   }; //end class
00117 }
00118 
00119 /* For the emacs weenies in the crowd.
00120 Local Variables:
00121    c-basic-offset: 2
00122 End:
00123 */
00124 
00125 
00126 #endif      /* !_ETHERCAT_COMPATIBILITY_HAND_HPP_ */


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