sr_friction_compensation.hpp
Go to the documentation of this file.
1 
26 #ifndef _SR_FRICTION_COMPENSATION_HPP_
27 #define _SR_FRICTION_COMPENSATION_HPP_
28 
29 #include <ros/node_handle.h>
30 
31 #include <boost/scoped_ptr.hpp>
32 
33 #include <utility>
34 #include <string>
35 #include <vector>
36 
37 #include <control_toolbox/pid.h>
38 #include <boost/thread/condition.hpp>
40 #include <std_msgs/Float64.h>
41 
42 
43 #include <sr_robot_msgs/SetMixedPositionVelocityPidGains.h>
44 
46 
48 {
50 {
51 public:
52  explicit SrFrictionCompensator(const std::string &joint_name);
53 
55 
78  double friction_compensation(double position, double velocity, int force_demand, int deadband);
79 
80 private:
83 
92  std::pair<std::vector<joint_calibration::Point>, std::vector<joint_calibration::Point> > read_friction_map();
93 
102  std::vector<joint_calibration::Point> read_one_way_map(XmlRpc::XmlRpcValue &raw_map);
103 
110  std::vector<joint_calibration::Point> generate_flat_map();
111 
113  boost::scoped_ptr<shadow_robot::JointCalibration> friction_interpoler_forward;
115  boost::scoped_ptr<shadow_robot::JointCalibration> friction_interpoler_backward;
116 
117  // the joint name
118  std::string joint_name_;
119 
120  // the threshold under which we use the static friction map
121  static const double velocity_for_static_friction;
122 };
123 } // namespace sr_friction_compensation
124 
125 /* For the emacs weenies in the crowd.
126 Local Variables:
127  c-basic-offset: 2
128 End:
129 */
130 
131 
132 #endif
std::vector< joint_calibration::Point > generate_flat_map()
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)
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...


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58