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