#include <sr_muscle_robot_lib.hpp>
Public Member Functions | |
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 Attributes | |
operation_mode::device_update_state::DeviceUpdateState | muscle_current_state |
Protected Member Functions | |
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) |
virtual void | initialize (std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors)=0 |
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 Attributes | |
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. | |
boost::shared_ptr < shadow_robot::JointCalibration > | pressure_calibration_tmp_ |
A temporary calibration for a given joint. | |
std::queue< int16_t, std::list < int16_t > > | reset_muscle_driver_queue |
Static Protected Attributes | |
static const double | timeout = 5.0 |
Definition at line 46 of file sr_muscle_robot_lib.hpp.
shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::SrMuscleRobotLib | ( | hardware_interface::HardwareInterface * | hw, |
ros::NodeHandle | nh, | ||
ros::NodeHandle | nhtilde, | ||
std::string | device_id, | ||
std::string | joint_prefix | ||
) |
Definition at line 69 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::add_diagnostics | ( | std::vector< diagnostic_msgs::DiagnosticStatus > & | vec, |
diagnostic_updater::DiagnosticStatusWrapper & | d | ||
) | [virtual] |
This function adds the diagnostics for the hand to the multi diagnostic status published in sr06.cpp.
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 372 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::build_command | ( | CommandType * | command | ) | [virtual] |
Builds a motor command: either send a torque demand or a configuration demand if one is waiting.
command | The command we're building. |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 204 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::calibrate_joint | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp, |
StatusType * | status_data | ||
) | [protected, virtual] |
Compute the calibrated position for the given joint. This method is called from the update method, each time a new message is received.
joint_tmp | The joint we want to calibrate. |
status_data | The status information that comes from the robot |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 821 of file sr_muscle_robot_lib.cpp.
bool shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::check_muscle_driver_data_received_flags | ( | ) | [inline, protected] |
Definition at line 805 of file sr_muscle_robot_lib.cpp.
sr_actuator::SrMuscleActuator* shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::get_joint_actuator | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp | ) | [inline, protected, virtual] |
Returns a pointer to the actuator for a certain joint.
joint_tmp | The joint we want to get the actuator from. |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 169 of file sr_muscle_robot_lib.hpp.
unsigned int shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::get_muscle_pressure | ( | int | muscle_driver_id, |
int | muscle_id, | ||
StatusType * | status_data | ||
) | [protected] |
Decodes the pressure data for a certain muscle in a certain muscle driver from the status data structure
Definition at line 635 of file sr_muscle_robot_lib.cpp.
vector< pair< string, bool > > shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::humanize_flags | ( | int | flag | ) | [protected] |
Transforms the incoming flag as a human readable vector of strings.
flag | incoming flag. |
Definition at line 907 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::init_timer_callback | ( | const ros::TimerEvent & | event | ) | [protected] |
Callback for the timer that controls the timeout for the muscle initialization period
Definition at line 953 of file sr_muscle_robot_lib.cpp.
virtual void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::initialize | ( | std::vector< std::string > | joint_names, |
std::vector< int > | actuator_ids, | ||
std::vector< shadow_joints::JointToSensor > | joint_to_sensors | ||
) | [protected, pure 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::SrRobotLib< StatusType, CommandType >.
Implemented in shadow_robot::SrMuscleHandLib< StatusType, CommandType >.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::process_position_sensor_data | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp, |
StatusType * | status_data, | ||
double | timestamp | ||
) | [protected] |
Calibrates and filters the position information (and computes velocity) for a give joint. This method is called from the update method, each time a new message is received.
joint_tmp | The joint we process data from. |
status_data | The status information that comes from the robot |
timestamp | Timestamp of the data acquisition time |
Definition at line 888 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::read_additional_muscle_data | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp, |
StatusType * | status_data | ||
) | [protected] |
Read additional data from the latest message and stores it into the joints_vector.
joint_tmp | The joint we want to read the data for. |
status_data | The status information that comes from the robot |
Definition at line 494 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::read_muscle_driver_data | ( | std::vector< shadow_joints::MuscleDriver >::iterator | muscle_driver_tmp, |
StatusType * | status_data | ||
) | [protected] |
Read additional data from the latest message and stores it into the joints_vector.
muscle_driver_tmp | The muscle we want to read the data for. |
status_data | The status information that comes from the robot |
Definition at line 695 of file sr_muscle_robot_lib.cpp.
CalibrationMap shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::read_pressure_calibration | ( | ) | [protected, virtual] |
Reads the calibration from the parameter server.
Definition at line 96 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::reinitialize_motors | ( | ) |
Initiates the process to retrieve the initialization information from the motors
Definition at line 935 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::set_muscle_driver_data_received_flags | ( | unsigned int | msg_type, |
int | muscle_driver_id | ||
) | [inline, protected] |
Definition at line 791 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::set_valve_demand | ( | uint8_t * | muscle_data_byte_to_set, |
int8_t | valve_value, | ||
uint8_t | shifting_index | ||
) | [inline, protected] |
Encodes the required valve value in a 4 bit 2's complement format, and writes it in the most significant or less significant half of the pointed byte (muscle_data_byte_to_set) depending on the value of shifting_index.
muscle_data_byte_to_set | pointer to the byte where we want to write the result |
valve_value | the integer value of the valve demand |
shifting_index | if 0, valve is written on the 4 MSB of muscle_data_byte_to_set, if 1 on the 4 LSB |
Definition at line 340 of file sr_muscle_robot_lib.cpp.
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::update | ( | StatusType * | status_data | ) | [virtual] |
This function is called each time a new etherCAT message is received in the sr06.cpp driver. It updates the joints_vector, updating the different values, computing the calibrated joint positions, etc... It also updates the tactile sensors values.
status_data | the received etherCAT message |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 140 of file sr_muscle_robot_lib.cpp.
ros::Timer shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::check_init_timeout_timer [protected] |
Definition at line 226 of file sr_muscle_robot_lib.hpp.
std::map<unsigned int, unsigned int> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::from_muscle_driver_data_received_flags_ [protected] |
A vector to store information about a certain message from the muscle driver. First in the pair is FROM_MUSCLE_DATA_TYPE second in the pair is a bit mask where the bit in position id_muscle_driver tells if this data has been received from that muscle driver It will only contain those FROM_MUSCLE_DATA_TYPE that are considered as initialization parameters
Definition at line 223 of file sr_muscle_robot_lib.hpp.
ros::Duration shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::init_max_duration [protected] |
Definition at line 228 of file sr_muscle_robot_lib.hpp.
boost::shared_ptr<boost::mutex> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::lock_init_timeout_ [protected] |
Definition at line 231 of file sr_muscle_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_current_state |
Definition at line 85 of file sr_muscle_robot_lib.hpp.
std::vector<shadow_joints::MuscleDriver> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_drivers_vector_ [protected] |
Definition at line 199 of file sr_muscle_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_update_rate_configs_vector [protected] |
Definition at line 215 of file sr_muscle_robot_lib.hpp.
boost::shared_ptr<generic_updater::MuscleUpdater<CommandType> > shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_updater_ [protected] |
The motor updater is used to create a correct command to send to the motor. It's build_command() is called each time the SR06::packCommand() is called.
Definition at line 207 of file sr_muscle_robot_lib.hpp.
shadow_joints::CalibrationMap shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::pressure_calibration_map_ [protected] |
The map used to calibrate each pressure sensor.
Definition at line 109 of file sr_muscle_robot_lib.hpp.
boost::shared_ptr<shadow_robot::JointCalibration> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::pressure_calibration_tmp_ [protected] |
A temporary calibration for a given joint.
Definition at line 111 of file sr_muscle_robot_lib.hpp.
std::queue<int16_t, std::list<int16_t> > shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::reset_muscle_driver_queue [protected] |
Definition at line 211 of file sr_muscle_robot_lib.hpp.
const double shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::timeout = 5.0 [static, protected] |
Definition at line 227 of file sr_muscle_robot_lib.hpp.