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();
00051     virtual ~CANCompatibilityArm();
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 
00102     std::vector< ros::Publisher > CAN_publishers;
00103 
00105     ros::Subscriber joint_state_subscriber;
00106   }; //end class
00107 }
00108 
00109 /* For the emacs weenies in the crowd.
00110 Local Variables:
00111    c-basic-offset: 2
00112 End:
00113 */
00114 
00115 
00116 #endif      /* !_ETHERCAT_COMPATIBILITY_HAND_HPP_ */


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