#include <sr_robot_lib.hpp>
Public Member Functions | |
virtual void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)=0 |
virtual void | build_command (CommandType *command)=0 |
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 (pr2_hardware_interface::HardwareInterface *hw) | |
virtual void | update (StatusType *status_data)=0 |
void | update_tactile_info (StatusType *status) |
virtual | ~SrRobotLib () |
Public Attributes | |
shadow_joints::CalibrationMap | calibration_map |
The map used to calibrate each joint. | |
int | main_pic_idle_time |
int | main_pic_idle_time_min |
operation_mode::device_update_state::DeviceUpdateState | tactile_current_state |
Current update state of the sensors (initialization, operation..) | |
boost::shared_ptr < tactiles::GenericTactiles < StatusType, CommandType > > | tactiles |
boost::shared_ptr < tactiles::GenericTactiles < StatusType, CommandType > > | tactiles_init |
Protected Member Functions | |
void | calibrate_joint (boost::ptr_vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data) |
void | checkSelfTests () |
It is run in a separate thread and calls the checkTests() method of the self_tests_. This avoids the tests blocking the main thread. | |
sr_actuator::SrActuatorState * | get_joint_actuator_state (boost::ptr_vector< shadow_joints::Joint >::iterator joint_tmp) |
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)=0 |
void | process_position_sensor_data (boost::ptr_vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data, double timestamp) |
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[]) |
Protected Attributes | |
std::vector < generic_updater::UpdateConfig > | biotac_sensor_update_rate_configs_vector |
The update rate for each sensor information type. | |
boost::shared_ptr < shadow_robot::JointCalibration > | calibration_tmp |
A temporary calibration for a given joint. | |
std::vector < generic_updater::UpdateConfig > | generic_sensor_update_rate_configs_vector |
The update rate for each sensor information type. | |
boost::ptr_vector < shadow_joints::Joint > | joints_vector |
The vector containing all the robot joints. | |
ros::NodeHandle | nh_tilde |
a ROS nodehandle (private naming, only inside the node namespace) to be able to advertise the Force PID service | |
ros::NodeHandle | nodehandle_ |
a ros nodehandle to be able to access resources out of the node namespace | |
bool | nullify_demand_ |
True if we want to set the demand to 0 (stop the controllers) | |
ros::ServiceServer | nullify_demand_server_ |
The ROS service handler for nullifying the demand. | |
std::vector < generic_updater::UpdateConfig > | pst3_sensor_update_rate_configs_vector |
The update rate for each sensor information type. | |
boost::shared_ptr< boost::thread > | self_test_thread_ |
Thread for running the tests in parallel when doing the tests on real hand. | |
boost::shared_ptr< SrSelfTest > | self_tests_ |
std::vector < generic_updater::UpdateConfig > | ubi0_sensor_update_rate_configs_vector |
The update rate for each sensor information type. | |
Static Protected Attributes | |
static const char * | human_readable_sensor_data_types [] |
static const int | nb_sensor_data = 32 |
static const int32u | sensor_data_types [] |
Definition at line 90 of file sr_robot_lib.hpp.
shadow_robot::SrRobotLib< StatusType, CommandType >::SrRobotLib | ( | pr2_hardware_interface::HardwareInterface * | hw | ) |
Definition at line 127 of file sr_robot_lib.cpp.
virtual shadow_robot::SrRobotLib< StatusType, CommandType >::~SrRobotLib | ( | ) | [inline, virtual] |
Definition at line 94 of file sr_robot_lib.hpp.
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::add_diagnostics | ( | std::vector< diagnostic_msgs::DiagnosticStatus > & | vec, |
diagnostic_updater::DiagnosticStatusWrapper & | d | ||
) | [pure virtual] |
This function adds the diagnostics for the hand to the multi diagnostic status published in sr06.cpp.
Implemented in shadow_robot::SrMotorRobotLib< StatusType, CommandType >, shadow_robot::SrMotorRobotLib< STATUS_TYPE, COMMAND_TYPE >, and shadow_robot::SrMuscleRobotLib< StatusType, CommandType >.
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::build_command | ( | CommandType * | command | ) | [pure virtual] |
Builds a command for the robot.
command | The command we're building. |
Implemented in shadow_robot::SrMotorRobotLib< StatusType, CommandType >, shadow_robot::SrMotorRobotLib< STATUS_TYPE, COMMAND_TYPE >, and shadow_robot::SrMuscleRobotLib< StatusType, CommandType >.
void shadow_robot::SrRobotLib< StatusType, CommandType >::build_tactile_command | ( | CommandType * | command | ) |
Builds a command to demand information form the tactile sensors.
command | The command we're building. |
Definition at line 283 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib< StatusType, CommandType >::calibrate_joint | ( | boost::ptr_vector< shadow_joints::Joint >::iterator | joint_tmp, |
StatusType * | status_data | ||
) | [protected] |
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 |
Definition at line 156 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib< StatusType, CommandType >::checkSelfTests | ( | ) | [protected] |
It is run in a separate thread and calls the checkTests() method of the self_tests_. This avoids the tests blocking the main thread.
Definition at line 483 of file sr_robot_lib.cpp.
sr_actuator::SrActuatorState * shadow_robot::SrRobotLib< StatusType, CommandType >::get_joint_actuator_state | ( | boost::ptr_vector< shadow_joints::Joint >::iterator | joint_tmp | ) | [protected] |
Returns a pointer to the actuator state for a certain joint. It checks the actuator type before accessing the state_ field, to avoid accessing the base class state_ field which is not what we want
joint_tmp | The joint we want to get the actuator state from. |
Definition at line 261 of file sr_robot_lib.cpp.
virtual void shadow_robot::SrRobotLib< 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, 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. |
actuators | A vector containing the actuators for the different joints. |
Implemented in shadow_robot::SrMotorHandLib< StatusType, CommandType >, shadow_robot::SrMotorHandLib< STATUS_TYPE, COMMAND_TYPE >, shadow_robot::SrMotorRobotLib< StatusType, CommandType >, shadow_robot::SrMotorRobotLib< STATUS_TYPE, COMMAND_TYPE >, shadow_robot::SrMuscleRobotLib< StatusType, CommandType >, and shadow_robot::SrMuscleHandLib< StatusType, CommandType >.
bool shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_callback | ( | sr_robot_msgs::NullifyDemand::Request & | request, |
sr_robot_msgs::NullifyDemand::Response & | response | ||
) |
This service is used to nullify the demand of the etherCAT hand. If the nullify_demand parameter is set to True, the demand sent to the robot will be 0, regardless of the computed effort demanded by the controller. If set to False, then the demand computed by the controllers will be sent to the motors.
request | contains the nullify_demand parameter |
response | empty |
Definition at line 228 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib< StatusType, CommandType >::process_position_sensor_data | ( | boost::ptr_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 241 of file sr_robot_lib.cpp.
shadow_joints::CalibrationMap shadow_robot::SrRobotLib< StatusType, CommandType >::read_joint_calibration | ( | ) | [protected] |
Reads the calibration from the parameter server.
Definition at line 348 of file sr_robot_lib.cpp.
std::vector< shadow_joints::JointToSensor > shadow_robot::SrRobotLib< StatusType, CommandType >::read_joint_to_sensor_mapping | ( | ) | [protected] |
Reads the mapping between the sensors and the joints from the parameter server.
Definition at line 390 of file sr_robot_lib.cpp.
std::vector< generic_updater::UpdateConfig > shadow_robot::SrRobotLib< StatusType, CommandType >::read_update_rate_configs | ( | std::string | base_param, |
int | nb_data_defined, | ||
const char * | human_readable_data_types[], | ||
const int32u | data_types[] | ||
) | [protected] |
Simply reads the config from the parameter server.
base_param | string with the base name of the set of parameters to apply (found in the yaml file) |
nb_data_defined | number of data defined in the typedef |
human_readable_data_types | names of the types of messages (must match with those in the yaml file) |
data_types | the command values corresponding to every one of the names |
Definition at line 447 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib< StatusType, CommandType >::reinitialize_sensors | ( | ) |
Initiates the process to retrieve the initialization information from the sensors
Definition at line 220 of file sr_robot_lib.cpp.
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::update | ( | StatusType * | status_data | ) | [pure 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 |
Implemented in shadow_robot::SrMotorRobotLib< StatusType, CommandType >, shadow_robot::SrMotorRobotLib< STATUS_TYPE, COMMAND_TYPE >, and shadow_robot::SrMuscleRobotLib< StatusType, CommandType >.
void shadow_robot::SrRobotLib< StatusType, CommandType >::update_tactile_info | ( | StatusType * | status | ) |
Reads the tactile information.
status | The status information that comes from the robot |
Definition at line 333 of file sr_robot_lib.cpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::biotac_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 292 of file sr_robot_lib.hpp.
shadow_joints::CalibrationMap shadow_robot::SrRobotLib< StatusType, CommandType >::calibration_map |
The map used to calibrate each joint.
Definition at line 155 of file sr_robot_lib.hpp.
boost::shared_ptr<shadow_robot::JointCalibration> shadow_robot::SrRobotLib< StatusType, CommandType >::calibration_tmp [protected] |
A temporary calibration for a given joint.
Definition at line 259 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::generic_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 288 of file sr_robot_lib.hpp.
const char * shadow_robot::SrRobotLib< StatusType, CommandType >::human_readable_sensor_data_types [static, protected] |
Definition at line 298 of file sr_robot_lib.hpp.
boost::ptr_vector<shadow_joints::Joint> shadow_robot::SrRobotLib< StatusType, CommandType >::joints_vector [protected] |
The vector containing all the robot joints.
Definition at line 183 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib< StatusType, CommandType >::main_pic_idle_time |
Contains the idle time of the PIC communicating via etherCAT with the host.
Definition at line 169 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib< StatusType, CommandType >::main_pic_idle_time_min |
Contains the minimum idle time of the PIC communicating via etherCAT with the host, this minimum is reset each time a diagnostic is being published.
Definition at line 176 of file sr_robot_lib.hpp.
const int shadow_robot::SrRobotLib< StatusType, CommandType >::nb_sensor_data = 32 [static, protected] |
Definition at line 297 of file sr_robot_lib.hpp.
ros::NodeHandle shadow_robot::SrRobotLib< StatusType, CommandType >::nh_tilde [protected] |
a ROS nodehandle (private naming, only inside the node namespace) to be able to advertise the Force PID service
Definition at line 263 of file sr_robot_lib.hpp.
ros::NodeHandle shadow_robot::SrRobotLib< StatusType, CommandType >::nodehandle_ [protected] |
a ros nodehandle to be able to access resources out of the node namespace
Definition at line 266 of file sr_robot_lib.hpp.
bool shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_ [protected] |
True if we want to set the demand to 0 (stop the controllers)
Definition at line 303 of file sr_robot_lib.hpp.
ros::ServiceServer shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_server_ [protected] |
The ROS service handler for nullifying the demand.
Definition at line 305 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::pst3_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 290 of file sr_robot_lib.hpp.
boost::shared_ptr<boost::thread> shadow_robot::SrRobotLib< StatusType, CommandType >::self_test_thread_ [protected] |
Thread for running the tests in parallel when doing the tests on real hand.
Definition at line 313 of file sr_robot_lib.hpp.
boost::shared_ptr<SrSelfTest> shadow_robot::SrRobotLib< StatusType, CommandType >::self_tests_ [protected] |
Definition at line 310 of file sr_robot_lib.hpp.
const int32u shadow_robot::SrRobotLib< StatusType, CommandType >::sensor_data_types [static, protected] |
Definition at line 299 of file sr_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_current_state |
Current update state of the sensors (initialization, operation..)
Definition at line 179 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles |
This is a pointer to the tactile object. This pointer will be instanciated during the initialization cycle, depending on the type of sensors attached to the hand.
Definition at line 162 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles_init |
Definition at line 163 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::ubi0_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 294 of file sr_robot_lib.hpp.