g2o
Loading...
Searching...
No Matches
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 <stdint.h>
28
29#include <iostream>
30#include <random>
31
34#include "g2o/core/solver.h"
37#include "g2o/stuff/sampler.h"
39
40using namespace Eigen;
41using namespace std;
42using namespace g2o;
43
44int main() {
45 double euc_noise = 0.01; // noise in position, m
46 // double outlier_ratio = 0.1;
47
48 SparseOptimizer optimizer;
49 optimizer.setVerbose(false);
50
51 // variable-size block solver
53 new g2o::OptimizationAlgorithmLevenberg(std::make_unique<BlockSolverX>(
54 std::make_unique<
56
57 optimizer.setAlgorithm(solver);
58
59 vector<Vector3d> true_points;
60 for (size_t i = 0; i < 1000; ++i) {
61 true_points.push_back(
62 Vector3d((g2o::Sampler::uniformRand(0., 1.) - 0.5) * 3,
63 g2o::Sampler::uniformRand(0., 1.) - 0.5,
64 g2o::Sampler::uniformRand(0., 1.) + 10));
65 }
66
67 // set up two poses
68 int vertex_id = 0;
69 for (size_t i = 0; i < 2; ++i) {
70 // set up rotation and translation for this node
71 Vector3d t(0, 0, i);
72 Quaterniond q;
73 q.setIdentity();
74
75 Eigen::Isometry3d cam; // camera pose
76 cam = q;
77 cam.translation() = t;
78
79 // set up node
80 VertexSE3* vc = new VertexSE3();
81 vc->setEstimate(cam);
82
83 vc->setId(vertex_id); // vertex id
84
85 cerr << t.transpose() << " | " << q.coeffs().transpose() << endl;
86
87 // set first cam pose fixed
88 if (i == 0) vc->setFixed(true);
89
90 // add to optimizer
91 optimizer.addVertex(vc);
92
93 vertex_id++;
94 }
95
96 // set up point matches
97 for (size_t i = 0; i < true_points.size(); ++i) {
98 // get two poses
99 VertexSE3* vp0 =
100 dynamic_cast<VertexSE3*>(optimizer.vertices().find(0)->second);
101 VertexSE3* vp1 =
102 dynamic_cast<VertexSE3*>(optimizer.vertices().find(1)->second);
103
104 // calculate the relative 3D position of the point
105 Vector3d pt0, pt1;
106 pt0 = vp0->estimate().inverse() * true_points[i];
107 pt1 = vp1->estimate().inverse() * true_points[i];
108
109 // add in noise
110 pt0 += Vector3d(g2o::Sampler::gaussRand(0., euc_noise),
111 g2o::Sampler::gaussRand(0., euc_noise),
112 g2o::Sampler::gaussRand(0., euc_noise));
113
114 pt1 += Vector3d(g2o::Sampler::gaussRand(0., euc_noise),
115 g2o::Sampler::gaussRand(0., euc_noise),
116 g2o::Sampler::gaussRand(0., euc_noise));
117
118 // form edge, with normals in varioius positions
119 Vector3d nm0, nm1;
120 nm0 << 0, i, 1;
121 nm1 << 0, i, 1;
122 nm0.normalize();
123 nm1.normalize();
124
125 Edge_V_V_GICP* e // new edge with correct cohort for caching
126 = new Edge_V_V_GICP();
127
128 e->setVertex(0, vp0); // first viewpoint
129 e->setVertex(1, vp1); // second viewpoint
130
131 EdgeGICP meas;
132 meas.pos0 = pt0;
133 meas.pos1 = pt1;
134 meas.normal0 = nm0;
135 meas.normal1 = nm1;
136
137 e->setMeasurement(meas);
138 // e->inverseMeasurement().pos() = -kp;
139
140 meas = e->measurement();
141 // use this for point-plane
142 e->information() = meas.prec0(0.01);
143
144 // use this for point-point
145 // e->information().setIdentity();
146
147 // e->setRobustKernel(true);
148 // e->setHuberWidth(0.01);
149
150 optimizer.addEdge(e);
151 }
152
153 // move second cam off of its true position
154 VertexSE3* vc =
155 dynamic_cast<VertexSE3*>(optimizer.vertices().find(1)->second);
156 Eigen::Isometry3d cam = vc->estimate();
157 cam.translation() = Vector3d(0, 0, 0.2);
158 vc->setEstimate(cam);
159
160 optimizer.initializeOptimization();
161 optimizer.computeActiveErrors();
162 cout << "Initial chi2 = " << FIXED(optimizer.chi2()) << endl;
163
164 optimizer.setVerbose(true);
165
166 optimizer.optimize(5);
167
168 cout << endl << "Second vertex should be near 0,0,1" << endl;
169 cout << dynamic_cast<VertexSE3*>(optimizer.vertices().find(0)->second)
170 ->estimate()
171 .translation()
172 .transpose()
173 << endl;
174 cout << dynamic_cast<VertexSE3*>(optimizer.vertices().find(1)->second)
175 ->estimate()
176 .translation()
177 .transpose()
178 << endl;
179}
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition base_edge.h:119
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
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Vector3 pos1
Definition types_icp.h:62
Vector3 pos0
Definition types_icp.h:62
Matrix3 prec0(double e)
Definition types_icp.h:107
Vector3 normal1
Definition types_icp.h:65
Vector3 normal0
Definition types_icp.h:65
void setVertex(size_t i, Vertex *v)
const VertexIDMap & vertices() const
linear solver using dense cholesky decomposition
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
Implementation of the Levenberg Algorithm.
static double gaussRand(double mean, double sigma)
Definition sampler.h:89
static double uniformRand(double lowerBndr, double upperBndr)
Definition sampler.h:102
int optimize(int iterations, bool online=false)
void setVerbose(bool verbose)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
void setAlgorithm(OptimizationAlgorithm *algorithm)
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
int main()
Definition gicp_demo.cpp:44
Definition jet.h:938
Definition jet.h:876
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
double chi2() const
returns the chi2 of the current configuration