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