#include <sr_robot_lib.hpp>
Public Member Functions | |
void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d) |
void | build_motor_command (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *command) |
bool | nullify_demand_callback (sr_robot_msgs::NullifyDemand::Request &request, sr_robot_msgs::NullifyDemand::Response &response) |
void | reinitialize_motors () |
void | reinitialize_sensors () |
SrRobotLib (pr2_hardware_interface::HardwareInterface *hw) | |
void | update (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *status_data) |
~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 | motor_current_state |
Current update state of the motor (initialization, operation..) | |
operation_mode::device_update_state::DeviceUpdateState | tactile_current_state |
Current update state of the sensors (initialization, operation..) | |
boost::shared_ptr < tactiles::GenericTactiles > | tactiles |
boost::shared_ptr < tactiles::GenericTactiles > | tactiles_init |
Protected Types | |
typedef std::pair< int, std::vector < crc_unions::union16 > > | ForceConfig |
Protected Member Functions | |
void | calibrate_joint (boost::ptr_vector< shadow_joints::Joint >::iterator joint_tmp) |
bool | change_control_parameters (int16_t control_type) |
bool | change_control_type_callback_ (sr_robot_msgs::ChangeControlType::Request &request, sr_robot_msgs::ChangeControlType::Response &response) |
void | generate_force_control_config (int motor_index, int max_pwm, int sg_left, int sg_right, int f, int p, int i, int d, int imax, int deadband, int sign) |
std::vector< std::pair < std::string, bool > > | humanize_flags (int flag) |
virtual void | initialize (std::vector< std::string > joint_names, std::vector< int > motor_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors, std::vector< sr_actuator::SrActuator * > actuators)=0 |
bool | motor_system_controls_callback_ (sr_robot_msgs::ChangeMotorSystemControls::Request &request, sr_robot_msgs::ChangeMotorSystemControls::Response &response) |
void | read_additional_data (boost::ptr_vector< shadow_joints::Joint >::iterator joint_tmp) |
Protected Attributes | |
sr_actuator::SrActuator * | actuator |
The current actuator. | |
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. | |
ros::ServiceServer | change_control_type_ |
A service server used to change the control type on the fly. | |
int | config_index |
this index is used to iterate over the config we're sending. | |
sr_robot_msgs::ControlType | control_type_ |
The current type of control (FORCE demand or PWM demand sent to the motors) | |
bool | control_type_changed_flag_ |
int8u | crc_byte |
int8u | crc_i |
int16u | crc_result |
std::vector < generic_updater::UpdateConfig > | generic_sensor_update_rate_configs_vector |
The update rate for each sensor information type. | |
int | index_motor_in_msg |
The index of the motor in the current message (from 0 to 9) | |
boost::ptr_vector < shadow_joints::Joint > | joints_vector |
The vector containing all the robot joints. | |
boost::shared_ptr< boost::mutex > | lock_command_sending_ |
A mutual exclusion object to ensure that no command will be sent to the robot while a change in the control type (PWM or torque) is ongoing. | |
boost::shared_ptr < generic_updater::MotorDataChecker > | motor_data_checker |
int | motor_index_full |
The index of the motor in all the 20 motors. | |
std::queue< std::vector < sr_robot_msgs::MotorSystemControls > , std::list< std::vector < sr_robot_msgs::MotorSystemControls > > > | motor_system_control_flags_ |
The Flag which will be sent to change the motor controls. | |
ros::ServiceServer | motor_system_control_server_ |
A service server used to call the different motor system controls "buttons". | |
std::vector < generic_updater::UpdateConfig > | motor_update_rate_configs_vector |
The update rate for each motor information. | |
boost::shared_ptr < generic_updater::MotorUpdater > | motor_updater_ |
ros::NodeHandle | nh_tilde |
a ROS nodehandle to be able to advertise the Force PID service | |
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. | |
std::queue< ForceConfig, std::list< ForceConfig > > | reconfig_queue |
std::queue< short, std::list < short > > | reset_motors_queue |
contains a queue of motor indexes to reset | |
ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS * | status_data |
The latest etherCAT message received. |
Definition at line 92 of file sr_robot_lib.hpp.
typedef std::pair<int, std::vector<crc_unions::union16> > shadow_robot::SrRobotLib::ForceConfig [protected] |
The ForceConfig type consists of an int representing the motor index for this config followed by a vector of config: the index in the vector of config corresponds to the type of the data, and the value at this index corresponds to the value we want to set.
Definition at line 254 of file sr_robot_lib.hpp.
Initialising service
Definition at line 47 of file sr_robot_lib.cpp.
shadow_robot::SrRobotLib::~SrRobotLib | ( | ) | [inline] |
Definition at line 96 of file sr_robot_lib.hpp.
void shadow_robot::SrRobotLib::add_diagnostics | ( | std::vector< diagnostic_msgs::DiagnosticStatus > & | vec, |
diagnostic_updater::DiagnosticStatusWrapper & | d | ||
) |
This function adds the diagnostics for the hand to the multi diagnostic status published in sr06.cpp.
Definition at line 463 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib::build_motor_command | ( | ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND * | command | ) |
Builds a motor command: either send a torque demand or a configuration demand if one is waiting.
command | The command we're building. |
Definition at line 197 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib::calibrate_joint | ( | boost::ptr_vector< shadow_joints::Joint >::iterator | joint_tmp | ) | [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. |
Definition at line 583 of file sr_robot_lib.cpp.
bool shadow_robot::SrRobotLib::change_control_parameters | ( | int16_t | control_type | ) | [protected] |
Load the necessary parameters in the Parameter Server and calls a service for every controller currently loaded in the controller manager to make it reload (resetGains()) its parameters from the Parameter Server
control_type | The new active control type (PWM or torque) |
Definition at line 1067 of file sr_robot_lib.cpp.
bool shadow_robot::SrRobotLib::change_control_type_callback_ | ( | sr_robot_msgs::ChangeControlType::Request & | request, |
sr_robot_msgs::ChangeControlType::Response & | response | ||
) | [protected] |
The callback to the change_control_type_ service. Updates the current control_type_ with the requested control_type.
request | Requested control_type_ |
response | The new control_type we'll use |
Definition at line 1027 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib::generate_force_control_config | ( | int | motor_index, |
int | max_pwm, | ||
int | sg_left, | ||
int | sg_right, | ||
int | f, | ||
int | p, | ||
int | i, | ||
int | d, | ||
int | imax, | ||
int | deadband, | ||
int | sign | ||
) | [protected] |
Generates a force control config and adds it to the reconfig_queue with its CRC. The config will be sent as soon as possible.
motor_index | The motor index. |
max_pwm | The max pwm the motor will apply |
sg_left | Strain gauge left |
sg_right | Strain gauge right |
f | The feedforward term (directly adds f*error to the output of the PID) |
p | The p value. |
i | the i value. |
d | the d value. |
imax | the imax value. |
deadband | the deadband on the force. |
sign | can be 0 or 1 depending on the way the motor is plugged in. |
Definition at line 933 of file sr_robot_lib.cpp.
std::vector< std::pair< std::string, bool > > shadow_robot::SrRobotLib::humanize_flags | ( | int | flag | ) | [protected] |
Transforms the incoming flag as a human readable vector of strings.
flag | incoming flag. |
Definition at line 910 of file sr_robot_lib.cpp.
virtual void shadow_robot::SrRobotLib::initialize | ( | std::vector< std::string > | joint_names, |
std::vector< int > | motor_ids, | ||
std::vector< shadow_joints::JointToSensor > | joint_to_sensors, | ||
std::vector< sr_actuator::SrActuator * > | actuators | ||
) | [protected, pure virtual] |
Initializes the joints_vector.
joint_names | A vector containing all the joints. |
motor_ids | A vector containing the corresponding motor indexes (-1 if no motor is associated). |
joint_to_sensors | The mapping between the joints and the sensors (e.g. FFJ0 = FFJ1+FFJ2) |
actuators | The actuators. |
Implemented in shadow_robot::SrHandLib.
bool shadow_robot::SrRobotLib::motor_system_controls_callback_ | ( | sr_robot_msgs::ChangeMotorSystemControls::Request & | request, |
sr_robot_msgs::ChangeMotorSystemControls::Response & | response | ||
) | [protected] |
The callback to the control_motor_ service. Sets the correct flags to 1 or 0 for the MOTOR_SYSTEM_CONTROLS, to control the motors (backlash compensation on/off, increase sg tracking, jiggling, write config to EEprom)
request | Contains the different flags the user wants to set |
response | SUCCESS if success, MOTOR_ID_OUT_OF_RANGE if bad motor_id given |
Definition at line 1121 of file sr_robot_lib.cpp.
bool shadow_robot::SrRobotLib::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 1015 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib::read_additional_data | ( | boost::ptr_vector< shadow_joints::Joint >::iterator | joint_tmp | ) | [protected] |
Read additional data from the latest message and stores it into the joints_vector.
joint_tmp | The joint we want to read teh data for. |
Definition at line 644 of file sr_robot_lib.cpp.
Initiates the process to retrieve the initialization information from the motors
Definition at line 999 of file sr_robot_lib.cpp.
Initiates the process to retrieve the initialization information from the sensors
Definition at line 1008 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib::update | ( | ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS * | status_data | ) |
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 |
Definition at line 93 of file sr_robot_lib.cpp.
The current actuator.
Definition at line 266 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib::biotac_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 309 of file sr_robot_lib.hpp.
The map used to calibrate each joint.
Definition at line 149 of file sr_robot_lib.hpp.
boost::shared_ptr<shadow_robot::JointCalibration> shadow_robot::SrRobotLib::calibration_tmp [protected] |
A temporary calibration for a given joint.
Definition at line 270 of file sr_robot_lib.hpp.
A service server used to change the control type on the fly.
Definition at line 330 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib::config_index [protected] |
this index is used to iterate over the config we're sending.
Definition at line 260 of file sr_robot_lib.hpp.
The current type of control (FORCE demand or PWM demand sent to the motors)
Definition at line 319 of file sr_robot_lib.hpp.
Flag to signal that there has been a change in the value of control_type_ and certain actions are required. The flag is set in the callback function of the change_control_type_ service. The flag is checked in build_motor_command() and the necessary actions are taken there. These actions involve calling services in the controller manager and all the active controllers. This is the reason why we don't do it directly in the callback function. As we use a single thread to serve the callbacks, doing so would cause a deadlock, thus we do it in the realtime loop thread instead.
Definition at line 328 of file sr_robot_lib.hpp.
int8u shadow_robot::SrRobotLib::crc_byte [protected] |
Definition at line 277 of file sr_robot_lib.hpp.
int8u shadow_robot::SrRobotLib::crc_i [protected] |
Definition at line 279 of file sr_robot_lib.hpp.
int16u shadow_robot::SrRobotLib::crc_result [protected] |
Definition at line 278 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib::generic_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 305 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib::index_motor_in_msg [protected] |
The index of the motor in the current message (from 0 to 9)
Definition at line 275 of file sr_robot_lib.hpp.
boost::ptr_vector<shadow_joints::Joint> shadow_robot::SrRobotLib::joints_vector [protected] |
The vector containing all the robot joints.
Definition at line 180 of file sr_robot_lib.hpp.
boost::shared_ptr<boost::mutex> shadow_robot::SrRobotLib::lock_command_sending_ [protected] |
A mutual exclusion object to ensure that no command will be sent to the robot while a change in the control type (PWM or torque) is ongoing.
Definition at line 332 of file sr_robot_lib.hpp.
Contains the idle time of the PIC communicating via etherCAT with the host.
Definition at line 163 of file sr_robot_lib.hpp.
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 170 of file sr_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrRobotLib::motor_current_state |
Current update state of the motor (initialization, operation..)
Definition at line 173 of file sr_robot_lib.hpp.
boost::shared_ptr<generic_updater::MotorDataChecker> shadow_robot::SrRobotLib::motor_data_checker [protected] |
Definition at line 311 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib::motor_index_full [protected] |
The index of the motor in all the 20 motors.
Definition at line 273 of file sr_robot_lib.hpp.
std::queue<std::vector<sr_robot_msgs::MotorSystemControls>, std::list<std::vector<sr_robot_msgs::MotorSystemControls> > > shadow_robot::SrRobotLib::motor_system_control_flags_ [protected] |
The Flag which will be sent to change the motor controls.
Definition at line 358 of file sr_robot_lib.hpp.
A service server used to call the different motor system controls "buttons".
Definition at line 360 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib::motor_update_rate_configs_vector [protected] |
The update rate for each motor information.
Definition at line 303 of file sr_robot_lib.hpp.
boost::shared_ptr<generic_updater::MotorUpdater> shadow_robot::SrRobotLib::motor_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 246 of file sr_robot_lib.hpp.
ros::NodeHandle shadow_robot::SrRobotLib::nh_tilde [protected] |
a ROS nodehandle to be able to advertise the Force PID service
Definition at line 282 of file sr_robot_lib.hpp.
bool shadow_robot::SrRobotLib::nullify_demand_ [protected] |
True if we want to set the demand to 0 (stop the controllers)
Definition at line 314 of file sr_robot_lib.hpp.
The ROS service handler for nullifying the demand.
Definition at line 316 of file sr_robot_lib.hpp.
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib::pst3_sensor_update_rate_configs_vector [protected] |
The update rate for each sensor information type.
Definition at line 307 of file sr_robot_lib.hpp.
std::queue<ForceConfig, std::list<ForceConfig> > shadow_robot::SrRobotLib::reconfig_queue [protected] |
This queue contains the force PID config waiting to be pushed to the motor.
Definition at line 258 of file sr_robot_lib.hpp.
std::queue<short, std::list<short> > shadow_robot::SrRobotLib::reset_motors_queue [protected] |
contains a queue of motor indexes to reset
Definition at line 263 of file sr_robot_lib.hpp.
ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS* shadow_robot::SrRobotLib::status_data [protected] |
The latest etherCAT message received.
Definition at line 268 of file sr_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrRobotLib::tactile_current_state |
Current update state of the sensors (initialization, operation..)
Definition at line 176 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles> shadow_robot::SrRobotLib::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 156 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles> shadow_robot::SrRobotLib::tactiles_init |
Definition at line 157 of file sr_robot_lib.hpp.