Public Member Functions | Public Attributes | Protected Types | Protected Member Functions | Protected Attributes
shadow_robot::SrMotorRobotLib< StatusType, CommandType > Class Template Reference

#include <sr_motor_robot_lib.hpp>

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

List of all members.

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 Attributes

operation_mode::device_update_state::DeviceUpdateState motor_current_state

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)
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)
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 Attributes

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

Detailed Description

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

Definition at line 50 of file sr_motor_robot_lib.hpp.


Member Typedef Documentation

template<class StatusType, class CommandType>
typedef std::pair<int, std::vector<crc_unions::union16> > shadow_robot::SrMotorRobotLib< StatusType, CommandType >::ForceConfig [protected]

The ForceConfig type consists of an int representing the motor index for this config followed by a vector of config: the index in the vector of config corresponds to the type of the data, and the value at this index corresponds to the value we want to set.

Definition at line 187 of file sr_motor_robot_lib.hpp.


Constructor & Destructor Documentation

template<class StatusType, class CommandType>
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 62 of file sr_motor_robot_lib.cpp.


Member Function Documentation

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

This function adds the diagnostics for the hand to the multi diagnostic status published in sr06.cpp.

Implements shadow_robot::SrRobotLib< StatusType, CommandType >.

Definition at line 472 of file sr_motor_robot_lib.cpp.

template<class StatusType , class CommandType>
void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::build_command ( CommandType *  command) [virtual]

Builds a motor command: either send a torque demand or a configuration demand if one is waiting.

Parameters:
commandThe command we're building.

Implements shadow_robot::SrRobotLib< StatusType, CommandType >.

Definition at line 197 of file sr_motor_robot_lib.cpp.

template<class StatusType, class CommandType>
void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::calibrate_joint ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data 
) [protected, virtual]

Compute the calibrated position for the given joint. This method is called from the update method, each time a new message is received.

Parameters:
joint_tmpThe joint we want to calibrate.
status_dataThe status information that comes from the robot

Implements shadow_robot::SrRobotLib< StatusType, CommandType >.

Definition at line 919 of file sr_motor_robot_lib.cpp.

template<class StatusType , class CommandType >
bool shadow_robot::SrMotorRobotLib< StatusType, CommandType >::change_control_parameters ( int16_t  control_type) [protected]

Load the necessary parameters in the Parameter Server and calls a service for every controller currently loaded in the controller manager to make it reload (resetGains()) its parameters from the Parameter Server

Parameters:
control_typeThe new active control type (PWM or torque)
Returns:
true if all the steps successful

Definition at line 1180 of file sr_motor_robot_lib.cpp.

template<class StatusType , class CommandType >
bool shadow_robot::SrMotorRobotLib< StatusType, CommandType >::change_control_type_callback_ ( sr_robot_msgs::ChangeControlType::Request &  request,
sr_robot_msgs::ChangeControlType::Response &  response 
) [protected]

The callback to the change_control_type_ service. Updates the current control_type_ with the requested control_type.

Parameters:
requestRequested control_type_
responseThe new control_type we'll use
Returns:
true if success, false if bad control type requested

Definition at line 1125 of file sr_motor_robot_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::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 
) [protected]

Generates a force control config and adds it to the reconfig_queue with its CRC. The config will be sent as soon as possible.

Parameters:
motor_indexThe motor index.
max_pwmThe max pwm the motor will apply
sg_leftStrain gauge left
sg_rightStrain gauge right
fThe feedforward term (directly adds f*error to the output of the PID)
pThe p value.
ithe i value.
dthe d value.
imaxthe imax value.
deadbandthe deadband on the force.
signcan be 0 or 1 depending on the way the motor is plugged in.

Definition at line 1032 of file sr_motor_robot_lib.cpp.

template<class StatusType, class CommandType>
sr_actuator::SrMotorActuator* shadow_robot::SrMotorRobotLib< StatusType, CommandType >::get_joint_actuator ( std::vector< shadow_joints::Joint >::iterator  joint_tmp) [inline, protected, virtual]

Returns a pointer to the actuator for a certain joint.

Parameters:
joint_tmpThe joint we want to get the actuator from.
Returns:
a pointer to the actuator

Implements shadow_robot::SrRobotLib< StatusType, CommandType >.

Definition at line 169 of file sr_motor_robot_lib.hpp.

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

Transforms the incoming flag as a human readable vector of strings.

Parameters:
flagincoming flag.
Returns:
human readable flags.

Definition at line 1004 of file sr_motor_robot_lib.cpp.

template<class StatusType, class CommandType>
virtual void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::initialize ( std::vector< std::string >  joint_names,
std::vector< int >  actuator_ids,
std::vector< shadow_joints::JointToSensor joint_to_sensors 
) [protected, pure virtual]

Initializes the hand library with the needed values.

Parameters:
joint_namesA vector containing all the joint names.
actuator_idsA vector containing the corresponding actuator ids.
joint_to_sensorsA vector mapping the joint to the sensor index we read from the palm.

Implements shadow_robot::SrRobotLib< StatusType, CommandType >.

Implemented in shadow_robot::SrMotorHandLib< StatusType, CommandType >, and shadow_robot::SrMotorHandLib< STATUS_TYPE, COMMAND_TYPE >.

template<class StatusType , class CommandType >
bool shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_system_controls_callback_ ( sr_robot_msgs::ChangeMotorSystemControls::Request &  request,
sr_robot_msgs::ChangeMotorSystemControls::Response &  response 
) [protected]

The callback to the control_motor_ service. Sets the correct flags to 1 or 0 for the MOTOR_SYSTEM_CONTROLS, to control the motors (backlash compensation on/off, increase sg tracking, jiggling, write config to EEprom)

Parameters:
requestContains the different flags the user wants to set
responseSUCCESS if success, MOTOR_ID_OUT_OF_RANGE if bad motor_id given
Returns:
false if motor_id is out of range

Definition at line 1268 of file sr_motor_robot_lib.cpp.

template<class StatusType, class CommandType>
void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::process_position_sensor_data ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data,
double  timestamp 
) [protected]

Calibrates and filters the position information (and computes velocity) for a give joint. This method is called from the update method, each time a new message is received.

Parameters:
joint_tmpThe joint we process data from.
status_dataThe status information that comes from the robot
timestampTimestamp of the data acquisition time

Definition at line 986 of file sr_motor_robot_lib.cpp.

template<class StatusType, class CommandType>
void shadow_robot::SrMotorRobotLib< StatusType, CommandType >::read_additional_data ( std::vector< shadow_joints::Joint >::iterator  joint_tmp,
StatusType *  status_data 
) [protected]

Read additional data from the latest message and stores it into the joints_vector.

Parameters:
joint_tmpThe joint we want to read the data for.
status_dataThe status information that comes from the robot

Definition at line 613 of file sr_motor_robot_lib.cpp.

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

Initiates the process to retrieve the initialization information from the motors

Definition at line 1112 of file sr_motor_robot_lib.cpp.

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

This function is called each time a new etherCAT message is received in the sr06.cpp driver. It updates the joints_vector, updating the different values, computing the calibrated joint positions, etc... It also updates the tactile sensors values.

Parameters:
status_datathe received etherCAT message

Implements shadow_robot::SrRobotLib< StatusType, CommandType >.

Definition at line 105 of file sr_motor_robot_lib.cpp.


Member Data Documentation

template<class StatusType, class CommandType>
ros::ServiceServer shadow_robot::SrMotorRobotLib< StatusType, CommandType >::change_control_type_ [protected]

Definition at line 227 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
int shadow_robot::SrMotorRobotLib< StatusType, CommandType >::config_index [protected]

Definition at line 193 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
sr_robot_msgs::ControlType shadow_robot::SrMotorRobotLib< StatusType, CommandType >::control_type_ [protected]

Definition at line 216 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
bool shadow_robot::SrMotorRobotLib< StatusType, CommandType >::control_type_changed_flag_ [protected]

Flag to signal that there has been a change in the value of control_type_ and certain actions are required. The flag is set in the callback function of the change_control_type_ service. The flag is checked in build_command() and the necessary actions are taken there. These actions involve calling services in the controller manager and all the active controllers. This is the reason why we don't do it directly in the callback function. As we use a single thread to serve the callbacks, doing so would cause a deadlock, thus we do it in the realtime loop thread instead.

Definition at line 225 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
int8u shadow_robot::SrMotorRobotLib< StatusType, CommandType >::crc_byte [protected]

Definition at line 204 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
int8u shadow_robot::SrMotorRobotLib< StatusType, CommandType >::crc_i [protected]

Definition at line 206 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
int16u shadow_robot::SrMotorRobotLib< StatusType, CommandType >::crc_result [protected]

Definition at line 205 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
int shadow_robot::SrMotorRobotLib< StatusType, CommandType >::index_motor_in_msg [protected]

Definition at line 202 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
boost::shared_ptr<boost::mutex> shadow_robot::SrMotorRobotLib< StatusType, CommandType >::lock_command_sending_ [protected]

Definition at line 230 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
operation_mode::device_update_state::DeviceUpdateState shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_current_state

Definition at line 89 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
boost::shared_ptr<generic_updater::MotorDataChecker> shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_data_checker [protected]

Definition at line 212 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
int shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_index_full [protected]

Definition at line 200 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
std::queue<std::vector<sr_robot_msgs::MotorSystemControls>, std::list<std::vector<sr_robot_msgs::MotorSystemControls> > > shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_system_control_flags_ [protected]

Definition at line 257 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
ros::ServiceServer shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_system_control_server_ [protected]

Definition at line 259 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
std::vector<generic_updater::UpdateConfig> shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_update_rate_configs_vector [protected]

Definition at line 210 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
boost::shared_ptr<generic_updater::MotorUpdater<CommandType> > shadow_robot::SrMotorRobotLib< StatusType, CommandType >::motor_updater_ [protected]

The motor updater is used to create a correct command to send to the motor. It's build_command() is called each time the SR06::packCommand() is called.

Definition at line 179 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
std::queue<ForceConfig, std::list<ForceConfig> > shadow_robot::SrMotorRobotLib< StatusType, CommandType >::reconfig_queue [protected]

This queue contains the force PID config waiting to be pushed to the motor.

Definition at line 191 of file sr_motor_robot_lib.hpp.

template<class StatusType, class CommandType>
std::queue<int16_t, std::list<int16_t> > shadow_robot::SrMotorRobotLib< StatusType, CommandType >::reset_motors_queue [protected]

Definition at line 196 of file sr_motor_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 Jul 1 2019 20:06:26