g2o
Loading...
Searching...
No Matches
g2o_slam_interface.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 "g2o_slam_interface.h"
28
29#include <cassert>
30#include <iostream>
31
32#include "fast_output.h"
35#include "types_slam2d_online.h"
36#include "types_slam3d_online.h"
37using namespace std;
38using namespace Eigen;
39
40namespace g2o {
41
42namespace {
43void quat_to_euler(const Eigen::Quaterniond& q, double& yaw, double& pitch,
44 double& roll) {
45 const double& q0 = q.w();
46 const double& q1 = q.x();
47 const double& q2 = q.y();
48 const double& q3 = q.z();
49 roll = atan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1 * q1 + q2 * q2));
50 pitch = asin(2 * (q0 * q2 - q3 * q1));
51 yaw = atan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2 * q2 + q3 * q3));
52}
53
54void jac_quat3_euler3(Eigen::Matrix<double, 6, 6>& J, const SE3Quat& t) {
55 const Vector3d& tr0 = t.translation();
56 const Quaterniond& q0 = t.rotation();
57
58 double delta = 1e-6;
59 double idelta = 1. / (2. * delta);
60
61 for (int i = 0; i < 6; i++) {
62 SE3Quat ta, tb;
63 if (i < 3) {
64 Vector3d tra = tr0;
65 Vector3d trb = tr0;
66 tra[i] -= delta;
67 trb[i] += delta;
68 ta = SE3Quat(q0, tra);
69 tb = SE3Quat(q0, trb);
70 } else {
71 Quaterniond qa = q0;
72 Quaterniond qb = q0;
73 if (i == 3) {
74 qa.x() -= delta;
75 qb.x() += delta;
76 } else if (i == 4) {
77 qa.y() -= delta;
78 qb.y() += delta;
79 } else if (i == 5) {
80 qa.z() -= delta;
81 qb.z() += delta;
82 }
83 qa.normalize();
84 qb.normalize();
85 ta = SE3Quat(qa, tr0);
86 tb = SE3Quat(qb, tr0);
87 }
88
89 Vector3d dtr = (tb.translation() - ta.translation()) * idelta;
90 Vector3d taAngles, tbAngles;
91 quat_to_euler(ta.rotation(), taAngles(2), taAngles(1), taAngles(0));
92 quat_to_euler(tb.rotation(), tbAngles(2), tbAngles(1), tbAngles(0));
93 Vector3d da =
94 (tbAngles - taAngles) * idelta; // TODO wraparounds not handled
95
96 for (int j = 0; j < 6; j++) {
97 if (j < 3) {
98 J(j, i) = dtr(j);
99 } else {
100 J(j, i) = da(j - 3);
101 }
102 }
103 }
104}
105} // namespace
106
108 : _optimizer(optimizer),
109 _firstOptimization(true),
110 _nodesAdded(0),
111 _incIterations(1),
112 _updateGraphEachN(10),
113 _batchEveryN(100),
114 _lastBatchStep(0),
115 _initSolverDone(false) {}
116
117bool G2oSlamInterface::addNode(const std::string& tag, int id, int dimension,
118 const std::vector<double>& values) {
119 // allocating the desired solver + testing whether the solver is okay
120 if (!_initSolverDone) {
121 _initSolverDone = true;
123 }
124
125 // we add the node when we are asked to add the according edge
126 (void)tag;
127 (void)id;
128 (void)dimension;
129 (void)values;
130 return true;
131}
132
133bool G2oSlamInterface::addEdge(const std::string& tag, int id, int dimension,
134 int v1Id, int v2Id,
135 const std::vector<double>& measurement,
136 const std::vector<double>& information) {
137 (void)tag;
138 (void)id;
139 size_t oldEdgesSize = _optimizer->edges().size();
140
141 if (dimension == 3) {
142 SE2 transf(measurement[0], measurement[1], measurement[2]);
143 Eigen::Matrix3d infMat;
144 int idx = 0;
145 for (int r = 0; r < 3; ++r)
146 for (int c = r; c < 3; ++c, ++idx) {
147 assert(idx < (int)information.size());
148 infMat(r, c) = infMat(c, r) = information[idx];
149 }
150 // cerr << PVAR(infMat) << endl;
151
152 int doInit = 0;
155 if (!v1) {
156 OptimizableGraph::Vertex* v = v1 = addVertex(dimension, v1Id);
157 _verticesAdded.insert(v);
158 doInit = 1;
159 ++_nodesAdded;
160 }
161
162 if (!v2) {
163 OptimizableGraph::Vertex* v = v2 = addVertex(dimension, v2Id);
164 _verticesAdded.insert(v);
165 doInit = 2;
166 ++_nodesAdded;
167 }
168
169 if (_optimizer->edges().size() == 0) {
170 cerr << "FIRST EDGE ";
171 if (v1->id() < v2->id()) {
172 cerr << "fixing " << v1->id() << endl;
173 v1->setFixed(true);
174 } else {
175 cerr << "fixing " << v2->id() << endl;
176 v2->setFixed(true);
177 }
178 }
179
181 e->vertices()[0] = v1;
182 e->vertices()[1] = v2;
183 e->setMeasurement(transf);
184 e->setInformation(infMat);
186 _edgesAdded.insert(e);
187
188 if (doInit) {
190 static_cast<OptimizableGraph::Vertex*>(e->vertices()[0]);
192 static_cast<OptimizableGraph::Vertex*>(e->vertices()[1]);
193 switch (doInit) {
194 case 1: // initialize v1 from v2
195 {
197 toSet.insert(to);
198 if (e->initialEstimatePossible(toSet, from) > 0.) {
199 e->initialEstimate(toSet, from);
200 }
201 break;
202 }
203 case 2: {
204 HyperGraph::VertexSet fromSet;
205 fromSet.insert(from);
206 if (e->initialEstimatePossible(fromSet, to) > 0.) {
207 e->initialEstimate(fromSet, to);
208 }
209 break;
210 }
211 default:
212 cerr << "doInit wrong value\n";
213 }
214 }
215
216 } else if (dimension == 6) {
217 Eigen::Isometry3d transf;
218 Matrix<double, 6, 6> infMat;
219
220 if (measurement.size() == 7) { // measurement is a Quaternion
221 Vector7 meas;
222 for (int i = 0; i < 7; ++i) meas(i) = measurement[i];
223 // normalize the quaternion to recover numerical precision lost by storing
224 // as human readable text
225 Vector4::MapType(meas.data() + 3).normalize();
226 transf = internal::fromVectorQT(meas);
227
228 for (int i = 0, idx = 0; i < infMat.rows(); ++i)
229 for (int j = i; j < infMat.cols(); ++j) {
230 infMat(i, j) = information[idx++];
231 if (i != j) infMat(j, i) = infMat(i, j);
232 }
233 } else { // measurement consists of Euler angles
234 Vector6 aux;
235 aux << measurement[0], measurement[1], measurement[2], measurement[3],
236 measurement[4], measurement[5];
237 transf = internal::fromVectorET(aux);
238 Matrix<double, 6, 6> infMatEuler;
239 int idx = 0;
240 for (int r = 0; r < 6; ++r)
241 for (int c = r; c < 6; ++c, ++idx) {
242 assert(idx < (int)information.size());
243 infMatEuler(r, c) = infMatEuler(c, r) = information[idx];
244 }
245 // convert information matrix to our internal representation
246 Matrix<double, 6, 6> J;
247 SE3Quat transfAsSe3(transf.matrix().topLeftCorner<3, 3>(),
248 transf.translation());
249 jac_quat3_euler3(J, transfAsSe3);
250 infMat.noalias() = J.transpose() * infMatEuler * J;
251 // cerr << PVAR(transf.matrix()) << endl;
252 // cerr << PVAR(infMat) << endl;
253 }
254
255 int doInit = 0;
258 if (!v1) {
259 OptimizableGraph::Vertex* v = v1 = addVertex(dimension, v1Id);
260 _verticesAdded.insert(v);
261 doInit = 1;
262 ++_nodesAdded;
263 }
264
265 if (!v2) {
266 OptimizableGraph::Vertex* v = v2 = addVertex(dimension, v2Id);
267 _verticesAdded.insert(v);
268 doInit = 2;
269 ++_nodesAdded;
270 }
271
272 if (_optimizer->edges().size() == 0) {
273 cerr << "FIRST EDGE ";
274 if (v1->id() < v2->id()) {
275 cerr << "fixing " << v1->id() << endl;
276 v1->setFixed(true);
277 } else {
278 cerr << "fixing " << v2->id() << endl;
279 v2->setFixed(true);
280 }
281 }
282
284 e->vertices()[0] = v1;
285 e->vertices()[1] = v2;
286 e->setMeasurement(transf);
287 e->setInformation(infMat);
289 _edgesAdded.insert(e);
290
291 if (doInit) {
293 static_cast<OptimizableGraph::Vertex*>(e->vertices()[0]);
295 static_cast<OptimizableGraph::Vertex*>(e->vertices()[1]);
296 switch (doInit) {
297 case 1: // initialize v1 from v2
298 {
300 toSet.insert(to);
301 if (e->initialEstimatePossible(toSet, from) > 0.) {
302 e->initialEstimate(toSet, from);
303 }
304 break;
305 }
306 case 2: {
307 HyperGraph::VertexSet fromSet;
308 fromSet.insert(from);
309 if (e->initialEstimatePossible(fromSet, to) > 0.) {
310 e->initialEstimate(fromSet, to);
311 }
312 break;
313 }
314 default:
315 cerr << "doInit wrong value\n";
316 }
317 }
318
319 } else {
320 cerr << __PRETTY_FUNCTION__ << " not implemented for this dimension"
321 << endl;
322 return false;
323 }
324
325 if (oldEdgesSize == 0) {
327 }
328
329 return true;
330}
331
332bool G2oSlamInterface::fixNode(const std::vector<int>& nodes) {
333 for (size_t i = 0; i < nodes.size(); ++i) {
335 if (v) v->setFixed(true);
336 }
337 return true;
338}
339
340bool G2oSlamInterface::queryState(const std::vector<int>& nodes) {
341 // return true;
342 cout << "BEGIN" << endl;
343#if 1
344 if (nodes.size() == 0) {
345 for (OptimizableGraph::VertexIDMap::const_iterator it =
346 _optimizer->vertices().begin();
347 it != _optimizer->vertices().end(); ++it) {
349 static_cast<OptimizableGraph::Vertex*>(it->second);
350 printVertex(v);
351 }
352 } else {
353 for (size_t i = 0; i < nodes.size(); ++i) {
355 if (v) printVertex(v);
356 }
357 }
358#endif
359 cout << "END" << endl << flush;
360
361 return true;
362}
363
365 SolveResult state = solve();
366 return state != ERROR;
367}
368
370 if (dimension == 3) {
372 v->setId(id); // estimate will be set later when the edge is added
374 return v;
375 } else if (dimension == 6) {
377 v->setId(id); // estimate will be set later when the edge is added
379 return v;
380 } else {
381 return 0;
382 }
383}
384
386 static char buffer[10000]; // that should be more than enough
387 int vdim = v->dimension();
388 if (vdim == 3) {
389 char* s = buffer;
390 OnlineVertexSE2* v2 = static_cast<OnlineVertexSE2*>(v);
391 memcpy(s, "VERTEX_XYT ", 11);
392 s += 11;
393 s += modp_itoa10(v->id(), s);
394 *s++ = ' ';
395 s += modp_dtoa(v2->updatedEstimate.translation().x(), s, 6);
396 *s++ = ' ';
397 s += modp_dtoa(v2->updatedEstimate.translation().y(), s, 6);
398 *s++ = ' ';
399 s += modp_dtoa(v2->updatedEstimate.rotation().angle(), s, 6);
400 *s++ = '\n';
401 cout.write(buffer, s - buffer);
402 return true;
403 } else if (vdim == 6) {
404 char* s = buffer;
405 OnlineVertexSE3* v3 = static_cast<OnlineVertexSE3*>(v);
406 Vector3d eulerAngles =
407 internal::toEuler(v3->updatedEstimate.matrix().topLeftCorner<3, 3>());
408 const double& roll = eulerAngles(0);
409 const double& pitch = eulerAngles(1);
410 const double& yaw = eulerAngles(2);
411 memcpy(s, "VERTEX_XYZRPY ", 14);
412 s += 14;
413 s += modp_itoa10(v->id(), s);
414 *s++ = ' ';
415 s += modp_dtoa(v3->updatedEstimate.translation().x(), s, 6);
416 *s++ = ' ';
417 s += modp_dtoa(v3->updatedEstimate.translation().y(), s, 6);
418 *s++ = ' ';
419 s += modp_dtoa(v3->updatedEstimate.translation().z(), s, 6);
420 *s++ = ' ';
421 s += modp_dtoa(roll, s, 6);
422 *s++ = ' ';
423 s += modp_dtoa(pitch, s, 6);
424 *s++ = ' ';
425 s += modp_dtoa(yaw, s, 6);
426 *s++ = '\n';
427 cout.write(buffer, s - buffer);
428 return true;
429 }
430 return false;
431}
432
434
437 // decide on batch step or normal step
438 _optimizer->batchStep = false;
439 if ((int)_optimizer->vertices().size() - _lastBatchStep >= _batchEveryN) {
441 _optimizer->batchStep = true;
442 }
443
444 if (_firstOptimization) {
446 cerr << "initialization failed" << endl;
447 return ERROR;
448 }
449 } else {
451 cerr << "updating initialization failed" << endl;
452 return ERROR;
453 }
454 }
455
457 (void)currentIt;
458 _firstOptimization = false;
459 _nodesAdded = 0;
460 _verticesAdded.clear();
461 _edgesAdded.clear();
462 if (_optimizer->batchStep) return SOLVED_BATCH;
463 return SOLVED;
464 }
465
466 return NOOP;
467}
468
470
471} // namespace g2o
void setInformation(const InformationType &information)
Definition base_edge.h:111
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
Definition edge_se2.h:85
virtual void setMeasurement(const SE2 &m)
Definition edge_se2.h:56
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
Definition edge_se3.h:76
virtual void setMeasurement(const Isometry3 &m)
Definition edge_se3.h:53
bool printVertex(OptimizableGraph::Vertex *v)
HyperGraph::EdgeSet _edgesAdded
bool fixNode(const std::vector< int > &nodes)
bool queryState(const std::vector< int > &nodes)
G2oSlamInterface(SparseOptimizerOnline *optimizer)
bool addEdge(const std::string &tag, int id, int dimension, int v1, int v2, const std::vector< double > &measurement, const std::vector< double > &information)
bool addNode(const std::string &tag, int id, int dimension, const std::vector< double > &values)
OptimizableGraph::Vertex * addVertex(int dimension, int id)
SparseOptimizerOnline * _optimizer
HyperGraph::VertexSet _verticesAdded
const VertexContainer & vertices() const
abstract Vertex, your types must derive from that one
int id() const
returns the id
std::set< Vertex * > VertexSet
const EdgeSet & edges() const
const VertexIDMap & vertices() const
void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
VertexSE2::EstimateType updatedEstimate
VertexSE3::EstimateType updatedEstimate
A general case Vertex for optimization.
int dimension() const
dimension of the estimated state belonging to this node
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
represent SE2
Definition se2.h:43
const Vector2 & translation() const
translational component
Definition se2.h:57
const Rotation2D & rotation() const
rotational component
Definition se2.h:61
virtual bool initSolver(int dimension, int batchEveryN)
int optimize(int iterations, bool online=false)
virtual bool updateInitialization(HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
int modp_itoa10(int32_t value, char *str)
int modp_dtoa(double value, char *str, int prec)
Definition fast_output.h:56
#define __PRETTY_FUNCTION__
Definition macros.h:90
Definition jet.h:938
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition jet.h:730
Jet< T, N > asin(const Jet< T, N > &f)
Definition jet.h:471
Isometry3 fromVectorQT(const Vector7 &v)
Vector3 toEuler(const Matrix3 &R)
Isometry3 fromVectorET(const Vector6 &v)
VectorN< 7 > Vector7
Definition eigen_types.h:54
VectorN< 6 > Vector6
Definition eigen_types.h:53
static void jac_quat3_euler3(Eigen::Matrix< double, 6, 6, Eigen::ColMajor > &J, const Isometry3 &t)
Definition jet.h:876
JacobianWorkspace & jacobianWorkspace()
the workspace for storing the Jacobians of the graph
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
Vertex * vertex(int id)
returns the vertex number id appropriately casted