g2o
gicp_demo.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 Kurt Konolige
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 <Eigen/StdVector>
28 #include <random>
29 #include <iostream>
30 #include <stdint.h>
31 
33 #include "g2o/core/block_solver.h"
34 #include "g2o/core/solver.h"
38 
39 using namespace Eigen;
40 using namespace std;
41 using namespace g2o;
42 
43 // sampling distributions
44  class Sample
45  {
46 
47  static default_random_engine gen_real;
48  static default_random_engine gen_int;
49  public:
50  static int uniform(int from, int to);
51 
52  static double uniform();
53 
54  static double gaussian(double sigma);
55  };
56 
57 
58  default_random_engine Sample::gen_real;
59  default_random_engine Sample::gen_int;
60 
61  int Sample::uniform(int from, int to)
62  {
63  uniform_int_distribution<int> unif(from, to);
64  int sam = unif(gen_int);
65  return sam;
66  }
67 
68  double Sample::uniform()
69  {
70  std::uniform_real_distribution<double> unif(0.0, 1.0);
71  double sam = unif(gen_real);
72  return sam;
73  }
74 
75  double Sample::gaussian(double sigma)
76  {
77  std::normal_distribution<double> gauss(0.0, sigma);
78  double sam = gauss(gen_real);
79  return sam;
80  }
81 
82 
83 //
84 // set up simulated system with noise, optimize it
85 //
86 
87 int main()
88 {
89  double euc_noise = 0.01; // noise in position, m
90  // double outlier_ratio = 0.1;
91 
92 
93  SparseOptimizer optimizer;
94  optimizer.setVerbose(false);
95 
96  // variable-size block solver
98  BlockSolverX * solver_ptr = new BlockSolverX(linearSolver);
100 
101  optimizer.setAlgorithm(solver);
102 
103  vector<Vector3d> true_points;
104  for (size_t i=0;i<1000; ++i)
105  {
106  true_points.push_back(Vector3d((Sample::uniform()-0.5)*3,
107  Sample::uniform()-0.5,
108  Sample::uniform()+10));
109  }
110 
111 
112  // set up two poses
113  int vertex_id = 0;
114  for (size_t i=0; i<2; ++i)
115  {
116  // set up rotation and translation for this node
117  Vector3d t(0,0,i);
118  Quaterniond q;
119  q.setIdentity();
120 
121  Eigen::Isometry3d cam; // camera pose
122  cam = q;
123  cam.translation() = t;
124 
125  // set up node
126  VertexSE3 *vc = new VertexSE3();
127  vc->setEstimate(cam);
128 
129  vc->setId(vertex_id); // vertex id
130 
131  cerr << t.transpose() << " | " << q.coeffs().transpose() << endl;
132 
133  // set first cam pose fixed
134  if (i==0)
135  vc->setFixed(true);
136 
137  // add to optimizer
138  optimizer.addVertex(vc);
139 
140  vertex_id++;
141  }
142 
143  // set up point matches
144  for (size_t i=0; i<true_points.size(); ++i)
145  {
146  // get two poses
147  VertexSE3* vp0 =
148  dynamic_cast<VertexSE3*>(optimizer.vertices().find(0)->second);
149  VertexSE3* vp1 =
150  dynamic_cast<VertexSE3*>(optimizer.vertices().find(1)->second);
151 
152  // calculate the relative 3D position of the point
153  Vector3d pt0,pt1;
154  pt0 = vp0->estimate().inverse() * true_points[i];
155  pt1 = vp1->estimate().inverse() * true_points[i];
156 
157  // add in noise
158  pt0 += Vector3d(Sample::gaussian(euc_noise ),
159  Sample::gaussian(euc_noise ),
160  Sample::gaussian(euc_noise ));
161 
162  pt1 += Vector3d(Sample::gaussian(euc_noise ),
163  Sample::gaussian(euc_noise ),
164  Sample::gaussian(euc_noise ));
165 
166  // form edge, with normals in varioius positions
167  Vector3d nm0, nm1;
168  nm0 << 0, i, 1;
169  nm1 << 0, i, 1;
170  nm0.normalize();
171  nm1.normalize();
172 
173  Edge_V_V_GICP * e // new edge with correct cohort for caching
174  = new Edge_V_V_GICP();
175 
176  e->setVertex(0, vp0); // first viewpoint
177 
178  e->setVertex(1, vp1); // second viewpoint
179 
180  EdgeGICP meas;
181  meas.pos0 = pt0;
182  meas.pos1 = pt1;
183  meas.normal0 = nm0;
184  meas.normal1 = nm1;
185 
186  e->setMeasurement(meas);
187  // e->inverseMeasurement().pos() = -kp;
188 
189  meas = e->measurement();
190  // use this for point-plane
191  e->information() = meas.prec0(0.01);
192 
193  // use this for point-point
194  // e->information().setIdentity();
195 
196  // e->setRobustKernel(true);
197  //e->setHuberWidth(0.01);
198 
199  optimizer.addEdge(e);
200  }
201 
202  // move second cam off of its true position
203  VertexSE3* vc =
204  dynamic_cast<VertexSE3*>(optimizer.vertices().find(1)->second);
205  Eigen::Isometry3d cam = vc->estimate();
206  cam.translation() = Vector3d(0,0,0.2);
207  vc->setEstimate(cam);
208 
209  optimizer.initializeOptimization();
210  optimizer.computeActiveErrors();
211  cout << "Initial chi2 = " << FIXED(optimizer.chi2()) << endl;
212 
213  optimizer.setVerbose(true);
214 
215  optimizer.optimize(5);
216 
217  cout << endl << "Second vertex should be near 0,0,1" << endl;
218  cout << dynamic_cast<VertexSE3*>(optimizer.vertices().find(0)->second)
219  ->estimate().translation().transpose() << endl;
220  cout << dynamic_cast<VertexSE3*>(optimizer.vertices().find(1)->second)
221  ->estimate().translation().transpose() << endl;
222 }
Implementation of the Levenberg Algorithm.
static default_random_engine gen_int
Definition: gicp_demo.cpp:48
int optimize(int iterations, bool online=false)
Vector3D normal0
Definition: types_icp.h:69
virtual void setMeasurement(const Measurement &m)
Definition: base_edge.h:76
linear solver using dense cholesky decomposition
void setVertex(size_t i, Vertex *v)
Definition: hyper_graph.h:194
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
Traits::LinearSolverType LinearSolverType
Definition: block_solver.h:110
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 ...
static double uniform()
Definition: ba_demo.cpp:73
double chi2() const
returns the chi2 of the current configuration
void setVerbose(bool verbose)
Vector3D pos1
Definition: types_icp.h:66
void setAlgorithm(OptimizationAlgorithm *algorithm)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
Vector3D normal1
Definition: types_icp.h:69
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
int main()
Definition: gicp_demo.cpp:87
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
Implementation of a solver operating on the blocks of the Hessian.
Definition: block_solver.h:96
Matrix3D prec0(double e)
Definition: types_icp.h:114
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
static double gaussian(double sigma)
Definition: ba_demo.cpp:77
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
static default_random_engine gen_real
Definition: gicp_demo.cpp:47
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX
Definition: block_solver.h:179
Vector3D pos0
Definition: types_icp.h:66