#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 (hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix) | |
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. | |
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. | |
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 | |
static const double | tactile_timeout = 10.0 |
Timeout handling variables for UBI sensors. | |
Protected Member Functions | |
virtual void | calibrate_joint (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data)=0 |
void | checkSelfTests () |
It is run in a separate thread and calls the checkTests() method of the self_tests_. | |
virtual ros_ethercat_model::Actuator * | get_joint_actuator (std::vector< shadow_joints::Joint >::iterator joint_tmp)=0 |
virtual void | initialize (std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors)=0 |
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) |
Protected Attributes | |
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. | |
std::string | device_id_ |
Id of the ethercat device (alias) | |
std::vector < generic_updater::UpdateConfig > | generic_sensor_update_rate_configs_vector |
std::string | joint_prefix_ |
Prefix used to access the joints. | |
std::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_ |
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 | |
static const char * | human_readable_sensor_data_types [] |
static const int | nb_sensor_data = 37 |
static const int32u | sensor_data_types [] |
Definition at line 98 of file sr_robot_lib.hpp.
shadow_robot::SrRobotLib< StatusType, CommandType >::SrRobotLib | ( | hardware_interface::HardwareInterface * | hw, |
ros::NodeHandle | nh, | ||
ros::NodeHandle | nhtilde, | ||
std::string | device_id, | ||
std::string | joint_prefix | ||
) |
Definition at line 167 of file sr_robot_lib.cpp.
virtual shadow_robot::SrRobotLib< StatusType, CommandType >::~SrRobotLib | ( | ) | [inline, virtual] |
Definition at line 104 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 255 of file sr_robot_lib.cpp.
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::calibrate_joint | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp, |
StatusType * | status_data | ||
) | [protected, pure 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 |
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 >::checkSelfTests | ( | ) | [protected] |
It is run in a separate thread and calls the checkTests() method of the self_tests_.
virtual ros_ethercat_model::Actuator* shadow_robot::SrRobotLib< StatusType, CommandType >::get_joint_actuator | ( | std::vector< shadow_joints::Joint >::iterator | joint_tmp | ) | [protected, pure virtual] |
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. |
Implemented in shadow_robot::SrMotorRobotLib< StatusType, CommandType >, shadow_robot::SrMuscleRobotLib< StatusType, CommandType >, and shadow_robot::SrMotorRobotLib< STATUS_TYPE, COMMAND_TYPE >.
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 | ||
) | [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. |
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 240 of file sr_robot_lib.cpp.
CalibrationMap shadow_robot::SrRobotLib< StatusType, CommandType >::read_joint_calibration | ( | ) | [protected] |
Reads the calibration from the parameter server.
Definition at line 337 of file sr_robot_lib.cpp.
vector< 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 379 of file sr_robot_lib.cpp.
vector< 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 444 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 229 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_init_timer_callback | ( | const ros::TimerEvent & | event | ) | [protected] |
Calback for the timer that controls the timeout for the tactile initialization period
Definition at line 485 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 316 of file sr_robot_lib.cpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::biotac_sensor_update_rate_configs_vector [protected] |
Definition at line 312 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 336 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 266 of file sr_robot_lib.hpp.
std::string shadow_robot::SrRobotLib< StatusType, CommandType >::device_id_ [protected] |
Id of the ethercat device (alias)
Definition at line 286 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::generic_sensor_update_rate_configs_vector [protected] |
Definition at line 308 of file sr_robot_lib.hpp.
const char * shadow_robot::SrRobotLib< StatusType, CommandType >::human_readable_sensor_data_types [static, protected] |
Definition at line 317 of file sr_robot_lib.hpp.
ros_ethercat_model::RobotState* shadow_robot::SrRobotLib< StatusType, CommandType >::hw_ |
Definition at line 190 of file sr_robot_lib.hpp.
std::string shadow_robot::SrRobotLib< StatusType, CommandType >::joint_prefix_ [protected] |
Prefix used to access the joints.
Definition at line 284 of file sr_robot_lib.hpp.
std::vector<shadow_joints::Joint> shadow_robot::SrRobotLib< StatusType, CommandType >::joints_vector [protected] |
The vector containing all the robot joints.
Definition at line 197 of file sr_robot_lib.hpp.
boost::shared_ptr<boost::mutex> shadow_robot::SrRobotLib< StatusType, CommandType >::lock_tactile_init_timeout_ |
A mutual exclusion object to ensure that the intitialization timeout event does work without threading issues.
Definition at line 331 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 178 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 185 of file sr_robot_lib.hpp.
const int shadow_robot::SrRobotLib< StatusType, CommandType >::nb_sensor_data = 37 [static, protected] |
Definition at line 316 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 270 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 281 of file sr_robot_lib.hpp.
bool shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_ [protected] |
Definition at line 194 of file sr_robot_lib.hpp.
ros::ServiceServer shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_server_ [protected] |
Definition at line 273 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::pst3_sensor_update_rate_configs_vector [protected] |
Definition at line 310 of file sr_robot_lib.hpp.
boost::shared_ptr<boost::thread> shadow_robot::SrRobotLib< StatusType, CommandType >::self_test_thread_ [protected] |
Definition at line 278 of file sr_robot_lib.hpp.
const int32u shadow_robot::SrRobotLib< StatusType, CommandType >::sensor_data_types [static, protected] |
Definition at line 318 of file sr_robot_lib.hpp.
ros::Timer shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_check_init_timeout_timer |
Definition at line 328 of file sr_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_current_state |
Definition at line 188 of file sr_robot_lib.hpp.
ros::Duration shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_init_max_duration |
Definition at line 327 of file sr_robot_lib.hpp.
const double shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_timeout = 10.0 [static] |
Timeout handling variables for UBI sensors.
Definition at line 326 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 instantiated during the initialization cycle, depending on the type of sensors attached to the hand.
Definition at line 172 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles_init |
Definition at line 333 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::ubi0_sensor_update_rate_configs_vector [protected] |
Definition at line 314 of file sr_robot_lib.hpp.