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

#include <sr_muscle_robot_lib.hpp>

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

Public Member Functions

void add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
 
void build_command (CommandType *command)
 
void reinitialize_motors ()
 
 SrMuscleRobotLib (hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
 
void update (StatusType *status_data)
 
- Public Member Functions inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
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)
 
void update_tactile_info (StatusType *status)
 
virtual ~SrRobotLib ()
 

Public Attributes

operation_mode::device_update_state::DeviceUpdateState muscle_current_state
 
- Public Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
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
 

Protected Member Functions

void calibrate_joint (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data)
 
bool check_muscle_driver_data_received_flags ()
 
sr_actuator::SrMuscleActuator * get_joint_actuator (std::vector< shadow_joints::Joint >::iterator joint_tmp)
 
unsigned int get_muscle_pressure (int muscle_driver_id, int muscle_id, StatusType *status_data)
 
std::vector< std::pair< std::string, bool > > humanize_flags (int flag)
 
void init_timer_callback (const ros::TimerEvent &event)
 
virtual void initialize (std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors)=0
 
void process_position_sensor_data (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data, double timestamp)
 
void read_additional_muscle_data (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data)
 
void read_muscle_driver_data (std::vector< shadow_joints::MuscleDriver >::iterator muscle_driver_tmp, StatusType *status_data)
 
virtual shadow_joints::CalibrationMap read_pressure_calibration ()
 
void set_muscle_driver_data_received_flags (unsigned int msg_type, int muscle_driver_id)
 
void set_valve_demand (uint8_t *muscle_data_byte_to_set, int8_t valve_value, uint8_t shifting_index)
 
- Protected Member Functions inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
void checkSelfTests ()
 It is run in a separate thread and calls the checkTests() method of the self_tests_. More...
 
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

ros::Timer check_init_timeout_timer
 
std::map< unsigned int, unsigned int > from_muscle_driver_data_received_flags_
 
ros::Duration init_max_duration
 
boost::shared_ptr< boost::mutex > lock_init_timeout_
 
std::vector< shadow_joints::MuscleDrivermuscle_drivers_vector_
 
std::vector< generic_updater::UpdateConfigmuscle_update_rate_configs_vector
 
boost::shared_ptr< generic_updater::MuscleUpdater< CommandType > > muscle_updater_
 
shadow_joints::CalibrationMap pressure_calibration_map_
 The map used to calibrate each pressure sensor. More...
 
boost::shared_ptr< shadow_robot::JointCalibration > pressure_calibration_tmp_
 A temporary calibration for a given joint. More...
 
std::queue< int16_t, std::list< int16_t > > reset_muscle_driver_queue
 
- Protected Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
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 double timeout = 5.0
 
- Static Protected Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
static const char * human_readable_sensor_data_types []
 
static const int nb_sensor_data = 37
 
static const int32u sensor_data_types []
 

Additional Inherited Members

- Public Types inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
typedef std::map< std::string, CoupledJointCoupledJointMapType
 
- Static Public Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType >
static const double tactile_timeout = 10.0
 Timeout handling variables for UBI sensors. More...
 

Detailed Description

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

Definition at line 45 of file sr_muscle_robot_lib.hpp.

Constructor & Destructor Documentation

template<class StatusType , class CommandType >
shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::SrMuscleRobotLib ( hardware_interface::HardwareInterface *  hw,
ros::NodeHandle  nh,
ros::NodeHandle  nhtilde,
std::string  device_id,
std::string  joint_prefix 
)

Definition at line 68 of file sr_muscle_robot_lib.cpp.

Member Function Documentation

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::add_diagnostics ( std::vector< diagnostic_msgs::DiagnosticStatus > &  vec,
diagnostic_updater::DiagnosticStatusWrapper d 
)
virtual
template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::build_command ( CommandType *  command)
virtual
template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::calibrate_joint ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data 
)
protectedvirtual
template<class StatusType , class CommandType >
bool shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::check_muscle_driver_data_received_flags ( )
inlineprotected

Definition at line 804 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
sr_actuator::SrMuscleActuator* shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::get_joint_actuator ( std::vector< shadow_joints::Joint >::iterator  joint_tmp)
inlineprotectedvirtual
template<class StatusType , class CommandType >
unsigned int shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::get_muscle_pressure ( int  muscle_driver_id,
int  muscle_id,
StatusType *  status_data 
)
protected

Definition at line 634 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
vector< pair< string, bool > > shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::humanize_flags ( int  flag)
protected

Definition at line 906 of file sr_muscle_robot_lib.cpp.

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

Definition at line 952 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
virtual void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::initialize ( std::vector< std::string >  joint_names,
std::vector< int >  actuator_ids,
std::vector< shadow_joints::JointToSensor joint_to_sensors 
)
protectedpure virtual
template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::process_position_sensor_data ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data,
double  timestamp 
)
protected

Definition at line 887 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::read_additional_muscle_data ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data 
)
protected

Definition at line 493 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::read_muscle_driver_data ( std::vector< shadow_joints::MuscleDriver >::iterator  muscle_driver_tmp,
StatusType *  status_data 
)
protected

Definition at line 694 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
CalibrationMap shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::read_pressure_calibration ( )
protectedvirtual

Definition at line 95 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::reinitialize_motors ( )

Definition at line 934 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::set_muscle_driver_data_received_flags ( unsigned int  msg_type,
int  muscle_driver_id 
)
inlineprotected

Definition at line 790 of file sr_muscle_robot_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::set_valve_demand ( uint8_t *  muscle_data_byte_to_set,
int8_t  valve_value,
uint8_t  shifting_index 
)
inlineprotected

Definition at line 339 of file sr_muscle_robot_lib.cpp.

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

Member Data Documentation

template<class StatusType , class CommandType >
ros::Timer shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::check_init_timeout_timer
protected

Definition at line 225 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
std::map<unsigned int, unsigned int> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::from_muscle_driver_data_received_flags_
protected

Definition at line 222 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
ros::Duration shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::init_max_duration
protected

Definition at line 227 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
boost::shared_ptr<boost::mutex> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::lock_init_timeout_
protected

Definition at line 230 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_current_state

Definition at line 84 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
std::vector<shadow_joints::MuscleDriver> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_drivers_vector_
protected

Definition at line 198 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
std::vector<generic_updater::UpdateConfig> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_update_rate_configs_vector
protected

Definition at line 214 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
boost::shared_ptr<generic_updater::MuscleUpdater<CommandType> > shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::muscle_updater_
protected

Definition at line 206 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
shadow_joints::CalibrationMap shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::pressure_calibration_map_
protected

The map used to calibrate each pressure sensor.

Definition at line 108 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
boost::shared_ptr<shadow_robot::JointCalibration> shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::pressure_calibration_tmp_
protected

A temporary calibration for a given joint.

Definition at line 110 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
std::queue<int16_t, std::list<int16_t> > shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::reset_muscle_driver_queue
protected

Definition at line 210 of file sr_muscle_robot_lib.hpp.

template<class StatusType , class CommandType >
const double shadow_robot::SrMuscleRobotLib< StatusType, CommandType >::timeout = 5.0
staticprotected

Definition at line 226 of file sr_muscle_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 Tue Oct 13 2020 04:01:58