|  | 
| 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) | 
|  | 
|  Public Member Functions inherited from shadow_robot::SrMuscleRobotLib< StatusType, CommandType > | 
| void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d) | 
|  | 
| void | build_command (CommandType *command) | 
|  | 
| void | reinitialize_motors () | 
|  | 
|  | SrMuscleRobotLib (hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix) | 
|  | 
| void | update (StatusType *status_data) | 
|  | 
|  Public Member Functions inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| void | build_tactile_command (CommandType *command) | 
|  | 
| bool | nullify_demand_callback (sr_robot_msgs::NullifyDemand::Request &request, sr_robot_msgs::NullifyDemand::Response &response) | 
|  | 
| void | reinitialize_sensors () | 
|  | 
|  | SrRobotLib (hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix) | 
|  | 
| void | update_tactile_info (StatusType *status) | 
|  | 
| virtual | ~SrRobotLib () | 
|  | 
|  | 
| 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) | 
|  | 
|  Protected Member Functions inherited from shadow_robot::SrMuscleRobotLib< StatusType, CommandType > | 
| void | calibrate_joint (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data) | 
|  | 
| bool | check_muscle_driver_data_received_flags () | 
|  | 
| sr_actuator::SrMuscleActuator * | get_joint_actuator (std::vector< shadow_joints::Joint >::iterator joint_tmp) | 
|  | 
| unsigned int | get_muscle_pressure (int muscle_driver_id, int muscle_id, StatusType *status_data) | 
|  | 
| std::vector< std::pair< std::string, bool > > | humanize_flags (int flag) | 
|  | 
| void | init_timer_callback (const ros::TimerEvent &event) | 
|  | 
| void | process_position_sensor_data (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data, double timestamp) | 
|  | 
| void | read_additional_muscle_data (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data) | 
|  | 
| void | read_muscle_driver_data (std::vector< shadow_joints::MuscleDriver >::iterator muscle_driver_tmp, StatusType *status_data) | 
|  | 
| virtual shadow_joints::CalibrationMap | read_pressure_calibration () | 
|  | 
| void | set_muscle_driver_data_received_flags (unsigned int msg_type, int muscle_driver_id) | 
|  | 
| void | set_valve_demand (uint8_t *muscle_data_byte_to_set, int8_t valve_value, uint8_t shifting_index) | 
|  | 
|  Protected Member Functions inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| void | checkSelfTests () | 
|  | It is run in a separate thread and calls the checkTests() method of the self_tests_.  More... 
 | 
|  | 
| CoupledJointMapType | read_coupled_joint_calibration () | 
|  | 
| shadow_joints::CalibrationMap | read_joint_calibration () | 
|  | 
| std::vector< shadow_joints::JointToSensor > | read_joint_to_sensor_mapping () | 
|  | 
| std::vector< generic_updater::UpdateConfig > | read_update_rate_configs (std::string base_param, int nb_data_defined, const char *human_readable_data_types[], const int32u data_types[]) | 
|  | 
| void | tactile_init_timer_callback (const ros::TimerEvent &event) | 
|  | 
|  | 
|  Public Types inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| typedef std::map< std::string, CoupledJoint > | CoupledJointMapType | 
|  | 
|  Public Attributes inherited from shadow_robot::SrMuscleRobotLib< StatusType, CommandType > | 
| operation_mode::device_update_state::DeviceUpdateState | muscle_current_state | 
|  | 
|  Public Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| shadow_joints::CalibrationMap | calibration_map | 
|  | The map used to calibrate each joint.  More... 
 | 
|  | 
| CoupledJointMapType | coupled_calibration_map | 
|  | 
| ros_ethercat_model::RobotState * | hw_ | 
|  | 
| boost::shared_ptr< boost::mutex > | lock_tactile_init_timeout_ | 
|  | A mutual exclusion object to ensure that the intitialization timeout event does work without threading issues.  More... 
 | 
|  | 
| int | main_pic_idle_time | 
|  | 
| int | main_pic_idle_time_min | 
|  | 
| ros::Timer | tactile_check_init_timeout_timer | 
|  | 
| operation_mode::device_update_state::DeviceUpdateState | tactile_current_state | 
|  | 
| ros::Duration | tactile_init_max_duration | 
|  | 
| boost::shared_ptr< tactiles::GenericTactiles< StatusType, CommandType > > | tactiles | 
|  | 
| boost::shared_ptr< tactiles::GenericTactiles< StatusType, CommandType > > | tactiles_init | 
|  | 
|  Static Public Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| static const double | tactile_timeout = 10.0 | 
|  | Timeout handling variables for UBI sensors.  More... 
 | 
|  | 
|  Protected Attributes inherited from shadow_robot::SrMuscleRobotLib< StatusType, CommandType > | 
| ros::Timer | check_init_timeout_timer | 
|  | 
| std::map< unsigned int, unsigned int > | from_muscle_driver_data_received_flags_ | 
|  | 
| ros::Duration | init_max_duration | 
|  | 
| boost::shared_ptr< boost::mutex > | lock_init_timeout_ | 
|  | 
| std::vector< shadow_joints::MuscleDriver > | muscle_drivers_vector_ | 
|  | 
| std::vector< generic_updater::UpdateConfig > | muscle_update_rate_configs_vector | 
|  | 
| boost::shared_ptr< generic_updater::MuscleUpdater< CommandType > > | muscle_updater_ | 
|  | 
| shadow_joints::CalibrationMap | pressure_calibration_map_ | 
|  | The map used to calibrate each pressure sensor.  More... 
 | 
|  | 
| boost::shared_ptr< shadow_robot::JointCalibration > | pressure_calibration_tmp_ | 
|  | A temporary calibration for a given joint.  More... 
 | 
|  | 
| std::queue< int16_t, std::list< int16_t > > | reset_muscle_driver_queue | 
|  | 
|  Protected Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| std::vector< generic_updater::UpdateConfig > | biotac_sensor_update_rate_configs_vector | 
|  | 
| boost::shared_ptr< shadow_robot::JointCalibration > | calibration_tmp | 
|  | A temporary calibration for a given joint.  More... 
 | 
|  | 
| std::string | device_id_ | 
|  | Id of the ethercat device (alias)  More... 
 | 
|  | 
| std::vector< generic_updater::UpdateConfig > | generic_sensor_update_rate_configs_vector | 
|  | 
| std::string | joint_prefix_ | 
|  | Prefix used to access the joints.  More... 
 | 
|  | 
| std::vector< shadow_joints::Joint > | joints_vector | 
|  | The vector containing all the robot joints.  More... 
 | 
|  | 
| ros::NodeHandle | nh_tilde | 
|  | a ROS nodehandle (private naming, only inside the node namespace) to be able to advertise the Force PID service  More... 
 | 
|  | 
| ros::NodeHandle | nodehandle_ | 
|  | a ros nodehandle to be able to access resources out of the node namespace  More... 
 | 
|  | 
| bool | nullify_demand_ | 
|  | 
| ros::ServiceServer | nullify_demand_server_ | 
|  | 
| std::vector< generic_updater::UpdateConfig > | pst3_sensor_update_rate_configs_vector | 
|  | 
| boost::shared_ptr< boost::thread > | self_test_thread_ | 
|  | 
| std::vector< generic_updater::UpdateConfig > | ubi0_sensor_update_rate_configs_vector | 
|  | 
|  Static Protected Attributes inherited from shadow_robot::SrMuscleRobotLib< StatusType, CommandType > | 
| static const double | timeout = 5.0 | 
|  | 
|  Static Protected Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | 
| static const char * | human_readable_sensor_data_types [] | 
|  | 
| static const int | nb_sensor_data = 37 | 
|  | 
| static const int32u | sensor_data_types [] | 
|  | 
template<class StatusType, class CommandType>
class shadow_robot::SrMuscleHandLib< StatusType, CommandType >
Definition at line 43 of file sr_muscle_hand_lib.hpp.