Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
shadow_robot::SrMotorHandLib< StatusType, CommandType > Class Template Reference

#include <sr_motor_hand_lib.hpp>

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

List of all members.

Public Member Functions

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 (pr2_hardware_interface::HardwareInterface *hw)
 ~SrMotorHandLib ()

Protected Member Functions

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, std::vector< sr_actuator::SrGenericActuator * > actuators)
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)

Private Member Functions

std::vector< int > read_joint_to_motor_mapping ()
void resend_pids (std::string joint_name, int motor_index)

Private Attributes

ros::ServiceServer debug_service
 a service server for reconfiguring the debug data we want to publish
std::map< std::string, ros::Timerpid_timers

Static Private Attributes

static const char * human_readable_motor_data_types []
static const int32u motor_data_types []
static const int nb_motor_data = 14

Detailed Description

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

Definition at line 42 of file sr_motor_hand_lib.hpp.


Constructor & Destructor Documentation

template<class StatusType , class CommandType >
shadow_robot::SrMotorHandLib< StatusType, CommandType >::SrMotorHandLib ( pr2_hardware_interface::HardwareInterface hw)

Definition at line 62 of file sr_motor_hand_lib.cpp.

template<class StatusType , class CommandType >
shadow_robot::SrMotorHandLib< StatusType, CommandType >::~SrMotorHandLib ( )

Definition at line 114 of file sr_motor_hand_lib.cpp.


Member Function Documentation

template<class StatusType , class CommandType >
std::string shadow_robot::SrMotorHandLib< StatusType, CommandType >::find_joint_name ( int  motor_index) [protected]

Finds the joint name for a certain motor index

Parameters:
motor_indexThe integer motor index

Definition at line 383 of file sr_motor_hand_lib.cpp.

template<class StatusType , class CommandType >
bool shadow_robot::SrMotorHandLib< StatusType, CommandType >::force_pid_callback ( sr_robot_msgs::ForceController::Request &  request,
sr_robot_msgs::ForceController::Response &  response,
int  motor_index 
)

The service callback for setting the Force PID values. There's only one callback function, but it can called for any motors. We know which motor called the service thanks to the motor_index.

Parameters:
requestThe request contains the new parameters for the controllers.
responseTrue if succeeded.
motor_indexThe index of the motor for which the service has been called.
Returns:
true if succeeded.

Definition at line 272 of file sr_motor_hand_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMotorHandLib< StatusType, CommandType >::initialize ( std::vector< std::string >  joint_names,
std::vector< int >  actuator_ids,
std::vector< shadow_joints::JointToSensor joint_to_sensors,
std::vector< sr_actuator::SrGenericActuator * >  actuators 
) [protected, 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.
actuatorsA vector containing the actuators for the different joints.

Implements shadow_robot::SrMotorRobotLib< StatusType, CommandType >.

Definition at line 124 of file sr_motor_hand_lib.cpp.

template<class StatusType , class CommandType >
std::vector< int > shadow_robot::SrMotorHandLib< StatusType, CommandType >::read_joint_to_motor_mapping ( ) [private]

Reads the mapping associating a joint to a motor. If the motor index is -1, then no motor is associated to this joint.

Returns:
a vector of motor indexes, ordered by joint.

Definition at line 440 of file sr_motor_hand_lib.cpp.

template<class StatusType , class CommandType >
void shadow_robot::SrMotorHandLib< StatusType, CommandType >::resend_pids ( std::string  joint_name,
int  motor_index 
) [private]

Read the motor board force pids from the parameter servers, called when resetting the motor.

Parameters:
joint_namethe joint we want to reset
motor_indexthe index of the motor for this joint

Definition at line 193 of file sr_motor_hand_lib.cpp.

template<class StatusType , class CommandType >
bool shadow_robot::SrMotorHandLib< StatusType, CommandType >::reset_motor_callback ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response,
std::pair< int, std::string >  joint 
)

Reset the motor at motor index.

Parameters:
requestempty
responseempty
jointA pair containing the index of the motor for the given joint followed by the name of the joint we're resetting
Returns:
true if success

Definition at line 168 of file sr_motor_hand_lib.cpp.

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

Updates the parameter values for the force control in the Parameter Server

Parameters:
joint_nameThe name of the joint.
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 399 of file sr_motor_hand_lib.cpp.


Member Data Documentation

template<class StatusType, class CommandType>
ros::ServiceServer shadow_robot::SrMotorHandLib< StatusType, CommandType >::debug_service [private]

a service server for reconfiguring the debug data we want to publish

Definition at line 147 of file sr_motor_hand_lib.hpp.

template<class StatusType, class CommandType>
const char * shadow_robot::SrMotorHandLib< StatusType, CommandType >::human_readable_motor_data_types [static, private]
Initial value:
 {"sgl", "sgr", "pwm", "flags", "current",
                                                                           "voltage", "temperature", "can_num_received",
                                                                           "can_num_transmitted", "slow_data",
                                                                           "can_error_counters",
                                                                           "pterm", "iterm", "dterm"}

Definition at line 143 of file sr_motor_hand_lib.hpp.

template<class StatusType, class CommandType>
const int32u shadow_robot::SrMotorHandLib< StatusType, CommandType >::motor_data_types [static, private]
Initial value:
 {MOTOR_DATA_SGL, MOTOR_DATA_SGR,
                                                             MOTOR_DATA_PWM, MOTOR_DATA_FLAGS,
                                                             MOTOR_DATA_CURRENT, MOTOR_DATA_VOLTAGE,
                                                             MOTOR_DATA_TEMPERATURE, MOTOR_DATA_CAN_NUM_RECEIVED,
                                                             MOTOR_DATA_CAN_NUM_TRANSMITTED, MOTOR_DATA_SLOW_MISC,
                                                             MOTOR_DATA_CAN_ERROR_COUNTERS,
                                                             MOTOR_DATA_PTERM, MOTOR_DATA_ITERM,
                                                             MOTOR_DATA_DTERM}

Definition at line 144 of file sr_motor_hand_lib.hpp.

template<class StatusType, class CommandType>
const int shadow_robot::SrMotorHandLib< StatusType, CommandType >::nb_motor_data = 14 [static, private]

Definition at line 142 of file sr_motor_hand_lib.hpp.

template<class StatusType, class CommandType>
std::map<std::string, ros::Timer> shadow_robot::SrMotorHandLib< StatusType, CommandType >::pid_timers [private]

A map used to keep the timers created in reset_motor_callback alive. We're using a map to keep only one timer per joint.

Definition at line 162 of file sr_motor_hand_lib.hpp.


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


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:37:50