CAN_compatibility_arm.hpp
Go to the documentation of this file.
00001 
00031 #ifndef         _CAN_COMPATIBILITY_ARM_HPP_
00032 # define        _CAN_COMPATIBILITY_ARM_HPP_
00033 
00034 #include "sr_hand/hand/sr_articulated_robot.h"
00035 #include <sensor_msgs/JointState.h>
00036 
00037 namespace shadowrobot
00038 {
00044   class CANCompatibilityArm : public SRArticulatedRobot
00045   {
00046   public:
00050     ROS_DEPRECATED CANCompatibilityArm();
00052     ~CANCompatibilityArm();
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 
00103     std::vector< ros::Publisher > CAN_publishers;
00104 
00106     ros::Subscriber joint_state_subscriber;
00107   }; //end class
00108 }
00109 
00110 /* For the emacs weenies in the crowd.
00111 Local Variables:
00112    c-basic-offset: 2
00113 End:
00114 */
00115 
00116 
00117 #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