g2o
sclam_helpers.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 "sclam_helpers.h"
28 
29 #include "gm2dl_io.h"
30 
37 
39 #include "g2o/core/block_solver.h"
43 
44 #include <iostream>
45 using namespace std;
46 using namespace Eigen;
47 
48 namespace g2o {
49 
50  static const double INFORMATION_SCALING_ODOMETRY = 100;
51 
53  {
54  SparseOptimizer::Vertex* odomParamsVertex = 0;
55  odomParamsVertex = new VertexOdomDifferentialParams;
56  odomParamsVertex->setToOrigin();
57  odomParamsVertex->setId(Gm2dlIO::ID_ODOMCALIB);
58  optimizer.addVertex(odomParamsVertex);
59 
60  SparseOptimizer::EdgeSet odomCalibEdges;
61  for (SparseOptimizer::EdgeSet::const_iterator it = optimizer.edges().begin(); it != optimizer.edges().end(); ++it) {
62  EdgeSE2SensorCalib* scanmatchEdge = dynamic_cast<EdgeSE2SensorCalib*>(*it);
63  if (! scanmatchEdge)
64  continue;
65 
66  VertexSE2* r1 = dynamic_cast<VertexSE2*>(scanmatchEdge->vertices()[0]);
67  VertexSE2* r2 = dynamic_cast<VertexSE2*>(scanmatchEdge->vertices()[1]);
68  if (r2->id() - r1->id() != 1) { // ignore non-incremental edges
69  continue;
70  }
71 
72  RobotLaser* rl1 = dynamic_cast<RobotLaser*>(r1->userData());
73  RobotLaser* rl2 = dynamic_cast<RobotLaser*>(r2->userData());
74  RobotLaser* odom1 = dynamic_cast<RobotLaser*>(odomData.findClosestData(rl1->timestamp()));
75  RobotLaser* odom2 = dynamic_cast<RobotLaser*>(odomData.findClosestData(rl2->timestamp()));
76 
77  if (fabs(rl1->timestamp() - rl2->timestamp()) < 1e-7) {
78  cerr << "strange egde " << r1->id() << " <-> " << r2->id() << endl;
79  cerr << FIXED(PVAR(rl1->timestamp()) << "\t " << PVAR(rl2->timestamp())) << endl;
80  cerr << FIXED(PVAR(odom1->timestamp()) << "\t " << PVAR(odom2->timestamp())) << endl;
81  }
82 
83  //cerr << PVAR(odom1->odomPose().toVector().transpose()) << endl;
84 
85  SE2 odomMotion = odom1->odomPose().inverse() * odom2->odomPose();
86  //cerr << PVAR(odomMotion.toVector().transpose()) << endl;
87  //cerr << PVAR(scanmatchEdge->measurement().toVector().transpose()) << endl;
88 
90  e->vertices()[0] = r1;
91  e->vertices()[1] = r2;
92  e->vertices()[2] = odomParamsVertex;
93 
94  MotionMeasurement mm(odomMotion.translation().x(), odomMotion.translation().y(), odomMotion.rotation().angle(), odom2->timestamp() - odom1->timestamp());
95  e->setMeasurement(OdomConvert::convertToVelocity(mm));
96  //cerr << PVAR(e->measurement()) << endl;
97 
98  e->information() = Matrix3d::Identity() * INFORMATION_SCALING_ODOMETRY;
99  odomCalibEdges.insert(e);
100 
101  }
102 
103  for (SparseOptimizer::EdgeSet::iterator it = odomCalibEdges.begin(); it != odomCalibEdges.end(); ++it)
104  optimizer.addEdge(dynamic_cast<OptimizableGraph::Edge*>(*it));
105 
106  }
107 
108  void allocateSolverForSclam(SparseOptimizer& optimizer, bool levenberg)
109  {
110  typedef BlockSolver< BlockSolverTraits<-1, -1> > SclamBlockSolver;
112 
113  SclamLinearSolver* linearSolver = new SclamLinearSolver();
114  linearSolver->setBlockOrdering(false);
115  SclamBlockSolver* blockSolver = new SclamBlockSolver(linearSolver);
116  OptimizationAlgorithm* solver = 0;
117  if (levenberg) {
118  solver = new OptimizationAlgorithmLevenberg(blockSolver);
119  } else {
120  solver = new OptimizationAlgorithmGaussNewton(blockSolver);
121  }
122  optimizer.setAlgorithm(solver);
123  }
124 
125 } // end namespace
const SE2 & odomPose() const
Definition: robot_laser.h:53
int id() const
returns the id
Definition: hyper_graph.h:148
const Data * userData() const
the user data associated with this vertex
Definition: hyper_graph.h:126
scanmatch measurement that also calibrates an offset for the laser
Implementation of the Levenberg Algorithm.
laser measurement obtained by a robot
Definition: robot_laser.h:42
represent SE2
Definition: se2.h:40
traits to summarize the properties of the fixed size optimization problem
Definition: block_solver.h:43
virtual void setMeasurement(const Measurement &m)
Definition: base_edge.h:76
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
double timestamp() const
Definition: robot_data.h:47
virtual void setId(int newId)
Definition: hyper_graph.h:149
Implementation of the Gauss Newton Algorithm.
std::set< Edge * > EdgeSet
Definition: hyper_graph.h:135
const VertexContainer & vertices() const
Definition: hyper_graph.h:178
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
linear solver which uses CSparse
const EdgeSet & edges() const
Definition: hyper_graph.h:230
void setAlgorithm(OptimizationAlgorithm *algorithm)
A 2D odometry measurement expressed as a transformation.
void addOdometryCalibLinksDifferential(SparseOptimizer &optimizer, const DataQueue &odomData)
static const double INFORMATION_SCALING_ODOMETRY
a simple queue to store data and retrieve based on a timestamp
Definition: data_queue.h:40
abstract Vertex, your types must derive from that one
Definition: hyper_graph.h:142
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
void allocateSolverForSclam(SparseOptimizer &optimizer, bool levenberg)
Implementation of a solver operating on the blocks of the Hessian.
Definition: block_solver.h:96
SE2 inverse() const
invert :-)
Definition: se2.h:82
Generic interface for a non-linear solver operating on a graph.
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)