Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
shadow_robot::SrHandLib Class Reference

#include <sr_hand_lib.hpp>

Inheritance diagram for shadow_robot::SrHandLib:
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)
 SrHandLib (pr2_hardware_interface::HardwareInterface *hw)
 ~SrHandLib ()

Protected Member Functions

std::string find_joint_name (int motor_index)
virtual void initialize (std::vector< std::string > joint_names, std::vector< int > motor_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors, std::vector< sr_actuator::SrActuator * > 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

shadow_joints::CalibrationMap read_joint_calibration ()
std::vector< int > read_joint_to_motor_mapping ()
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 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
ros::NodeHandle nodehandle_
std::map< std::string, ros::Timerpid_timers

Static Private Attributes

static const char * human_readable_motor_data_types []
static const char * human_readable_sensor_data_types []
static const int32u motor_data_types []
static const int nb_motor_data = 14
static const int nb_sensor_data = 31
static const int32u sensor_data_types []

Detailed Description

Definition at line 41 of file sr_hand_lib.hpp.


Constructor & Destructor Documentation

Definition at line 123 of file sr_hand_lib.cpp.

Definition at line 185 of file sr_hand_lib.cpp.


Member Function Documentation

std::string shadow_robot::SrHandLib::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 447 of file sr_hand_lib.cpp.

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 337 of file sr_hand_lib.cpp.

void shadow_robot::SrHandLib::initialize ( std::vector< std::string >  joint_names,
std::vector< int >  motor_ids,
std::vector< shadow_joints::JointToSensor joint_to_sensors,
std::vector< sr_actuator::SrActuator * >  actuators 
) [protected, virtual]

Initializes the hand library with the needed values.

Parameters:
joint_namesA vector containing all the joint names.
motor_idsA vector containing the corresponding motor 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::SrRobotLib.

Definition at line 194 of file sr_hand_lib.cpp.

Reads the calibration from the parameter server.

Returns:
a calibration map

Definition at line 561 of file sr_hand_lib.cpp.

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 603 of file sr_hand_lib.cpp.

Reads the mapping between the sensors and the joints from the parameter server.

Returns:
a vector (size of the number of joints) containing vectors (containing the sensors which are combined to form a given joint)

Definition at line 503 of file sr_hand_lib.cpp.

std::vector< generic_updater::UpdateConfig > shadow_robot::SrHandLib::read_update_rate_configs ( std::string  base_param,
int  nb_data_defined,
const char *  human_readable_data_types[],
const int32u  data_types[] 
) [private]

Simply reads the config from the parameter server.

string with the base name of the set of parameters to apply (found in the yaml file) number of data defined in the typedef names of the types of messages (must match with those in the yaml file) the command values corresponding to every one of the names

Returns:
A vector of UpdateConfig containing the type of data and the frequency at which we want to poll this data

Definition at line 621 of file sr_hand_lib.cpp.

void shadow_robot::SrHandLib::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 259 of file sr_hand_lib.cpp.

bool shadow_robot::SrHandLib::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 235 of file sr_hand_lib.cpp.

void shadow_robot::SrHandLib::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 462 of file sr_hand_lib.cpp.


Member Data Documentation

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

Definition at line 180 of file sr_hand_lib.hpp.

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 172 of file sr_hand_lib.hpp.

Definition at line 176 of file sr_hand_lib.hpp.

const int shadow_robot::SrHandLib::nb_motor_data = 14 [static, private]

Definition at line 171 of file sr_hand_lib.hpp.

const int shadow_robot::SrHandLib::nb_sensor_data = 31 [static, private]

Definition at line 175 of file sr_hand_lib.hpp.

Definition at line 129 of file sr_hand_lib.hpp.

std::map<std::string, ros::Timer> shadow_robot::SrHandLib::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 195 of file sr_hand_lib.hpp.

Definition at line 177 of file sr_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 Thu Jan 2 2014 12:02:17