sr_friction_compensation.cpp
Go to the documentation of this file.
1 /*
2 * Copyright 2011 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
28 
29 #include <utility>
30 #include <vector>
31 #include <string>
32 #include <sstream>
33 #include <math.h>
36 
37 using std::string;
38 using std::vector;
39 using std::pair;
40 
42 {
44 
46  joint_name_(joint_name)
47  {
48  pair<vector<joint_calibration::Point>, vector<joint_calibration::Point> > both_maps = read_friction_map();
51  }
52 
54  {
55  }
56 
57  double SrFrictionCompensator::friction_compensation(double position, double velocity, int force_demand, int deadband)
58  {
59  double compensation = 0.0;
60 
61  if (force_demand > 0.0)
62  {
63  compensation = friction_interpoler_forward->compute(position);
64  }
65  else
66  {
67  compensation = friction_interpoler_backward->compute(position);
68  }
69 
70  // A value by which we'll multiply the compensation computed by the
71  // friction map.
72  double mult = 1.0;
73  // we're out of the "finger is stopped" zone ->
74  // progressively decrease the amount of compensation
75  if (fabs(velocity) > velocity_for_static_friction)
76  {
77  if (velocity < 0.0)
78  {
79  mult = exp(-fabs(velocity + velocity_for_static_friction) * 20);
80  }
81  else
82  {
83  mult = exp(-fabs(velocity - velocity_for_static_friction) * 20);
84  }
85  }
86 
87  // decrease the compensation around the force sign change
88  // to have less discontinuity. Use the deadband for this.
89  if (abs(force_demand) < deadband)
90  {
91  // we want the multiplier to be 1 if force_demand = deadband
92  // and 0 if force_demand = 0
93  mult *= sr_math_utils::linear_interpolate_(static_cast<double> (abs(force_demand)),
94  0.0, 0.0,
95  static_cast<double> (deadband), 1.0);
96  }
97 
98  // amend the compensation value
99  compensation *= mult;
100 
101  return compensation;
102  }
103 
104  pair<vector<joint_calibration::Point>, vector<joint_calibration::Point> > SrFrictionCompensator::read_friction_map()
105  {
106  vector<joint_calibration::Point> friction_map_forward, friction_map_backward;
107  string param_name = "/sr_friction_map";
108 
109  bool joint_not_found_forward = true;
110  bool joint_not_found_backward = true;
111 
112  XmlRpc::XmlRpcValue calib;
113  if (node_.hasParam(param_name))
114  {
115  node_.getParam(param_name, calib);
116 
117  ROS_DEBUG_STREAM(" Reading friction for: " << joint_name_);
118  ROS_DEBUG_STREAM(" value: " << calib);
119 
121  // iterate on all the joints
122  for (int32_t index_cal = 0; index_cal < calib.size(); ++index_cal)
123  {
124  // check the calibration is well formatted:
125  // first joint name, then calibration table
126  ROS_ASSERT(calib[index_cal][0].getType() == XmlRpc::XmlRpcValue::TypeString);
127  ROS_ASSERT(calib[index_cal][1].getType() == XmlRpc::XmlRpcValue::TypeInt);
128  ROS_ASSERT(calib[index_cal][2].getType() == XmlRpc::XmlRpcValue::TypeArray);
129 
130  string joint_name_tmp = static_cast<string> (calib[index_cal][0]);
131 
132  ROS_DEBUG_STREAM(" Checking joint name: " << joint_name_tmp << " / " << joint_name_);
133  if (joint_name_tmp.compare(joint_name_) != 0)
134  {
135  continue;
136  }
137 
138  // reading the forward map:
139  if (static_cast<int> (calib[index_cal][1]) == 1)
140  {
141  joint_not_found_forward = false;
142 
143  friction_map_forward = read_one_way_map(calib[index_cal][2]);
144  }
145  else
146  {
147  joint_not_found_backward = false;
148 
149  friction_map_backward = read_one_way_map(calib[index_cal][2]);
150  }
151  }
152  }
153 
154  if (joint_not_found_forward)
155  {
156  ROS_INFO_STREAM(" No forward friction compensation map for: " << joint_name_);
157 
158  friction_map_forward = generate_flat_map();
159  }
160 
161  if (joint_not_found_backward)
162  {
163  ROS_INFO_STREAM(" No backward friction compensation map for: " << joint_name_);
164 
165  friction_map_backward = generate_flat_map();
166  }
167 
168  /*
169  ROS_INFO_STREAM(" Friction map forward: [" << joint_name_ << "]");
170  for( unsigned int i=0; i<friction_map_forward.size(); ++i )
171  ROS_INFO_STREAM(" -> position=" << friction_map_forward[i].raw_value << " compensation: " << friction_map_forward[i].calibrated_value);
172  ROS_INFO_STREAM(" Friction map backward: [" << joint_name_ << "]");
173  for( unsigned int i=0; i<friction_map_backward.size(); ++i )
174  ROS_INFO_STREAM(" -> position=" << friction_map_backward[i].raw_value << " compensation: " << friction_map_backward[i].calibrated_value);
175  */
176 
177  pair<vector<joint_calibration::Point>, vector<joint_calibration::Point> > both_maps;
178  both_maps.first = friction_map_forward;
179  both_maps.second = friction_map_backward;
180 
181  return both_maps;
182  } // end read_friction_map
183 
184  vector<joint_calibration::Point> SrFrictionCompensator::read_one_way_map(XmlRpc::XmlRpcValue &raw_map)
185  {
186  vector<joint_calibration::Point> friction_map;
187 
188  // now iterates on the calibration table for the current joint
189  for (int32_t index_table = 0; index_table < raw_map.size(); ++index_table)
190  {
191  ROS_ASSERT(raw_map[index_table].getType() == XmlRpc::XmlRpcValue::TypeArray);
192  // only 2 values per calibration point: raw and calibrated (doubles)
193  ROS_ASSERT(raw_map[index_table].size() == 2);
194  ROS_ASSERT(raw_map[index_table][0].getType() == XmlRpc::XmlRpcValue::TypeDouble);
195  ROS_ASSERT(raw_map[index_table][1].getType() == XmlRpc::XmlRpcValue::TypeDouble);
196 
197 
198  joint_calibration::Point point_tmp;
199  point_tmp.raw_value = sr_math_utils::to_rad(static_cast<double> (raw_map[index_table][0]));
200  point_tmp.calibrated_value = static_cast<double> (raw_map[index_table][1]);
201  friction_map.push_back(point_tmp);
202  }
203 
204  return friction_map;
205  }
206 
207  vector<joint_calibration::Point> SrFrictionCompensator::generate_flat_map()
208  {
209  vector<joint_calibration::Point> friction_map;
210 
211  joint_calibration::Point point_tmp;
212  point_tmp.raw_value = 0.0;
213  point_tmp.calibrated_value = 0.0;
214  friction_map.push_back(point_tmp);
215  point_tmp.raw_value = 1.0;
216  friction_map.push_back(point_tmp);
217 
218  return friction_map;
219  }
220 } // namespace sr_friction_compensation
221 
222 
223 
224 /* For the emacs weenies in the crowd.
225  Local Variables:
226  c-basic-offset: 2
227  End:
228  */
229 
230 
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)
std::size_t size(custom_string const &s)
static double to_rad(double degrees)
Type const & getType() const
Compensate the tendon friction by adding a given value depending on the sign of the force demand...
boost::scoped_ptr< shadow_robot::JointCalibration > friction_interpoler_backward
An interpolator for the backward friction map: used to compute the offset from the map...
bool getParam(const std::string &key, std::string &s) const
static double linear_interpolate_(double x, double x0, double y0, double x1, double y1)
ros::NodeHandle node_
node handle for reading the map from the parameters server.
#define ROS_DEBUG_STREAM(args)
bool hasParam(const std::string &key) const
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
#define ROS_INFO_STREAM(args)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
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...
#define ROS_ASSERT(cond)


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:30