26 #ifndef _SR_FRICTION_COMPENSATION_HPP_ 27 #define _SR_FRICTION_COMPENSATION_HPP_ 31 #include <boost/scoped_ptr.hpp> 38 #include <boost/thread/condition.hpp> 40 #include <std_msgs/Float64.h> 43 #include <sr_robot_msgs/SetMixedPositionVelocityPidGains.h> 92 std::pair<std::vector<joint_calibration::Point>, std::vector<joint_calibration::Point> >
read_friction_map();
std::vector< joint_calibration::Point > generate_flat_map()
static const double velocity_for_static_friction
std::pair< std::vector< joint_calibration::Point >, std::vector< joint_calibration::Point > > read_friction_map()
double friction_compensation(double position, double velocity, int force_demand, int deadband)
SrFrictionCompensator(const std::string &joint_name)
boost::scoped_ptr< shadow_robot::JointCalibration > friction_interpoler_backward
An interpolator for the backward friction map: used to compute the offset from the map...
ros::NodeHandle node_
node handle for reading the map from the parameters server.
std::vector< joint_calibration::Point > read_one_way_map(XmlRpc::XmlRpcValue &raw_map)
boost::scoped_ptr< shadow_robot::JointCalibration > friction_interpoler_forward
An interpolator for the forward friction map: used to compute the offset from the map...