$search
#include <sr_friction_compensation.hpp>
| Public Member Functions | |
| double | friction_compensation (double position, double velocity, int force_demand, int deadband) | 
| SrFrictionCompensator (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::shared_ptr < shadow_robot::JointCalibration > | friction_interpoler_backward | 
| An interpoler for the backward friction map: used to compute the offset from the map, given the current position. | |
| boost::shared_ptr < shadow_robot::JointCalibration > | friction_interpoler_forward | 
| An interpoler 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 | |
Definition at line 52 of file sr_friction_compensation.hpp.
| sr_friction_compensation::SrFrictionCompensator::SrFrictionCompensator | ( | std::string | joint_name | ) | 
Definition at line 37 of file sr_friction_compensation.cpp.
| sr_friction_compensation::SrFrictionCompensator::~SrFrictionCompensator | ( | ) | 
Definition at line 46 of file sr_friction_compensation.cpp.
| 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.
| position | the current joint position. | |
| force_demand | the force demand is used to know in which direction we want to move: if > 0 -> forward if < 0 -> backward | |
| deadband | the deadband on the force_demand (in the deadband region, we're returning an offset of 0.0 for stability reasons). | 
Definition at line 49 of file sr_friction_compensation.cpp.
| std::vector< joint_calibration::Point > sr_friction_compensation::SrFrictionCompensator::generate_flat_map | ( | ) |  [private] | 
Generates a flat map for the joints missing one of their friction map.
Definition at line 189 of file sr_friction_compensation.cpp.
| std::pair< std::vector< joint_calibration::Point >, std::vector< joint_calibration::Point > > sr_friction_compensation::SrFrictionCompensator::read_friction_map | ( | ) |  [private] | 
Read the 2 friction maps from the parameter servers for each joint. Generate a flat map (no offset) if the map doesn't exist.
Definition at line 88 of file sr_friction_compensation.cpp.
| std::vector< joint_calibration::Point > sr_friction_compensation::SrFrictionCompensator::read_one_way_map | ( | XmlRpc::XmlRpcValue | raw_map | ) |  [private] | 
Format one map from the given raw map directly taken from the parameter server.
| raw_map | the raw_map directly read from the parameters. | 
Definition at line 166 of file sr_friction_compensation.cpp.
| boost::shared_ptr<shadow_robot::JointCalibration> sr_friction_compensation::SrFrictionCompensator::friction_interpoler_backward  [private] | 
An interpoler for the backward friction map: used to compute the offset from the map, given the current position.
Definition at line 117 of file sr_friction_compensation.hpp.
| boost::shared_ptr<shadow_robot::JointCalibration> sr_friction_compensation::SrFrictionCompensator::friction_interpoler_forward  [private] | 
An interpoler for the forward friction map: used to compute the offset from the map, given the current position.
Definition at line 115 of file sr_friction_compensation.hpp.
| std::string sr_friction_compensation::SrFrictionCompensator::joint_name_  [private] | 
the joint name
Definition at line 120 of file sr_friction_compensation.hpp.
node handle for reading the map from the parameters server.
Definition at line 84 of file sr_friction_compensation.hpp.
| const double sr_friction_compensation::SrFrictionCompensator::velocity_for_static_friction = 0.01  [static, private] | 
the threshold under which we use the static friction map
Definition at line 123 of file sr_friction_compensation.hpp.