|
bool | force_pid_callback (sr_robot_msgs::ForceController::Request &request, sr_robot_msgs::ForceController::Response &response, int motor_index) |
|
bool | reset_motor_callback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, std::pair< int, std::string > joint) |
|
| SrMotorHandLib (hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix) |
|
Public Member Functions inherited from shadow_robot::SrMotorRobotLib< StatusType, CommandType > |
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 () |
|
|
std::string | find_joint_name (int motor_index) |
|
virtual void | initialize (std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors) |
|
void | update_force_control_in_param_server (std::string joint_name, 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) |
|
Protected Member Functions inherited from shadow_robot::SrMotorRobotLib< StatusType, CommandType > |
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) |
|
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) |
|
|
Public Types inherited from shadow_robot::SrRobotLib< StatusType, CommandType > |
typedef std::map< std::string, CoupledJoint > | CoupledJointMapType |
|
Public Attributes inherited from shadow_robot::SrMotorRobotLib< StatusType, CommandType > |
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 |
|
Static Public Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > |
static const double | tactile_timeout = 10.0 |
| Timeout handling variables for UBI sensors. More...
|
|
Protected Types inherited from shadow_robot::SrMotorRobotLib< StatusType, CommandType > |
typedef std::pair< int, std::vector< crc_unions::union16 > > | ForceConfig |
|
Protected Attributes inherited from shadow_robot::SrMotorRobotLib< StatusType, CommandType > |
ros::ServiceServer | change_control_type_ |
|
int | config_index |
|
sr_robot_msgs::ControlType | control_type_ |
|
bool | control_type_changed_flag_ |
|
int8u | crc_byte |
|
int8u | crc_i |
|
int16u | crc_result |
|
int | index_motor_in_msg |
|
boost::shared_ptr< boost::mutex > | lock_command_sending_ |
|
boost::shared_ptr< generic_updater::MotorDataChecker > | motor_data_checker |
|
int | motor_index_full |
|
std::queue< std::vector< sr_robot_msgs::MotorSystemControls >, std::list< std::vector< sr_robot_msgs::MotorSystemControls > > > | motor_system_control_flags_ |
|
ros::ServiceServer | motor_system_control_server_ |
|
std::vector< generic_updater::UpdateConfig > | motor_update_rate_configs_vector |
|
boost::shared_ptr< generic_updater::MotorUpdater< CommandType > > | motor_updater_ |
|
std::queue< ForceConfig, std::list< ForceConfig > > | reconfig_queue |
|
std::queue< int16_t, std::list< int16_t > > | reset_motors_queue |
|
Protected Attributes inherited from shadow_robot::SrRobotLib< StatusType, CommandType > |
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 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 [] |
|
template<class StatusType, class CommandType>
class shadow_robot::SrMotorHandLib< StatusType, CommandType >
Definition at line 44 of file sr_motor_hand_lib.hpp.