calibration_offset_parser.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2019 Michael Ferguson
3  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 // Author: Michael Ferguson
19 
20 #include <fstream>
21 #include <string>
22 #include <map>
23 #include <tinyxml.h>
24 #include <boost/algorithm/string.hpp>
25 #include <boost/lexical_cast.hpp>
27 #include <robot_calibration/models/chain.h> // for rotation functions
28 
29 namespace robot_calibration
30 {
31 
33 {
34  num_free_params_ = 0;
35 }
36 
37 bool CalibrationOffsetParser::add(const std::string name)
38 {
39  double value = 0.0;
40 
41  // Check against parameters
42  for (size_t i = 0; i < parameter_names_.size(); ++i)
43  {
44  if (parameter_names_[i] == name)
45  {
46  if (i < num_free_params_)
47  {
48  // This is already a free param, don't re-add
49  return false;
50  }
51  // Get the current value
52  value = parameter_offsets_[i];
53  // Remove the non-free-param version
54  parameter_names_.erase(parameter_names_.begin() + i);
55  parameter_offsets_.erase(parameter_offsets_.begin() + i);
56  }
57  }
58 
59  // Add the parameter at end of current free params
60  parameter_names_.insert(parameter_names_.begin() + num_free_params_, name);
63  return true;
64 }
65 
67  const std::string name,
68  bool calibrate_x, bool calibrate_y, bool calibrate_z,
69  bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw)
70 {
71  frame_names_.push_back(name);
72  if (calibrate_x)
73  add(std::string(name).append("_x"));
74  if (calibrate_y)
75  add(std::string(name).append("_y"));
76  if (calibrate_z)
77  add(std::string(name).append("_z"));
78 
79  // These don't really correspond to rpy unless only one is set
80  // TODO: check that we do either roll, pitch or yaw, or all 3 (never just 2)
81  if (calibrate_roll)
82  add(std::string(name).append("_a"));
83  if (calibrate_pitch)
84  add(std::string(name).append("_b"));
85  if (calibrate_yaw)
86  add(std::string(name).append("_c"));
87 
88  return true;
89 }
90 
91 bool CalibrationOffsetParser::set(const std::string name, double value)
92 {
93  for (size_t i = 0; i < num_free_params_; ++i)
94  {
95  if (parameter_names_[i] == name)
96  {
97  parameter_offsets_[i] = value;
98  return true;
99  }
100  }
101  return false;
102 }
103 
105  const std::string name,
106  double x, double y, double z,
107  double roll, double pitch, double yaw)
108 {
109  // Get axis-magnitude
110  double a, b, c;
111  KDL::Rotation r = KDL::Rotation::RPY(roll, pitch, yaw);
112  axis_magnitude_from_rotation(r, a, b, c);
113 
114  // Set values
115  set(std::string(name).append("_x"), x);
116  set(std::string(name).append("_y"), y);
117  set(std::string(name).append("_z"), z);
118  set(std::string(name).append("_a"), a);
119  set(std::string(name).append("_b"), b);
120  set(std::string(name).append("_c"), c);
121 
122  return true;
123 }
124 
125 bool CalibrationOffsetParser::initialize(double* free_params)
126 {
127  for (size_t i = 0; i < num_free_params_; ++i)
128  free_params[i] = parameter_offsets_[i];
129  return true;
130 }
131 
132 bool CalibrationOffsetParser::update(const double* const free_params)
133 {
134  for (size_t i = 0; i < num_free_params_; ++i)
135  parameter_offsets_[i] = free_params[i];
136  return true;
137 }
138 
139 double CalibrationOffsetParser::get(const std::string name) const
140 {
141  for (size_t i = 0; i < parameter_names_.size(); ++i)
142  {
143  if (parameter_names_[i] == name)
144  return parameter_offsets_[i];
145  }
146  // Not calibrating this
147  return 0.0;
148 }
149 
150 bool CalibrationOffsetParser::getFrame(const std::string name, KDL::Frame& offset) const
151 {
152  // Don't bother with following computation if this isn't a calibrated frame.
153  bool has_offset = false;
154  for (size_t i = 0; i < frame_names_.size(); ++i)
155  {
156  if (frame_names_[i] == name)
157  {
158  has_offset = true;
159  break;
160  }
161  }
162 
163  if (!has_offset)
164  return false;
165 
166  offset.p.x(get(std::string(name).append("_x")));
167  offset.p.y(get(std::string(name).append("_y")));
168  offset.p.z(get(std::string(name).append("_z")));
169 
171  get(std::string(name).append("_a")),
172  get(std::string(name).append("_b")),
173  get(std::string(name).append("_c")));
174 
175  return true;
176 }
177 
179 {
180  return num_free_params_;
181 }
182 
184 {
185  num_free_params_ = 0;
186  return true;
187 }
188 
189 bool CalibrationOffsetParser::loadOffsetYAML(const std::string& filename)
190 {
191  std::string line;
192  std::ifstream f(filename.c_str());
193  while (std::getline(f, line))
194  {
195  std::istringstream str(line.c_str());
196  std::string param;
197  double value;
198  if (str >> param >> value)
199  {
200  // Remove the ":"
201  param.erase(param.size() - 1);
202  std::cout << "Loading '" << param << "' with value " << value << std::endl;
203  set(param, value);
204  }
205  }
206  f.close();
207  return true;
208 }
209 
211 {
212  std::stringstream ss;
213  for (size_t i = 0; i < parameter_names_.size(); ++i)
214  {
215  ss << parameter_names_[i] << ": " << parameter_offsets_[i] << std::endl;
216  }
217  return ss.str();
218 }
219 
220 std::string CalibrationOffsetParser::updateURDF(const std::string &urdf)
221 {
222  const double precision = 8;
223 
224  TiXmlDocument xml_doc;
225  xml_doc.Parse(urdf.c_str());
226 
227  TiXmlElement *robot_xml = xml_doc.FirstChildElement("robot");
228  if (!robot_xml)
229  {
230  // TODO: error notification? We should never get here since URDF parse
231  // at beginning of calibration will fail
232  return urdf;
233  }
234 
235  // Update each joint
236  for (TiXmlElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint"))
237  {
238  const char * name = joint_xml->Attribute("name");
239 
240  // Is there a joint calibration needed?
241  double offset = get(std::string(name));
242  if (offset != 0.0)
243  {
244  TiXmlElement *calibration_xml = joint_xml->FirstChildElement("calibration");
245  if (calibration_xml)
246  {
247  // Existing calibration, update rising attribute
248  const char * rising_position_str = calibration_xml->Attribute("rising");
249  if (rising_position_str != NULL)
250  {
251  try
252  {
253  offset += double(boost::lexical_cast<double>(rising_position_str));
254  calibration_xml->SetDoubleAttribute("rising", offset);
255  }
256  catch (boost::bad_lexical_cast &e)
257  {
258  // TODO: error
259  }
260  }
261  else
262  {
263  // TODO: error
264  }
265  }
266  else
267  {
268  // No calibration previously, add an element + attribute
269  calibration_xml = new TiXmlElement("calibration");
270  calibration_xml->SetDoubleAttribute("rising", offset);
271  TiXmlNode * calibration = calibration_xml->Clone();
272  joint_xml->InsertEndChild(*calibration);
273  }
274  }
275 
276  KDL::Frame frame_offset;
277  bool has_update = getFrame(name, frame_offset);
278  if (has_update)
279  {
280  std::vector<double> xyz(3, 0.0);
281  std::vector<double> rpy(3, 0.0);
282 
283  // String streams for output
284  std::stringstream xyz_ss, rpy_ss;
285 
286  TiXmlElement *origin_xml = joint_xml->FirstChildElement("origin");
287  if (origin_xml)
288  {
289  // Update existing origin
290  const char * xyz_str = origin_xml->Attribute("xyz");
291  const char * rpy_str = origin_xml->Attribute("rpy");
292 
293  // Split out xyz of origin, break into 3 strings
294  std::vector<std::string> xyz_pieces;
295  boost::split(xyz_pieces, xyz_str, boost::is_any_of(" "));
296 
297  // Split out rpy of origin, break into 3 strings
298  std::vector<std::string> rpy_pieces;
299  boost::split(rpy_pieces, rpy_str, boost::is_any_of(" "));
300 
302  if (xyz_pieces.size() == 3)
303  {
304  origin.p = KDL::Vector(boost::lexical_cast<double>(xyz_pieces[0]), boost::lexical_cast<double>(xyz_pieces[1]), boost::lexical_cast<double>(xyz_pieces[2]));
305  }
306 
307  if (rpy_pieces.size() == 3)
308  {
309  origin.M = KDL::Rotation::RPY(boost::lexical_cast<double>(rpy_pieces[0]), boost::lexical_cast<double>(rpy_pieces[1]), boost::lexical_cast<double>(rpy_pieces[2]));
310  }
311 
312  // Update
313  origin = origin * frame_offset;
314 
315  xyz[0] = origin.p.x();
316  xyz[1] = origin.p.y();
317  xyz[2] = origin.p.z();
318 
319  // Get roll, pitch, yaw about fixed axis
320  origin.M.GetRPY(rpy[0], rpy[1], rpy[2]);
321 
322  // Update xyz
323  for (int i = 0; i < 3; ++i)
324  {
325  if (i > 0)
326  xyz_ss << " ";
327  xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
328  }
329 
330  // Update rpy
331  for (int i = 0; i < 3; ++i)
332  {
333  if (i > 0)
334  rpy_ss << " ";
335  rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
336  }
337 
338  // Update xml
339  origin_xml->SetAttribute("xyz", xyz_ss.str());
340  origin_xml->SetAttribute("rpy", rpy_ss.str());
341  }
342  else
343  {
344  xyz[0] = frame_offset.p.x();
345  xyz[1] = frame_offset.p.y();
346  xyz[2] = frame_offset.p.z();
347 
348  // Get roll, pitch, yaw about fixed axis
349  frame_offset.M.GetRPY(rpy[0], rpy[1], rpy[2]);
350 
351  // No existing origin, create an element with attributes
352  origin_xml = new TiXmlElement("origin");
353 
354  // Create xyz
355  for (int i = 0; i < 3; ++i)
356  {
357  if (i > 0)
358  xyz_ss << " ";
359  xyz_ss << std::fixed << std::setprecision(precision) << xyz[i];
360  }
361  origin_xml->SetAttribute("xyz", xyz_ss.str());
362 
363  // Create rpy
364  for (int i = 0; i < 3; ++i)
365  {
366  if (i > 0)
367  rpy_ss << " ";
368  rpy_ss << std::fixed << std::setprecision(precision) << rpy[i];
369  }
370  origin_xml->SetAttribute("rpy", rpy_ss.str());
371 
372  TiXmlNode * origin = origin_xml->Clone();
373  joint_xml->InsertEndChild(*origin);
374  }
375  }
376  }
377 
378  // Print to a string
379  TiXmlPrinter printer;
380  printer.SetIndent(" ");
381  xml_doc.Accept(&printer);
382  std::string new_urdf = printer.CStr();
383 
384  return new_urdf;
385 }
386 
387 } // namespace robot_calibration
bool param(const std::string &param_name, T &param_val, const T &default_val)
f
bool set(const std::string name, double value)
Set the values for a single parameter.
bool getFrame(const std::string name, KDL::Frame &offset) const
Get the offset for a frame calibration.
double z() const
Rotation M
std::string getOffsetYAML()
Get all the current offsets as a YAML.
bool initialize(double *free_params)
Initialize the free_params.
bool add(const std::string name)
Tell the parser we wish to calibrate an active joint or other single parameter.
static Rotation RPY(double roll, double pitch, double yaw)
double y() const
bool setFrame(const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
Set the values for a frame.
double x() const
static Rotation Identity()
Calibration code lives under this namespace.
double get(const std::string name) const
Get the offset.
void GetRPY(double &roll, double &pitch, double &yaw) const
void axis_magnitude_from_rotation(const KDL::Rotation &r, double &x, double &y, double &z)
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude.
Definition: models.cpp:261
KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z)
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation.
Definition: models.cpp:248
bool addFrame(const std::string name, bool calibrate_x, bool calibrate_y, bool calibrate_z, bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw)
Tell the parser we wish to calibrate a fixed joint.
std::string updateURDF(const std::string &urdf)
Update the urdf with the new offsets.
bool reset()
Clear free parameters, but retain values for multi-step calirations.
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
bool loadOffsetYAML(const std::string &filename)
Load all the current offsets from a YAML.
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.
static Vector Zero()


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30