#include <sr_motor_robot_lib.hpp>
Public Member Functions | |
void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d) |
void | build_command (CommandType *command) |
void | reinitialize_motors () |
SrMotorRobotLib (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 | motor_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 Types | |
typedef std::pair< int, std::vector< crc_unions::union16 > > | ForceConfig |
Protected Member Functions | |
void | calibrate_joint (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data) |
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) |
bool | check_if_joint_coupled (string joint_name) |
int | find_joint_by_name (string joint_name) |
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, int torque_limit, int torque_limiter_gain) |
sr_actuator::SrMotorActuator * | get_joint_actuator (std::vector< shadow_joints::Joint >::iterator joint_tmp) |
std::vector< std::pair< std::string, bool > > | humanize_flags (int flag) |
virtual void | initialize (std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors)=0 |
bool | motor_system_controls_callback_ (sr_robot_msgs::ChangeMotorSystemControls::Request &request, sr_robot_msgs::ChangeMotorSystemControls::Response &response) |
void | process_position_sensor_data (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data, double timestamp) |
void | read_additional_data (std::vector< shadow_joints::Joint >::iterator joint_tmp, StatusType *status_data) |
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::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) |
Additional Inherited Members | |
Public Types inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | |
typedef std::map< std::string, CoupledJoint > | CoupledJointMapType |
Static Public Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > | |
static const double | tactile_timeout = 10.0 |
Timeout handling variables for UBI sensors. More... | |
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 [] |
Definition at line 49 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 186 of file sr_motor_robot_lib.hpp.
shadow_robot::SrMotorRobotLib< StatusType, CommandType >::SrMotorRobotLib | ( | hardware_interface::HardwareInterface * | hw, |
ros::NodeHandle | nh, | ||
ros::NodeHandle | nhtilde, | ||
std::string | device_id, | ||
std::string | joint_prefix | ||
) |
Definition at line 61 of file sr_motor_robot_lib.cpp.
|
virtual |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 471 of file sr_motor_robot_lib.cpp.
|
virtual |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 196 of file sr_motor_robot_lib.cpp.
|
protectedvirtual |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 918 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 1220 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 1165 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 1008 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 1330 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 1064 of file sr_motor_robot_lib.cpp.
|
inlineprotectedvirtual |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 168 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 1036 of file sr_motor_robot_lib.cpp.
|
protectedpure virtual |
|
protected |
Definition at line 1296 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 1018 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 612 of file sr_motor_robot_lib.cpp.
void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::reinitialize_motors | ( | ) |
Definition at line 1152 of file sr_motor_robot_lib.cpp.
|
virtual |
Implements shadow_robot::SrRobotLib< StatusType, CommandType >.
Definition at line 104 of file sr_motor_robot_lib.cpp.
|
protected |
Definition at line 226 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 192 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 215 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 224 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 203 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 205 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 204 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 201 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 229 of file sr_motor_robot_lib.hpp.
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_current_state |
Definition at line 88 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 211 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 199 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 256 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 258 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 209 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 178 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 190 of file sr_motor_robot_lib.hpp.
|
protected |
Definition at line 195 of file sr_motor_robot_lib.hpp.