#include <sr_motor_hand_lib.hpp>
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::Timer > | pid_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 |
Definition at line 42 of file sr_motor_hand_lib.hpp.
shadow_robot::SrMotorHandLib< StatusType, CommandType >::SrMotorHandLib | ( | pr2_hardware_interface::HardwareInterface * | hw | ) |
Definition at line 62 of file sr_motor_hand_lib.cpp.
shadow_robot::SrMotorHandLib< StatusType, CommandType >::~SrMotorHandLib | ( | ) |
Definition at line 114 of file sr_motor_hand_lib.cpp.
std::string shadow_robot::SrMotorHandLib< StatusType, CommandType >::find_joint_name | ( | int | motor_index | ) | [protected] |
Finds the joint name for a certain motor index
motor_index | The integer motor index |
Definition at line 383 of file sr_motor_hand_lib.cpp.
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.
request | The request contains the new parameters for the controllers. |
response | True if succeeded. |
motor_index | The index of the motor for which the service has been called. |
Definition at line 272 of file sr_motor_hand_lib.cpp.
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.
joint_names | A vector containing all the joint names. |
actuator_ids | A vector containing the corresponding actuator ids. |
joint_to_sensors | A vector mapping the joint to the sensor index we read from the palm. |
actuators | A 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.
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.
Definition at line 440 of file sr_motor_hand_lib.cpp.
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.
joint_name | the joint we want to reset |
motor_index | the index of the motor for this joint |
Definition at line 193 of file sr_motor_hand_lib.cpp.
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.
request | empty |
response | empty |
joint | A pair containing the index of the motor for the given joint followed by the name of the joint we're resetting |
Definition at line 168 of file sr_motor_hand_lib.cpp.
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
joint_name | The name of the joint. |
max_pwm | The max pwm the motor will apply |
sg_left | Strain gauge left |
sg_right | Strain gauge right |
f | The feedforward term (directly adds f*error to the output of the PID) |
p | The p value. |
i | the i value. |
d | the d value. |
imax | the imax value. |
deadband | the deadband on the force. |
sign | can be 0 or 1 depending on the way the motor is plugged in. |
Definition at line 399 of file sr_motor_hand_lib.cpp.
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.
const char * shadow_robot::SrMotorHandLib< StatusType, CommandType >::human_readable_motor_data_types [static, private] |
{"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.
const int32u shadow_robot::SrMotorHandLib< StatusType, CommandType >::motor_data_types [static, private] |
{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.
const int shadow_robot::SrMotorHandLib< StatusType, CommandType >::nb_motor_data = 14 [static, private] |
Definition at line 142 of file sr_motor_hand_lib.hpp.
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.