#include <sr_muscle_hand_lib.hpp>

Public Member Functions | |
| bool | reset_muscle_driver_callback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int muscle_driver_index) |
| SrMuscleHandLib (hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix) | |
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) |
| void | initialize (std::vector< std::string > joint_names, std::vector< shadow_joints::JointToMuscle > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors) |
Private Member Functions | |
| std::vector < shadow_joints::JointToMuscle > | read_joint_to_muscle_mapping () |
Static Private Attributes | |
| static const char * | human_readable_muscle_data_types [] |
| static const int32u | muscle_data_types [] |
| static const int | nb_muscle_data = 3 |
Definition at line 44 of file sr_muscle_hand_lib.hpp.
| shadow_robot::SrMuscleHandLib< StatusType, CommandType >::SrMuscleHandLib | ( | hardware_interface::HardwareInterface * | hw, |
| ros::NodeHandle | nh, | ||
| ros::NodeHandle | nhtilde, | ||
| std::string | device_id, | ||
| std::string | joint_prefix | ||
| ) |
Definition at line 74 of file sr_muscle_hand_lib.cpp.
| virtual 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 | ||
| ) | [protected, virtual] |
Initializes the hand library with the needed values.
| joint_names | A vector containing all the joint names. |
| actuator_ids | A vector containing the corresponding actuator ids. |
| joint_to_sensors | A vector mapping the joint to the sensor index we read from the palm. |
Implements shadow_robot::SrMuscleRobotLib< StatusType, 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 | ||
| ) | [protected] |
Initializes the hand library with the needed values.
| joint_names | A vector containing all the joint names. |
| actuator_ids | A vector containing the corresponding actuator ids. |
| joint_to_sensors | A vector mapping the joint to the sensor index we read from the palm. |
| vector< 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.
Definition at line 197 of file sr_muscle_hand_lib.cpp.
| 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.
| request | empty |
| response | empty |
| muscle_driver_index | The index of the muscle driver we're resetting |
Definition at line 185 of file sr_muscle_hand_lib.cpp.
const char * shadow_robot::SrMuscleHandLib< StatusType, CommandType >::human_readable_muscle_data_types [static, private] |
{
"muscle_data_pressure",
"muscle_data_can_stats",
"muscle_data_slow_misc"}
Definition at line 112 of file sr_muscle_hand_lib.hpp.
const int32u shadow_robot::SrMuscleHandLib< StatusType, CommandType >::muscle_data_types [static, private] |
Definition at line 113 of file sr_muscle_hand_lib.hpp.
const int shadow_robot::SrMuscleHandLib< StatusType, CommandType >::nb_muscle_data = 3 [static, private] |
Definition at line 111 of file sr_muscle_hand_lib.hpp.