#include <sr_robot_lib.hpp>
Public Types | |
typedef std::map< std::string, CoupledJoint > | CoupledJointMapType |
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. 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 | |
static const double | tactile_timeout = 10.0 |
Timeout handling variables for UBI sensors. More... | |
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_. More... | |
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 |
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) |
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. 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 | |
static const char * | human_readable_sensor_data_types [] |
static const int | nb_sensor_data = 37 |
static const int32u | sensor_data_types [] |
Definition at line 122 of file sr_robot_lib.hpp.
typedef std::map<std::string, CoupledJoint> shadow_robot::SrRobotLib< StatusType, CommandType >::CoupledJointMapType |
Definition at line 216 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 170 of file sr_robot_lib.cpp.
|
inlinevirtual |
Definition at line 128 of file sr_robot_lib.hpp.
|
pure virtual |
|
pure virtual |
void shadow_robot::SrRobotLib< StatusType, CommandType >::build_tactile_command | ( | CommandType * | command | ) |
Definition at line 271 of file sr_robot_lib.cpp.
|
protectedpure virtual |
|
protected |
It is run in a separate thread and calls the checkTests() method of the self_tests_.
|
protectedpure virtual |
|
protectedpure virtual |
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 | ||
) |
Definition at line 256 of file sr_robot_lib.cpp.
|
protected |
Definition at line 395 of file sr_robot_lib.cpp.
|
protected |
Definition at line 353 of file sr_robot_lib.cpp.
|
protected |
Definition at line 462 of file sr_robot_lib.cpp.
|
protected |
Definition at line 527 of file sr_robot_lib.cpp.
void shadow_robot::SrRobotLib< StatusType, CommandType >::reinitialize_sensors | ( | ) |
Definition at line 245 of file sr_robot_lib.cpp.
|
protected |
Definition at line 568 of file sr_robot_lib.cpp.
|
pure virtual |
void shadow_robot::SrRobotLib< StatusType, CommandType >::update_tactile_info | ( | StatusType * | status | ) |
Definition at line 332 of file sr_robot_lib.cpp.
|
protected |
Definition at line 340 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 364 of file sr_robot_lib.hpp.
|
protected |
A temporary calibration for a given joint.
Definition at line 294 of file sr_robot_lib.hpp.
CoupledJointMapType shadow_robot::SrRobotLib< StatusType, CommandType >::coupled_calibration_map |
Definition at line 365 of file sr_robot_lib.hpp.
|
protected |
Id of the ethercat device (alias)
Definition at line 314 of file sr_robot_lib.hpp.
|
protected |
Definition at line 336 of file sr_robot_lib.hpp.
|
staticprotected |
Definition at line 345 of file sr_robot_lib.hpp.
ros_ethercat_model::RobotState* shadow_robot::SrRobotLib< StatusType, CommandType >::hw_ |
Definition at line 214 of file sr_robot_lib.hpp.
|
protected |
Prefix used to access the joints.
Definition at line 312 of file sr_robot_lib.hpp.
|
protected |
The vector containing all the robot joints.
Definition at line 223 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 359 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib< StatusType, CommandType >::main_pic_idle_time |
Definition at line 202 of file sr_robot_lib.hpp.
int shadow_robot::SrRobotLib< StatusType, CommandType >::main_pic_idle_time_min |
Definition at line 209 of file sr_robot_lib.hpp.
|
staticprotected |
Definition at line 344 of file sr_robot_lib.hpp.
|
protected |
a ROS nodehandle (private naming, only inside the node namespace) to be able to advertise the Force PID service
Definition at line 298 of file sr_robot_lib.hpp.
|
protected |
a ros nodehandle to be able to access resources out of the node namespace
Definition at line 309 of file sr_robot_lib.hpp.
|
protected |
Definition at line 220 of file sr_robot_lib.hpp.
|
protected |
Definition at line 301 of file sr_robot_lib.hpp.
|
protected |
Definition at line 338 of file sr_robot_lib.hpp.
|
protected |
Definition at line 306 of file sr_robot_lib.hpp.
|
staticprotected |
Definition at line 346 of file sr_robot_lib.hpp.
ros::Timer shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_check_init_timeout_timer |
Definition at line 356 of file sr_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_current_state |
Definition at line 212 of file sr_robot_lib.hpp.
ros::Duration shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_init_max_duration |
Definition at line 355 of file sr_robot_lib.hpp.
|
static |
Timeout handling variables for UBI sensors.
Definition at line 354 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles |
Definition at line 196 of file sr_robot_lib.hpp.
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles_init |
Definition at line 361 of file sr_robot_lib.hpp.
|
protected |
Definition at line 342 of file sr_robot_lib.hpp.