Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
shadow_robot::SrRobotLib< StatusType, CommandType > Class Template Referenceabstract

#include <sr_robot_lib.hpp>

Inheritance diagram for shadow_robot::SrRobotLib< StatusType, CommandType >:
Inheritance graph
[legend]

Public Types

typedef std::map< std::string, CoupledJointCoupledJointMapType
 

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::JointToSensorread_joint_to_sensor_mapping ()
 
std::vector< generic_updater::UpdateConfigread_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::UpdateConfigbiotac_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::UpdateConfiggeneric_sensor_update_rate_configs_vector
 
std::string joint_prefix_
 Prefix used to access the joints. More...
 
std::vector< shadow_joints::Jointjoints_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::UpdateConfigpst3_sensor_update_rate_configs_vector
 
boost::shared_ptr< boost::thread > self_test_thread_
 
std::vector< generic_updater::UpdateConfigubi0_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 []
 

Detailed Description

template<class StatusType, class CommandType>
class shadow_robot::SrRobotLib< StatusType, CommandType >

Definition at line 122 of file sr_robot_lib.hpp.

Member Typedef Documentation

◆ CoupledJointMapType

template<class StatusType, class CommandType>
typedef std::map<std::string, CoupledJoint> shadow_robot::SrRobotLib< StatusType, CommandType >::CoupledJointMapType

Definition at line 216 of file sr_robot_lib.hpp.

Constructor & Destructor Documentation

◆ SrRobotLib()

template<class StatusType, class CommandType>
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.

◆ ~SrRobotLib()

template<class StatusType, class CommandType>
virtual shadow_robot::SrRobotLib< StatusType, CommandType >::~SrRobotLib ( )
inlinevirtual

Definition at line 128 of file sr_robot_lib.hpp.

Member Function Documentation

◆ add_diagnostics()

template<class StatusType, class CommandType>
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::add_diagnostics ( std::vector< diagnostic_msgs::DiagnosticStatus > &  vec,
diagnostic_updater::DiagnosticStatusWrapper d 
)
pure virtual

◆ build_command()

template<class StatusType, class CommandType>
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::build_command ( CommandType *  command)
pure virtual

◆ build_tactile_command()

template<class StatusType , class CommandType>
void shadow_robot::SrRobotLib< StatusType, CommandType >::build_tactile_command ( CommandType *  command)

Definition at line 271 of file sr_robot_lib.cpp.

◆ calibrate_joint()

template<class StatusType, class CommandType>
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::calibrate_joint ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data 
)
protectedpure virtual

◆ checkSelfTests()

template<class StatusType, class 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_.

◆ get_joint_actuator()

template<class StatusType, class CommandType>
virtual ros_ethercat_model::Actuator* shadow_robot::SrRobotLib< StatusType, CommandType >::get_joint_actuator ( std::vector< shadow_joints::Joint >::iterator  joint_tmp)
protectedpure virtual

◆ initialize()

template<class StatusType, class CommandType>
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 
)
protectedpure virtual

◆ nullify_demand_callback()

template<class StatusType , class 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.

◆ read_coupled_joint_calibration()

template<class StatusType , class CommandType >
SrRobotLib< StatusType, CommandType >::CoupledJointMapType shadow_robot::SrRobotLib< StatusType, CommandType >::read_coupled_joint_calibration ( )
protected

Definition at line 395 of file sr_robot_lib.cpp.

◆ read_joint_calibration()

template<class StatusType , class CommandType >
CalibrationMap shadow_robot::SrRobotLib< StatusType, CommandType >::read_joint_calibration ( )
protected

Definition at line 353 of file sr_robot_lib.cpp.

◆ read_joint_to_sensor_mapping()

template<class StatusType , class CommandType >
vector< JointToSensor > shadow_robot::SrRobotLib< StatusType, CommandType >::read_joint_to_sensor_mapping ( )
protected

Definition at line 462 of file sr_robot_lib.cpp.

◆ read_update_rate_configs()

template<class StatusType, class CommandType>
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

Definition at line 527 of file sr_robot_lib.cpp.

◆ reinitialize_sensors()

template<class StatusType , class CommandType >
void shadow_robot::SrRobotLib< StatusType, CommandType >::reinitialize_sensors ( )

Definition at line 245 of file sr_robot_lib.cpp.

◆ tactile_init_timer_callback()

template<class StatusType , class CommandType >
void shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_init_timer_callback ( const ros::TimerEvent event)
protected

Definition at line 568 of file sr_robot_lib.cpp.

◆ update()

template<class StatusType, class CommandType>
virtual void shadow_robot::SrRobotLib< StatusType, CommandType >::update ( StatusType *  status_data)
pure virtual

◆ update_tactile_info()

template<class StatusType, class CommandType >
void shadow_robot::SrRobotLib< StatusType, CommandType >::update_tactile_info ( StatusType *  status)

Definition at line 332 of file sr_robot_lib.cpp.

Member Data Documentation

◆ biotac_sensor_update_rate_configs_vector

template<class StatusType, class CommandType>
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::biotac_sensor_update_rate_configs_vector
protected

Definition at line 340 of file sr_robot_lib.hpp.

◆ calibration_map

template<class StatusType, class CommandType>
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.

◆ calibration_tmp

template<class StatusType, class CommandType>
boost::shared_ptr<shadow_robot::JointCalibration> shadow_robot::SrRobotLib< StatusType, CommandType >::calibration_tmp
protected

A temporary calibration for a given joint.

Definition at line 294 of file sr_robot_lib.hpp.

◆ coupled_calibration_map

template<class StatusType, class CommandType>
CoupledJointMapType shadow_robot::SrRobotLib< StatusType, CommandType >::coupled_calibration_map

Definition at line 365 of file sr_robot_lib.hpp.

◆ device_id_

template<class StatusType, class CommandType>
std::string shadow_robot::SrRobotLib< StatusType, CommandType >::device_id_
protected

Id of the ethercat device (alias)

Definition at line 314 of file sr_robot_lib.hpp.

◆ generic_sensor_update_rate_configs_vector

template<class StatusType, class CommandType>
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::generic_sensor_update_rate_configs_vector
protected

Definition at line 336 of file sr_robot_lib.hpp.

◆ human_readable_sensor_data_types

template<class StatusType, class CommandType>
const char * shadow_robot::SrRobotLib< StatusType, CommandType >::human_readable_sensor_data_types
staticprotected

Definition at line 345 of file sr_robot_lib.hpp.

◆ hw_

template<class StatusType, class CommandType>
ros_ethercat_model::RobotState* shadow_robot::SrRobotLib< StatusType, CommandType >::hw_

Definition at line 214 of file sr_robot_lib.hpp.

◆ joint_prefix_

template<class StatusType, class CommandType>
std::string shadow_robot::SrRobotLib< StatusType, CommandType >::joint_prefix_
protected

Prefix used to access the joints.

Definition at line 312 of file sr_robot_lib.hpp.

◆ joints_vector

template<class StatusType, class CommandType>
std::vector<shadow_joints::Joint> shadow_robot::SrRobotLib< StatusType, CommandType >::joints_vector
protected

The vector containing all the robot joints.

Definition at line 223 of file sr_robot_lib.hpp.

◆ lock_tactile_init_timeout_

template<class StatusType, class CommandType>
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.

◆ main_pic_idle_time

template<class StatusType, class CommandType>
int shadow_robot::SrRobotLib< StatusType, CommandType >::main_pic_idle_time

Definition at line 202 of file sr_robot_lib.hpp.

◆ main_pic_idle_time_min

template<class StatusType, class CommandType>
int shadow_robot::SrRobotLib< StatusType, CommandType >::main_pic_idle_time_min

Definition at line 209 of file sr_robot_lib.hpp.

◆ nb_sensor_data

template<class StatusType, class CommandType>
const int shadow_robot::SrRobotLib< StatusType, CommandType >::nb_sensor_data = 37
staticprotected

Definition at line 344 of file sr_robot_lib.hpp.

◆ nh_tilde

template<class StatusType, class CommandType>
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 298 of file sr_robot_lib.hpp.

◆ nodehandle_

template<class StatusType, class CommandType>
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 309 of file sr_robot_lib.hpp.

◆ nullify_demand_

template<class StatusType, class CommandType>
bool shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_
protected

Definition at line 220 of file sr_robot_lib.hpp.

◆ nullify_demand_server_

template<class StatusType, class CommandType>
ros::ServiceServer shadow_robot::SrRobotLib< StatusType, CommandType >::nullify_demand_server_
protected

Definition at line 301 of file sr_robot_lib.hpp.

◆ pst3_sensor_update_rate_configs_vector

template<class StatusType, class CommandType>
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::pst3_sensor_update_rate_configs_vector
protected

Definition at line 338 of file sr_robot_lib.hpp.

◆ self_test_thread_

template<class StatusType, class CommandType>
boost::shared_ptr<boost::thread> shadow_robot::SrRobotLib< StatusType, CommandType >::self_test_thread_
protected

Definition at line 306 of file sr_robot_lib.hpp.

◆ sensor_data_types

template<class StatusType, class CommandType>
const int32u shadow_robot::SrRobotLib< StatusType, CommandType >::sensor_data_types
staticprotected

Definition at line 346 of file sr_robot_lib.hpp.

◆ tactile_check_init_timeout_timer

template<class StatusType, class CommandType>
ros::Timer shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_check_init_timeout_timer

Definition at line 356 of file sr_robot_lib.hpp.

◆ tactile_current_state

template<class StatusType, class CommandType>
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_current_state

Definition at line 212 of file sr_robot_lib.hpp.

◆ tactile_init_max_duration

template<class StatusType, class CommandType>
ros::Duration shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_init_max_duration

Definition at line 355 of file sr_robot_lib.hpp.

◆ tactile_timeout

template<class StatusType, class CommandType>
const double shadow_robot::SrRobotLib< StatusType, CommandType >::tactile_timeout = 10.0
static

Timeout handling variables for UBI sensors.

Definition at line 354 of file sr_robot_lib.hpp.

◆ tactiles

template<class StatusType, class CommandType>
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles

Definition at line 196 of file sr_robot_lib.hpp.

◆ tactiles_init

template<class StatusType, class CommandType>
boost::shared_ptr<tactiles::GenericTactiles<StatusType, CommandType> > shadow_robot::SrRobotLib< StatusType, CommandType >::tactiles_init

Definition at line 361 of file sr_robot_lib.hpp.

◆ ubi0_sensor_update_rate_configs_vector

template<class StatusType, class CommandType>
std::vector<generic_updater::UpdateConfig> shadow_robot::SrRobotLib< StatusType, CommandType >::ubi0_sensor_update_rate_configs_vector
protected

Definition at line 342 of file sr_robot_lib.hpp.


The documentation for this class was generated from the following files:


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Feb 28 2022 23:50:43