Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
shadow_robot::SrMuscleHandLib< StatusType, CommandType > Class Template Reference

#include <sr_muscle_hand_lib.hpp>

Inheritance diagram for shadow_robot::SrMuscleHandLib< StatusType, CommandType >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool reset_muscle_driver_callback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int muscle_driver_index)
 SrMuscleHandLib (pr2_hardware_interface::HardwareInterface *hw)
 ~SrMuscleHandLib ()

Protected Member Functions

virtual void initialize (std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors, std::vector< sr_actuator::SrGenericActuator * > actuators)
void initialize (std::vector< std::string > joint_names, std::vector< shadow_joints::JointToMuscle > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors, std::vector< sr_actuator::SrGenericActuator * > actuators)

Private Member Functions

std::vector
< shadow_joints::JointToMuscle
read_joint_to_muscle_mapping ()

Private Attributes

ros::ServiceServer debug_service
 a service server for reconfiguring the debug data we want to publish

Static Private Attributes

static const char * human_readable_muscle_data_types []
static const int32u muscle_data_types []
static const int nb_muscle_data = 3

Detailed Description

template<class StatusType, class CommandType>
class shadow_robot::SrMuscleHandLib< StatusType, CommandType >

Definition at line 42 of file sr_muscle_hand_lib.hpp.


Constructor & Destructor Documentation

template<class StatusType , class CommandType >
shadow_robot::SrMuscleHandLib< StatusType, CommandType >::SrMuscleHandLib ( pr2_hardware_interface::HardwareInterface hw)

Definition at line 54 of file sr_muscle_hand_lib.cpp.

template<class StatusType , class CommandType >
shadow_robot::SrMuscleHandLib< StatusType, CommandType >::~SrMuscleHandLib ( )

Definition at line 123 of file sr_muscle_hand_lib.cpp.


Member Function Documentation

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleHandLib< StatusType, CommandType >::initialize ( std::vector< std::string >  joint_names,
std::vector< int >  actuator_ids,
std::vector< shadow_joints::JointToSensor joint_to_sensors,
std::vector< sr_actuator::SrGenericActuator * >  actuators 
) [protected, virtual]

Initializes the hand library with the needed values.

Parameters:
joint_namesA vector containing all the joint names.
actuator_idsA vector containing the corresponding actuator ids.
joint_to_sensorsA vector mapping the joint to the sensor index we read from the palm.
actuatorsA vector containing the actuators for the different joints.

Implements shadow_robot::SrMuscleRobotLib< StatusType, CommandType >.

Definition at line 133 of file sr_muscle_hand_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleHandLib< StatusType, CommandType >::initialize ( std::vector< std::string >  joint_names,
std::vector< shadow_joints::JointToMuscle actuator_ids,
std::vector< shadow_joints::JointToSensor joint_to_sensors,
std::vector< sr_actuator::SrGenericActuator * >  actuators 
) [protected]

Initializes the hand library with the needed values.

Parameters:
joint_namesA vector containing all the joint names.
actuator_idsA vector containing the corresponding actuator ids.
joint_to_sensorsA vector mapping the joint to the sensor index we read from the palm.
actuatorsA vector containing the actuators for the different joints.

Definition at line 142 of file sr_muscle_hand_lib.cpp.

template<class StatusType , class CommandType >
std::vector< shadow_joints::JointToMuscle > shadow_robot::SrMuscleHandLib< StatusType, CommandType >::read_joint_to_muscle_mapping ( ) [private]

Reads the mapping associating a joint to a muscle. If the muscle index is -1, then no muscle is associated to this joint.

Returns:
a vector of JointToMuscle structures (containing the indexes of the muscles for the joint), ordered by joint.

Definition at line 188 of file sr_muscle_hand_lib.cpp.

template<class StatusType , class CommandType >
bool shadow_robot::SrMuscleHandLib< StatusType, CommandType >::reset_muscle_driver_callback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response,
int  muscle_driver_index 
)

Reset the muscle driver at motor index.

Parameters:
requestempty
responseempty
muscle_driver_indexThe index of the muscle driver we're resetting
Returns:
true if success

Definition at line 175 of file sr_muscle_hand_lib.cpp.


Member Data Documentation

template<class StatusType , class CommandType >
ros::ServiceServer shadow_robot::SrMuscleHandLib< StatusType, CommandType >::debug_service [private]

a service server for reconfiguring the debug data we want to publish

Definition at line 119 of file sr_muscle_hand_lib.hpp.

template<class StatusType , class CommandType >
const char * shadow_robot::SrMuscleHandLib< StatusType, CommandType >::human_readable_muscle_data_types [static, private]
Initial value:
 {"muscle_data_pressure",
                                                                                                            "muscle_data_can_stats",
                                                                                                            "muscle_data_slow_misc"}

Definition at line 115 of file sr_muscle_hand_lib.hpp.

template<class StatusType , class CommandType >
const int32u shadow_robot::SrMuscleHandLib< StatusType, CommandType >::muscle_data_types [static, private]
Initial value:
 {MUSCLE_DATA_PRESSURE,
                                                                                            MUSCLE_DATA_CAN_STATS,
                                                                                            MUSCLE_DATA_SLOW_MISC}

Definition at line 116 of file sr_muscle_hand_lib.hpp.

template<class StatusType , class CommandType >
const int shadow_robot::SrMuscleHandLib< StatusType, CommandType >::nb_muscle_data = 3 [static, private]

Definition at line 114 of file sr_muscle_hand_lib.hpp.


The documentation for this class was generated from the following files:


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Thu Aug 27 2015 15:16:37