g2o
Loading...
Searching...
No Matches
tutorial_slam2d.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 <cmath>
28#include <iostream>
29
30#include "edge_se2.h"
31#include "edge_se2_pointxy.h"
33#include "g2o/core/factory.h"
38#include "simulator.h"
40#include "vertex_point_xy.h"
41#include "vertex_se2.h"
42
43using namespace std;
44using namespace g2o;
45using namespace g2o::tutorial;
46
47int main() {
48 // TODO simulate different sensor offset
49 // simulate a robot observing landmarks while travelling on a grid
50 SE2 sensorOffsetTransf(0.2, 0.1, -0.1);
51 int numNodes = 300;
52 Simulator simulator;
53 simulator.simulate(numNodes, sensorOffsetTransf);
54
55 /*********************************************************************************
56 * creating the optimization problem
57 ********************************************************************************/
58
59 typedef BlockSolver<BlockSolverTraits<-1, -1> > SlamBlockSolver;
61
62 // allocating the optimizer
63 SparseOptimizer optimizer;
64 auto linearSolver = std::make_unique<SlamLinearSolver>();
65 linearSolver->setBlockOrdering(false);
68 std::make_unique<SlamBlockSolver>(std::move(linearSolver)));
69
70 optimizer.setAlgorithm(solver);
71
72 // add the parameter representing the sensor offset
73 ParameterSE2Offset* sensorOffset = new ParameterSE2Offset;
74 sensorOffset->setOffset(sensorOffsetTransf);
75 sensorOffset->setId(0);
76 optimizer.addParameter(sensorOffset);
77
78 // adding the odometry to the optimizer
79 // first adding all the vertices
80 cerr << "Optimization: Adding robot poses ... ";
81 for (size_t i = 0; i < simulator.poses().size(); ++i) {
82 const Simulator::GridPose& p = simulator.poses()[i];
83 const SE2& t = p.simulatorPose;
84 VertexSE2* robot = new VertexSE2;
85 robot->setId(p.id);
86 robot->setEstimate(t);
87 optimizer.addVertex(robot);
88 }
89 cerr << "done." << endl;
90
91 // second add the odometry constraints
92 cerr << "Optimization: Adding odometry measurements ... ";
93 for (size_t i = 0; i < simulator.odometry().size(); ++i) {
94 const Simulator::GridEdge& simEdge = simulator.odometry()[i];
95
96 EdgeSE2* odometry = new EdgeSE2;
97 odometry->vertices()[0] = optimizer.vertex(simEdge.from);
98 odometry->vertices()[1] = optimizer.vertex(simEdge.to);
99 odometry->setMeasurement(simEdge.simulatorTransf);
100 odometry->setInformation(simEdge.information);
101 optimizer.addEdge(odometry);
102 }
103 cerr << "done." << endl;
104
105 // add the landmark observations
106 cerr << "Optimization: add landmark vertices ... ";
107 for (size_t i = 0; i < simulator.landmarks().size(); ++i) {
108 const Simulator::Landmark& l = simulator.landmarks()[i];
109 VertexPointXY* landmark = new VertexPointXY;
110 landmark->setId(l.id);
111 landmark->setEstimate(l.simulatedPose);
112 optimizer.addVertex(landmark);
113 }
114 cerr << "done." << endl;
115
116 cerr << "Optimization: add landmark observations ... ";
117 for (size_t i = 0; i < simulator.landmarkObservations().size(); ++i) {
118 const Simulator::LandmarkEdge& simEdge =
119 simulator.landmarkObservations()[i];
120 EdgeSE2PointXY* landmarkObservation = new EdgeSE2PointXY;
121 landmarkObservation->vertices()[0] = optimizer.vertex(simEdge.from);
122 landmarkObservation->vertices()[1] = optimizer.vertex(simEdge.to);
123 landmarkObservation->setMeasurement(simEdge.simulatorMeas);
124 landmarkObservation->setInformation(simEdge.information);
125 landmarkObservation->setParameterId(0, sensorOffset->id());
126 optimizer.addEdge(landmarkObservation);
127 }
128 cerr << "done." << endl;
129
130 /*********************************************************************************
131 * optimization
132 ********************************************************************************/
133
134 // dump initial state to the disk
135 optimizer.save("tutorial_before.g2o");
136
137 // prepare and run the optimization
138 // fix the first robot pose to account for gauge freedom
139 VertexSE2* firstRobotPose = dynamic_cast<VertexSE2*>(optimizer.vertex(0));
140 firstRobotPose->setFixed(true);
141 optimizer.setVerbose(true);
142
143 cerr << "Optimizing" << endl;
144 optimizer.initializeOptimization();
145 optimizer.optimize(10);
146 cerr << "done." << endl;
147
148 optimizer.save("tutorial_after.g2o");
149
150 // freeing the graph memory
151 optimizer.clear();
152
153 return 0;
154}
virtual void setMeasurement(const Measurement &m)
Definition base_edge.h:122
void setInformation(const InformationType &information)
Definition base_edge.h:111
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Implementation of a solver operating on the blocks of the Hessian.
const VertexContainer & vertices() const
linear solver which uses the sparse Cholesky solver from Eigen
bool setParameterId(int argNum, int paramId)
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
Implementation of the Gauss Newton Algorithm.
int id() const
Definition parameter.h:44
void setId(int id_)
Definition parameter.cpp:33
int optimize(int iterations, bool online=false)
void setVerbose(bool verbose)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
void setAlgorithm(OptimizationAlgorithm *algorithm)
2D edge between two Vertex2, i.e., the odometry
Definition edge_se2.h:42
void setMeasurement(const SE2 &m)
Definition edge_se2.h:55
void setOffset(const SE2 &offset=SE2())
2D pose Vertex, (x,y,theta)
Definition vertex_se2.h:41
Definition jet.h:876
traits to summarize the properties of the fixed size optimization problem
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
bool addParameter(Parameter *p)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
Vertex * vertex(int id)
returns the vertex number id appropriately casted
int main()