g2o
sclam_odom_laser.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 
35 #include "g2o/stuff/macros.h"
36 #include "g2o/stuff/color_macros.h"
37 #include "g2o/stuff/command_args.h"
39 #include "g2o/stuff/string_tools.h"
40 #include "g2o/stuff/timeutil.h"
41 
44 
50 
51 using namespace std;
52 using namespace g2o;
53 using namespace Eigen;
54 
55 static bool hasToStop = false;
56 
57 void sigquit_handler(int sig)
58 {
59  if (sig == SIGINT) {
60  hasToStop = true;
61  static int cnt = 0;
62  if (cnt++ == 2) {
63  cerr << " forcing exit" << endl;
64  exit(1);
65  }
66  }
67 }
68 
69 int main(int argc, char** argv)
70 {
71  bool fixLaser;
72  int maxIterations;
73  bool verbose;
74  string inputFilename;
75  string outputfilename;
76  string rawFilename;
77  string odomTestFilename;
78  string dumpGraphFilename;
79  // command line parsing
80  CommandArgs commandLineArguments;
81  commandLineArguments.param("i", maxIterations, 10, "perform n iterations");
82  commandLineArguments.param("v", verbose, false, "verbose output of the optimization process");
83  commandLineArguments.param("o", outputfilename, "", "output final version of the graph");
84  commandLineArguments.param("test", odomTestFilename, "", "apply odometry calibration to some test data");
85  commandLineArguments.param("dump", dumpGraphFilename, "", "write the graph to the disk");
86  commandLineArguments.param("fixLaser", fixLaser, false, "keep the laser offset fixed during optimization");
87  commandLineArguments.paramLeftOver("gm2dl-input", inputFilename, "", "gm2dl file which will be processed");
88  commandLineArguments.paramLeftOver("raw-log", rawFilename, "", "raw log file containing the odometry");
89 
90  commandLineArguments.parseArgs(argc, argv);
91 
92  SparseOptimizer optimizer;
93  optimizer.setVerbose(verbose);
94  optimizer.setForceStopFlag(&hasToStop);
95 
96  allocateSolverForSclam(optimizer);
97 
98  // loading
99  if (! Gm2dlIO::readGm2dl(inputFilename, optimizer, false)) {
100  cerr << "Error while loading gm2dl file" << endl;
101  }
102  DataQueue robotLaserQueue;
103  int numLaserOdom = Gm2dlIO::readRobotLaser(rawFilename, robotLaserQueue);
104  if (numLaserOdom == 0) {
105  cerr << "No raw information read" << endl;
106  return 0;
107  }
108  cerr << "Read " << numLaserOdom << " laser readings from file" << endl;
109 
110  bool gaugeFreedom = optimizer.gaugeFreedom();
111 
112  OptimizableGraph::Vertex* gauge = optimizer.findGauge();
113  if (gaugeFreedom) {
114  if (! gauge) {
115  cerr << "# cannot find a vertex to fix in this thing" << endl;
116  return 2;
117  } else {
118  cerr << "# graph is fixed by node " << gauge->id() << endl;
119  gauge->setFixed(true);
120  }
121  } else {
122  cerr << "# graph is fixed by priors" << endl;
123  }
124 
125  addOdometryCalibLinksDifferential(optimizer, robotLaserQueue);
126 
127  // sanity check
128  HyperDijkstra d(&optimizer);
130  d.shortestPaths(gauge, &f);
131  //cerr << PVAR(d.visited().size()) << endl;
132 
133  if (d.visited().size()!=optimizer.vertices().size()) {
134  cerr << CL_RED("Warning: d.visited().size() != optimizer.vertices().size()") << endl;
135  cerr << "visited: " << d.visited().size() << endl;
136  cerr << "vertices: " << optimizer.vertices().size() << endl;
137  if (1)
138  for (SparseOptimizer::VertexIDMap::const_iterator it = optimizer.vertices().begin(); it != optimizer.vertices().end(); ++it) {
139  OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(it->second);
140  if (d.visited().count(v) == 0) {
141  cerr << "\t unvisited vertex " << it->first << " " << (void*)v << endl;
142  v->setFixed(true);
143  }
144  }
145  }
146 
147  for (SparseOptimizer::VertexIDMap::const_iterator it = optimizer.vertices().begin(); it != optimizer.vertices().end(); ++it) {
148  OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(it->second);
149  if (v->fixed()) {
150  cerr << "\t fixed vertex " << it->first << endl;
151  }
152  }
153 
154  VertexSE2* laserOffset = dynamic_cast<VertexSE2*>(optimizer.vertex(Gm2dlIO::ID_LASERPOSE));
155  VertexOdomDifferentialParams* odomParamsVertex = dynamic_cast<VertexOdomDifferentialParams*>(optimizer.vertex(Gm2dlIO::ID_ODOMCALIB));
156 
157  if (fixLaser) {
158  cerr << "Fix position of the laser offset" << endl;
159  laserOffset->setFixed(true);
160  }
161 
162  signal(SIGINT, sigquit_handler);
163  cerr << "Doing full estimation" << endl;
164  optimizer.initializeOptimization();
165  optimizer.computeActiveErrors();
166  cerr << "Initial chi2 = " << FIXED(optimizer.chi2()) << endl;
167 
168  int i=optimizer.optimize(maxIterations);
169  if (maxIterations > 0 && !i){
170  cerr << "optimize failed, result might be invalid" << endl;
171  }
172 
173  if (laserOffset) {
174  cerr << "Calibrated laser offset (x, y, theta):" << laserOffset->estimate().toVector().transpose() << endl;
175  }
176 
177  if (odomParamsVertex) {
178  cerr << "Odometry parameters (scaling factors (v_l, v_r, b)): " << odomParamsVertex->estimate().transpose() << endl;
179  }
180 
181  cerr << "vertices: " << optimizer.vertices().size() << endl;
182  cerr << "edges: " << optimizer.edges().size() << endl;
183 
184  if (dumpGraphFilename.size() > 0) {
185  cerr << "Writing " << dumpGraphFilename << " ... ";
186  optimizer.save(dumpGraphFilename.c_str());
187  cerr << "done." << endl;
188  }
189 
190  // optional input of a seperate file for applying the odometry calibration
191  if (odomTestFilename.size() > 0) {
192 
193  DataQueue testRobotLaserQueue;
194  int numTestOdom = Gm2dlIO::readRobotLaser(odomTestFilename, testRobotLaserQueue);
195  if (numTestOdom == 0) {
196  cerr << "Unable to read test data" << endl;
197  } else {
198 
199  ofstream rawStream("odometry_raw.txt");
200  ofstream calibratedStream("odometry_calibrated.txt");
201  const Vector3d& odomCalib = odomParamsVertex->estimate();
202  RobotLaser* prev = dynamic_cast<RobotLaser*>(testRobotLaserQueue.buffer().begin()->second);
203  SE2 prevCalibratedPose = prev->odomPose();
204 
205  for (DataQueue::Buffer::const_iterator it = testRobotLaserQueue.buffer().begin(); it != testRobotLaserQueue.buffer().end(); ++it) {
206  RobotLaser* cur = dynamic_cast<RobotLaser*>(it->second);
207  assert(cur);
208 
209  double dt = cur->timestamp() - prev->timestamp();
210  SE2 motion = prev->odomPose().inverse() * cur->odomPose();
211 
212  // convert to velocity measurment
213  MotionMeasurement motionMeasurement(motion.translation().x(), motion.translation().y(), motion.rotation().angle(), dt);
214  VelocityMeasurement velocityMeasurement = OdomConvert::convertToVelocity(motionMeasurement);
215 
216  // apply calibration
217  VelocityMeasurement calibratedVelocityMeasurment = velocityMeasurement;
218  calibratedVelocityMeasurment.setVl(odomCalib(0) * calibratedVelocityMeasurment.vl());
219  calibratedVelocityMeasurment.setVr(odomCalib(1) * calibratedVelocityMeasurment.vr());
220  MotionMeasurement mm = OdomConvert::convertToMotion(calibratedVelocityMeasurment, odomCalib(2));
221 
222  // combine calibrated odometry with the previous pose
223  SE2 remappedOdom;
224  remappedOdom.fromVector(mm.measurement());
225  SE2 calOdomPose = prevCalibratedPose * remappedOdom;
226 
227  // write output
228  rawStream << prev->odomPose().translation().x() << " " << prev->odomPose().translation().y() << " " << prev->odomPose().rotation().angle() << endl;
229  calibratedStream << calOdomPose.translation().x() << " " << calOdomPose.translation().y() << " " << calOdomPose.rotation().angle() << endl;
230 
231  prevCalibratedPose = calOdomPose;
232  prev = cur;
233  }
234  }
235 
236  }
237 
238  if (outputfilename.size() > 0) {
239  Gm2dlIO::updateLaserData(optimizer);
240  cerr << "Writing " << outputfilename << " ... ";
241  bool writeStatus = Gm2dlIO::writeGm2dl(outputfilename, optimizer);
242  cerr << (writeStatus ? "done." : "failed") << endl;
243  }
244 
245  return 0;
246 }
const SE2 & odomPose() const
Definition: robot_laser.h:53
int id() const
returns the id
Definition: hyper_graph.h:148
const Vector3D & measurement() const
int main(int argc, char **argv)
const Buffer & buffer() const
Definition: data_queue.h:56
Command line parsing of argc and argv.
Definition: command_args.h:46
HyperGraph::VertexSet & visited()
static bool hasToStop
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
laser measurement obtained by a robot
Definition: robot_laser.h:42
int optimize(int iterations, bool online=false)
#define CL_RED(s)
Definition: color_macros.h:46
represent SE2
Definition: se2.h:40
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
double timestamp() const
Definition: robot_data.h:47
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
Vertex * vertex(int id)
returns the vertex number id appropriately casted
utility functions for handling time related stuff
virtual Vertex * findGauge()
finds a gauge in the graph to remove the undefined dof.
double chi2() const
returns the chi2 of the current configuration
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 shortestPaths(HyperGraph::Vertex *v, HyperDijkstra::CostFunction *cost, double maxDistance=std::numeric_limits< double >::max(), double comparisonConditioner=1e-3, bool directed=false, double maxEdgeCost=std::numeric_limits< double >::max())
void setVerbose(bool verbose)
const EdgeSet & edges() const
Definition: hyper_graph.h:230
velocity measurement of a differential robot
void fromVector(const Vector3D &v)
assign from a 3D vector (x, y, theta)
Definition: se2.h:103
void setForceStopFlag(bool *flag)
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
A 2D odometry measurement expressed as a transformation.
void addOdometryCalibLinksDifferential(SparseOptimizer &optimizer, const DataQueue &odomData)
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void sigquit_handler(int sig)
a simple queue to store data and retrieve based on a timestamp
Definition: data_queue.h:40
A general case Vertex for optimization.
void allocateSolverForSclam(SparseOptimizer &optimizer, bool levenberg)
bool fixed() const
true => this node is fixed during the optimization
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)
const Vector2D & translation() const
translational component
Definition: se2.h:54