Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
sr_friction_compensation::SrFrictionCompensator Class Reference

#include <sr_friction_compensation.hpp>

List of all members.

Public Member Functions

double friction_compensation (double position, double velocity, int force_demand, int deadband)
 SrFrictionCompensator (const std::string &joint_name)
 ~SrFrictionCompensator ()

Private Member Functions

std::vector
< joint_calibration::Point
generate_flat_map ()
std::pair< std::vector
< joint_calibration::Point >
, std::vector
< joint_calibration::Point > > 
read_friction_map ()
std::vector
< joint_calibration::Point
read_one_way_map (XmlRpc::XmlRpcValue &raw_map)

Private Attributes

boost::scoped_ptr
< shadow_robot::JointCalibration
friction_interpoler_backward
 An interpolator for the backward friction map: used to compute the offset from the map, given the current position.
boost::scoped_ptr
< shadow_robot::JointCalibration
friction_interpoler_forward
 An interpolator for the forward friction map: used to compute the offset from the map, given the current position.
std::string joint_name_
 the joint name
ros::NodeHandle node_
 node handle for reading the map from the parameters server.

Static Private Attributes

static const double velocity_for_static_friction = 0.01
 the threshold under which we use the static friction map

Detailed Description

Definition at line 50 of file sr_friction_compensation.hpp.


Constructor & Destructor Documentation

Definition at line 39 of file sr_friction_compensation.cpp.

Definition at line 47 of file sr_friction_compensation.cpp.


Member Function Documentation

double sr_friction_compensation::SrFrictionCompensator::friction_compensation ( double  position,
double  velocity,
int  force_demand,
int  deadband 
)

Computes the value of the offset to add to the force demand to compensate for the friction. This offset is computed based on the current joint position and on the force demand sign as well, using a friction map.

The friction map is generated by moving the joint very slowly, from one end to the other, while recording the force necessary to move it. Two different map position->force are then created by interpolating those values, one for each direction.

Parameters:
positionthe current joint position.
velocitythe current joint velocity.
force_demandthe force demand is used to know in which direction we want to move: if > 0 -> forward if < 0 -> backward
deadbandthe deadband on the force_demand (in the deadband region, we're returning an offset of 0.0 for stability reasons).
Returns:
the force necessary to have the joint ready to move.

Definition at line 51 of file sr_friction_compensation.cpp.

Generates a flat map for the joints missing one of their friction map.

Returns:
A flat map (always 0.0)

Definition at line 191 of file sr_friction_compensation.cpp.

Read the 2 friction maps from the parameter servers for each joint. Generate a flat map (no offset) if the map doesn't exist.

Returns:
a pair of map: the first is the forward map, the second is the backward map.

Definition at line 90 of file sr_friction_compensation.cpp.

Format one map from the given raw map directly taken from the parameter server.

Parameters:
raw_mapthe raw_map directly read from the parameters.
Returns:
The map (either forward or backward)

Definition at line 168 of file sr_friction_compensation.cpp.


Member Data Documentation

An interpolator for the backward friction map: used to compute the offset from the map, given the current position.

Definition at line 116 of file sr_friction_compensation.hpp.

An interpolator for the forward friction map: used to compute the offset from the map, given the current position.

Definition at line 114 of file sr_friction_compensation.hpp.

the joint name

Definition at line 119 of file sr_friction_compensation.hpp.

node handle for reading the map from the parameters server.

Definition at line 83 of file sr_friction_compensation.hpp.

the threshold under which we use the static friction map

Definition at line 122 of file sr_friction_compensation.hpp.


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


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:26:14