27 #ifndef _SR_MUSCLE_HAND_LIB_HPP_ 28 #define _SR_MUSCLE_HAND_LIB_HPP_ 31 #include <std_srvs/Empty.h> 42 template<
class StatusType,
class CommandType>
48 std::string device_id, std::string joint_prefix);
61 int muscle_driver_index);
63 #ifdef DEBUG_PUBLISHER 73 bool set_debug_data_to_publish(sr_robot_msgs::SetDebugData::Request& request,
74 sr_robot_msgs::SetDebugData::Response& response);
85 virtual void initialize(std::vector<std::string> joint_names, std::vector<int> actuator_ids,
86 std::vector<shadow_joints::JointToSensor> joint_to_sensors);
95 void initialize(std::vector<std::string> joint_names, std::vector<shadow_joints::JointToMuscle> actuator_ids,
96 std::vector<shadow_joints::JointToSensor> joint_to_sensors);
114 #ifdef DEBUG_PUBLISHER bool reset_muscle_driver_callback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int muscle_driver_index)
static const int32u muscle_data_types[]
static const int nb_muscle_data
virtual void initialize(std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors)
static const char * human_readable_muscle_data_types[]
SrMuscleHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
std::vector< shadow_joints::JointToMuscle > read_joint_to_muscle_mapping()
const std::string response