g2o
sclam_pure_calibration.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 R. Kuemmerle, G.Grisetti, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #include <iostream>
28 #include <map>
29 #include <csignal>
30 #include <fstream>
31 
32 #include "sclam_helpers.h"
33 #include "gm2dl_io.h"
34 #include "motion_information.h"
36 
37 #include "g2o/stuff/macros.h"
38 #include "g2o/stuff/color_macros.h"
39 #include "g2o/stuff/command_args.h"
41 #include "g2o/stuff/string_tools.h"
42 #include "g2o/stuff/timeutil.h"
43 
46 
49 #include "edge_se2_pure_calib.h"
53 
54 using namespace std;
55 using namespace g2o;
56 
57 static Eigen::Vector2d linearSolution;
58 
59 class VertexBaseline : public BaseVertex<1, double>
60 {
61  public:
63 
64  virtual void setToOriginImpl() { _estimate = 1.;}
65  virtual void oplusImpl(const double* update) { _estimate += update[0];}
66  virtual bool read(std::istream&) { return false;}
67  virtual bool write(std::ostream&) const { return false;}
68 };
69 
70 class EdgeCalib : public BaseBinaryEdge<3, OdomAndLaserMotion, VertexSE2, VertexBaseline>
71 {
72  public:
74  EdgeCalib() {}
75 
76  void computeError()
77  {
78  const VertexSE2* laserOffset = static_cast<const VertexSE2*>(_vertices[0]);
79  const VertexBaseline* odomParams = dynamic_cast<const VertexBaseline*>(_vertices[1]);
80 
81  // get the calibrated motion given by the odometry
82  double rl = - odomParams->estimate() * linearSolution(0);
83  double rr = odomParams->estimate() * linearSolution(1);
84  VelocityMeasurement calibratedVelocityMeasurment(measurement().velocityMeasurement.vl() * rl,
85  measurement().velocityMeasurement.vr() * rr,
86  measurement().velocityMeasurement.dt());
87  MotionMeasurement mm = OdomConvert::convertToMotion(calibratedVelocityMeasurment, odomParams->estimate());
88  SE2 Ku_ij;
89  Ku_ij.fromVector(mm.measurement());
90 
91  SE2 laserMotionInRobotFrame = laserOffset->estimate() * measurement().laserMotion * laserOffset->estimate().inverse();
92  SE2 delta = Ku_ij.inverse() * laserMotionInRobotFrame;
93  _error = delta.toVector();
94  }
95 
96  virtual bool read(std::istream&) { return false;}
97  virtual bool write(std::ostream&) const { return false;}
98 };
99 
100 int main(int argc, char** argv)
101 {
102  bool fixLaser;
103  int maxIterations;
104  bool verbose;
105  string inputFilename;
106  string outputfilename;
107  string rawFilename;
108  string odomTestFilename;
109  string dumpGraphFilename;
110  // command line parsing
111  CommandArgs commandLineArguments;
112  commandLineArguments.param("i", maxIterations, 10, "perform n iterations");
113  commandLineArguments.param("v", verbose, false, "verbose output of the optimization process");
114  commandLineArguments.param("o", outputfilename, "", "output final version of the graph");
115  commandLineArguments.param("test", odomTestFilename, "", "apply odometry calibration to some test data");
116  commandLineArguments.param("dump", dumpGraphFilename, "", "write the graph to the disk");
117  commandLineArguments.param("fixLaser", fixLaser, false, "keep the laser offset fixed during optimization");
118  commandLineArguments.paramLeftOver("gm2dl-input", inputFilename, "", "gm2dl file which will be processed");
119  commandLineArguments.paramLeftOver("raw-log", rawFilename, "", "raw log file containing the odometry");
120 
121  commandLineArguments.parseArgs(argc, argv);
122 
123  SparseOptimizer optimizer;
124  optimizer.setVerbose(verbose);
125 
126  allocateSolverForSclam(optimizer);
127 
128  // loading
129  DataQueue odometryQueue;
130  int numLaserOdom = Gm2dlIO::readRobotLaser(rawFilename, odometryQueue);
131  if (numLaserOdom == 0) {
132  cerr << "No raw information read" << endl;
133  return 0;
134  }
135  cerr << "Read " << numLaserOdom << " laser readings from file" << endl;
136 
137  Eigen::Vector3d odomCalib(1., 1., 1.);
138  SE2 initialLaserPose;
139  DataQueue robotLaserQueue;
140  int numRobotLaser = Gm2dlIO::readRobotLaser(inputFilename, robotLaserQueue);
141  if (numRobotLaser == 0) {
142  cerr << "No robot laser read" << endl;
143  return 0;
144  } else {
145  RobotLaser* rl = dynamic_cast<RobotLaser*>(robotLaserQueue.buffer().begin()->second);
146  initialLaserPose = rl->odomPose().inverse() * rl->laserPose();
147  cerr << PVAR(initialLaserPose.toVector().transpose()) << endl;
148  }
149 
150  // adding the measurements
151  vector<MotionInformation, Eigen::aligned_allocator<MotionInformation> > motions;
152  {
153  std::map<double, RobotData*>::const_iterator it = robotLaserQueue.buffer().begin();
154  std::map<double, RobotData*>::const_iterator prevIt = it++;
155  for (; it != robotLaserQueue.buffer().end(); ++it) {
157  RobotLaser* prevLaser = dynamic_cast<RobotLaser*>(prevIt->second);
158  RobotLaser* curLaser = dynamic_cast<RobotLaser*>(it->second);
159  mi.laserMotion = prevLaser->laserPose().inverse() * curLaser->laserPose();
160  // get the motion of the robot in that time interval
161  RobotLaser* prevOdom = dynamic_cast<RobotLaser*>(odometryQueue.findClosestData(prevLaser->timestamp()));
162  RobotLaser* curOdom = dynamic_cast<RobotLaser*>(odometryQueue.findClosestData(curLaser->timestamp()));
163  mi.odomMotion = prevOdom->odomPose().inverse() * curOdom->odomPose();
164  mi.timeInterval = prevOdom->timestamp() - curOdom->timestamp();
165  prevIt = it;
166  motions.push_back(mi);
167  }
168  }
169 
170  if (1) {
171  VertexSE2* laserOffset = new VertexSE2;
172  laserOffset->setId(Gm2dlIO::ID_LASERPOSE);
173  laserOffset->setEstimate(initialLaserPose);
174  optimizer.addVertex(laserOffset);
176  odomParamsVertex->setId(Gm2dlIO::ID_ODOMCALIB);
177  odomParamsVertex->setEstimate(Eigen::Vector3d(1., 1., 1.));
178  optimizer.addVertex(odomParamsVertex);
179  for (size_t i = 0; i < motions.size(); ++i) {
180  const SE2& odomMotion = motions[i].odomMotion;
181  const SE2& laserMotion = motions[i].laserMotion;
182  const double& timeInterval = motions[i].timeInterval;
183  // add the edge
184  MotionMeasurement mm(odomMotion.translation().x(), odomMotion.translation().y(), odomMotion.rotation().angle(), timeInterval);
185  OdomAndLaserMotion meas;
186  meas.velocityMeasurement = OdomConvert::convertToVelocity(mm);
187  meas.laserMotion = laserMotion;
188  EdgeSE2PureCalib* calibEdge = new EdgeSE2PureCalib;
189  calibEdge->setVertex(0, laserOffset);
190  calibEdge->setVertex(1, odomParamsVertex);
191  calibEdge->setInformation(Eigen::Matrix3d::Identity());
192  calibEdge->setMeasurement(meas);
193  if (! optimizer.addEdge(calibEdge)) {
194  cerr << "Error adding calib edge" << endl;
195  delete calibEdge;
196  }
197  }
198 
199  if (fixLaser) {
200  cerr << "Fix position of the laser offset" << endl;
201  laserOffset->setFixed(true);
202  }
203 
204  cerr << "\nPerforming full non-linear estimation" << endl;
205  optimizer.initializeOptimization();
206  optimizer.computeActiveErrors();
207  optimizer.optimize(maxIterations);
208  cerr << "Calibrated laser offset (x, y, theta):" << laserOffset->estimate().toVector().transpose() << endl;
209  odomCalib = odomParamsVertex->estimate();
210  cerr << "Odometry parameters (scaling factors (v_l, v_r, b)): " << odomParamsVertex->estimate().transpose() << endl;
211  optimizer.clear();
212  }
213 
214  // linear least squares for some parameters
215  {
216  Eigen::MatrixXd A(motions.size(), 2);
217  Eigen::VectorXd x(motions.size());
218  for (size_t i = 0; i < motions.size(); ++i) {
219  const SE2& odomMotion = motions[i].odomMotion;
220  const SE2& laserMotion = motions[i].laserMotion;
221  const double& timeInterval = motions[i].timeInterval;
222  MotionMeasurement mm(odomMotion.translation().x(), odomMotion.translation().y(), odomMotion.rotation().angle(), timeInterval);
223  VelocityMeasurement velMeas = OdomConvert::convertToVelocity(mm);
224  A(i, 0) = velMeas.vl() * timeInterval;
225  A(i, 1) = velMeas.vr() * timeInterval;
226  x(i) = laserMotion.rotation().angle();
227  }
228  //linearSolution = (A.transpose() * A).inverse() * A.transpose() * x;
229  linearSolution = A.colPivHouseholderQr().solve(x);
230  //cout << PVAR(linearSolution.transpose()) << endl;
231  }
232 
233  //constructing non-linear least squares
234  VertexSE2* laserOffset = new VertexSE2;
235  laserOffset->setId(Gm2dlIO::ID_LASERPOSE);
236  laserOffset->setEstimate(initialLaserPose);
237  optimizer.addVertex(laserOffset);
238  VertexBaseline* odomParamsVertex = new VertexBaseline;
239  odomParamsVertex->setId(Gm2dlIO::ID_ODOMCALIB);
240  odomParamsVertex->setEstimate(1.);
241  optimizer.addVertex(odomParamsVertex);
242  for (size_t i = 0; i < motions.size(); ++i) {
243  const SE2& odomMotion = motions[i].odomMotion;
244  const SE2& laserMotion = motions[i].laserMotion;
245  const double& timeInterval = motions[i].timeInterval;
246  // add the edge
247  MotionMeasurement mm(odomMotion.translation().x(), odomMotion.translation().y(), odomMotion.rotation().angle(), timeInterval);
248  OdomAndLaserMotion meas;
249  meas.velocityMeasurement = OdomConvert::convertToVelocity(mm);
250  meas.laserMotion = laserMotion;
251  EdgeCalib* calibEdge = new EdgeCalib;
252  calibEdge->setVertex(0, laserOffset);
253  calibEdge->setVertex(1, odomParamsVertex);
254  calibEdge->setInformation(Eigen::Matrix3d::Identity());
255  calibEdge->setMeasurement(meas);
256  if (! optimizer.addEdge(calibEdge)) {
257  cerr << "Error adding calib edge" << endl;
258  delete calibEdge;
259  }
260  }
261 
262  if (fixLaser) {
263  cerr << "Fix position of the laser offset" << endl;
264  laserOffset->setFixed(true);
265  }
266 
267  cerr << "\nPerforming partial non-linear estimation" << endl;
268  optimizer.initializeOptimization();
269  optimizer.computeActiveErrors();
270  optimizer.optimize(maxIterations);
271  cerr << "Calibrated laser offset (x, y, theta):" << laserOffset->estimate().toVector().transpose() << endl;
272  odomCalib(0) = -1. * linearSolution(0) * odomParamsVertex->estimate();
273  odomCalib(1) = linearSolution(1) * odomParamsVertex->estimate();
274  odomCalib(2) = odomParamsVertex->estimate();
275  cerr << "Odometry parameters (scaling factors (v_l, v_r, b)): " << odomCalib.transpose() << endl;
276 
277  {
278  SE2 closedFormLaser;
279  Eigen::Vector3d closedFormOdom;
280  ClosedFormCalibration::calibrate(motions, closedFormLaser, closedFormOdom);
281  cerr << "\nObtaining closed form solution" << endl;
282  cerr << "Calibrated laser offset (x, y, theta):" << closedFormLaser.toVector().transpose() << endl;
283  cerr << "Odometry parameters (scaling factors (v_l, v_r, b)): " << closedFormOdom.transpose() << endl;
284  }
285 
286  if (dumpGraphFilename.size() > 0) {
287  cerr << "Writing " << dumpGraphFilename << " ... ";
288  optimizer.save(dumpGraphFilename.c_str());
289  cerr << "done." << endl;
290  }
291 
292  // optional input of a separate file for applying the odometry calibration
293  if (odomTestFilename.size() > 0) {
294 
295  DataQueue testRobotLaserQueue;
296  int numTestOdom = Gm2dlIO::readRobotLaser(odomTestFilename, testRobotLaserQueue);
297  if (numTestOdom == 0) {
298  cerr << "Unable to read test data" << endl;
299  } else {
300 
301  ofstream rawStream("odometry_raw.txt");
302  ofstream calibratedStream("odometry_calibrated.txt");
303  RobotLaser* prev = dynamic_cast<RobotLaser*>(testRobotLaserQueue.buffer().begin()->second);
304  SE2 prevCalibratedPose = prev->odomPose();
305 
306  for (DataQueue::Buffer::const_iterator it = testRobotLaserQueue.buffer().begin(); it != testRobotLaserQueue.buffer().end(); ++it) {
307  RobotLaser* cur = dynamic_cast<RobotLaser*>(it->second);
308  assert(cur);
309 
310  double dt = cur->timestamp() - prev->timestamp();
311  SE2 motion = prev->odomPose().inverse() * cur->odomPose();
312 
313  // convert to velocity measurement
314  MotionMeasurement motionMeasurement(motion.translation().x(), motion.translation().y(), motion.rotation().angle(), dt);
315  VelocityMeasurement velocityMeasurement = OdomConvert::convertToVelocity(motionMeasurement);
316 
317  // apply calibration
318  VelocityMeasurement calibratedVelocityMeasurment = velocityMeasurement;
319  calibratedVelocityMeasurment.setVl(odomCalib(0) * calibratedVelocityMeasurment.vl());
320  calibratedVelocityMeasurment.setVr(odomCalib(1) * calibratedVelocityMeasurment.vr());
321  MotionMeasurement mm = OdomConvert::convertToMotion(calibratedVelocityMeasurment, odomCalib(2));
322 
323  // combine calibrated odometry with the previous pose
324  SE2 remappedOdom;
325  remappedOdom.fromVector(mm.measurement());
326  SE2 calOdomPose = prevCalibratedPose * remappedOdom;
327 
328  // write output
329  rawStream << prev->odomPose().translation().x() << " " << prev->odomPose().translation().y() << " " << prev->odomPose().rotation().angle() << endl;
330  calibratedStream << calOdomPose.translation().x() << " " << calOdomPose.translation().y() << " " << calOdomPose.rotation().angle() << endl;
331 
332  prevCalibratedPose = calOdomPose;
333  prev = cur;
334  }
335  }
336 
337  }
338 
339  return 0;
340 }
const SE2 & odomPose() const
Definition: robot_laser.h:53
const Vector3D & measurement() const
const Buffer & buffer() const
Definition: data_queue.h:56
Command line parsing of argc and argv.
Definition: command_args.h:46
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
int main(int argc, char **argv)
virtual bool read(std::istream &)
read the vertex from a stream, i.e., the internal state of the vertex
laser measurement obtained by a robot
Definition: robot_laser.h:42
int optimize(int iterations, bool online=false)
calibrate odometry and laser based on a set of measurements
represent SE2
Definition: se2.h:40
Templatized BaseVertex.
Definition: base_vertex.h:50
virtual bool write(std::ostream &) const
write the vertex to a stream
virtual void setMeasurement(const Measurement &m)
Definition: base_edge.h:76
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
static Eigen::Vector2d linearSolution
void setVertex(size_t i, Vertex *v)
Definition: hyper_graph.h:194
double timestamp() const
Definition: robot_data.h:47
virtual bool read(std::istream &)
read the vertex from a stream, i.e., the internal state of the vertex
SE2 laserPose() const
Definition: robot_laser.h:52
utility functions for handling time related stuff
VelocityMeasurement velocityMeasurement
virtual void oplusImpl(const double *update)
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
bool parseArgs(int argc, char **argv, bool exitOnError=true)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
void setVerbose(bool verbose)
velocity measurement of a differential robot
void fromVector(const Vector3D &v)
assign from a 3D vector (x, y, theta)
Definition: se2.h:103
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
EIGEN_STRONG_INLINE void setInformation(const InformationType &information)
Definition: base_edge.h:69
A 2D odometry measurement expressed as a transformation.
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
a simple queue to store data and retrieve based on a timestamp
Definition: data_queue.h:40
virtual bool write(std::ostream &) const
write the vertex to a stream
void allocateSolverForSclam(SparseOptimizer &optimizer, bool levenberg)
virtual void setToOriginImpl()
sets the node to the origin (used in the multilevel stuff)
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
SE2 inverse() const
invert :-)
Definition: se2.h:82
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
RobotData * findClosestData(double timestamp) const
Definition: data_queue.cpp:41
const Vector2D & translation() const
translational component
Definition: se2.h:54
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)