Go to the documentation of this file.00001
00028 #ifndef _SR_MUSCLE_HAND_LIB_HPP_
00029 #define _SR_MUSCLE_HAND_LIB_HPP_
00030
00031 #include "sr_robot_lib/sr_muscle_robot_lib.hpp"
00032 #include <std_srvs/Empty.h>
00033
00034
00035
00036 #include <ros/ros.h>
00037 #include <string>
00038
00039 namespace shadow_robot
00040 {
00041 template <class StatusType, class CommandType>
00042 class SrMuscleHandLib : public SrMuscleRobotLib<StatusType, CommandType>
00043 {
00044 public:
00045 SrMuscleHandLib(pr2_hardware_interface::HardwareInterface *hw);
00046 ~SrMuscleHandLib();
00047
00048
00058 bool reset_muscle_driver_callback(std_srvs::Empty::Request& request,
00059 std_srvs::Empty::Response& response,
00060 int muscle_driver_index);
00061
00062 #ifdef DEBUG_PUBLISHER
00063
00072 bool set_debug_data_to_publish(sr_robot_msgs::SetDebugData::Request& request,
00073 sr_robot_msgs::SetDebugData::Response& response);
00074 #endif
00075
00076 protected:
00085 virtual void initialize(std::vector<std::string> joint_names, std::vector<int> actuator_ids,
00086 std::vector<shadow_joints::JointToSensor> joint_to_sensors,
00087 std::vector<sr_actuator::SrGenericActuator*> actuators);
00088
00097 void initialize(std::vector<std::string> joint_names, std::vector<shadow_joints::JointToMuscle> actuator_ids,
00098 std::vector<shadow_joints::JointToSensor> joint_to_sensors,
00099 std::vector<sr_actuator::SrGenericActuator*> actuators);
00100
00101 private:
00102
00111 std::vector<shadow_joints::JointToMuscle> read_joint_to_muscle_mapping();
00112
00113
00114 static const int nb_muscle_data;
00115 static const char* human_readable_muscle_data_types[];
00116 static const int32u muscle_data_types[];
00117
00119 ros::ServiceServer debug_service;
00120
00121 };
00122
00123 }
00124
00125
00126
00127
00128
00129
00130
00131 #endif