g2o
Loading...
Searching...
No Matches
ba_anchored_inverse_depth_demo.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2012 H. Strasdat
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 <cassert>
28#include <cstdint>
29#include <iostream>
30#include <unordered_set>
31
35#include "g2o/core/solver.h"
39// #include "g2o/math_groups/se3quat.h"
41#include "g2o/stuff/sampler.h"
42
43#if defined G2O_HAVE_CHOLMOD
45#else
47#endif
48
49using namespace Eigen;
50using namespace std;
51
52class Sample {
53 public:
54 static int uniform(int from, int to) {
55 return static_cast<int>(g2o::Sampler::uniformRand(from, to));
56 }
57};
58
59Vector2d project2d(const Vector3d& v) {
60 Vector2d res;
61 res(0) = v(0) / v(2);
62 res(1) = v(1) / v(2);
63 return res;
64}
65
66Vector3d unproject2d(const Vector2d& v) {
67 Vector3d res;
68 res(0) = v(0);
69 res(1) = v(1);
70 res(2) = 1;
71 return res;
72}
73
74inline Vector3d invert_depth(const Vector3d& x) {
75 return unproject2d(x.head<2>()) / x[2];
76}
77
78int main(int argc, const char* argv[]) {
79 if (argc < 2) {
80 cout << endl;
81 cout << "Please type: " << endl;
82 cout
83 << "ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [SCHUR-TRICK]"
84 << endl;
85 cout << endl;
86 cout << "PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
87 cout << "OUTLIER_RATIO: probability of spuroius observation (default: 0.0)"
88 << endl;
89 cout << "ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)"
90 << endl;
91 cout << "SCHUR-TRICK: Use Schur-complement trick (0 or 1; default: 0==true)"
92 << endl;
93 cout << endl;
94 cout << "Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to "
95 "1==true."
96 << endl;
97 cout << endl;
98 exit(0);
99 }
100
101 double PIXEL_NOISE = atof(argv[1]);
102
103 double OUTLIER_RATIO = 0.0;
104 if (argc > 2) {
105 OUTLIER_RATIO = atof(argv[2]);
106 }
107
108 bool ROBUST_KERNEL = false;
109 if (argc > 3) {
110 ROBUST_KERNEL = atoi(argv[3]) != 0;
111 }
112
113 bool SCHUR_TRICK = true;
114 if (argc > 4) {
115 SCHUR_TRICK = atoi(argv[4]) != 0;
116 }
117
118 cout << "PIXEL_NOISE: " << PIXEL_NOISE << endl;
119 cout << "OUTLIER_RATIO: " << OUTLIER_RATIO << endl;
120 cout << "ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
121 cout << "SCHUR-TRICK: " << SCHUR_TRICK << endl;
122
123 g2o::SparseOptimizer optimizer;
124 optimizer.setVerbose(false);
125
127 if (SCHUR_TRICK) {
128#ifdef G2O_HAVE_CHOLMOD
129 using LinearSolver =
131#else
132 using LinearSolver =
134#endif
136 std::make_unique<g2o::BlockSolver_6_3>(
137 std::make_unique<LinearSolver>()));
138 } else {
139#ifdef G2O_HAVE_CHOLMOD
140 using LinearSolver =
142#else
143 using LinearSolver =
145#endif
147 std::make_unique<g2o::BlockSolverX>(std::make_unique<LinearSolver>()));
148 }
149
150 optimizer.setAlgorithm(solver);
151
152 vector<Vector3d> true_points;
153 for (size_t i = 0; i < 500; ++i) {
154 true_points.push_back(
155 Vector3d((g2o::Sampler::uniformRand(0., 1.) - 0.5) * 3,
156 g2o::Sampler::uniformRand(0., 1.) - 0.5,
157 g2o::Sampler::uniformRand(0., 1.) + 3));
158 }
159
160 double focal_length = 1000.;
161 Vector2d principal_point(320., 240.);
162
163 vector<g2o::SE3Quat, aligned_allocator<g2o::SE3Quat>> true_poses;
164
165 g2o::CameraParameters* cam_params =
166 new g2o::CameraParameters(focal_length, principal_point, 0.);
167 cam_params->setId(0);
168
169 if (!optimizer.addParameter(cam_params)) {
170 assert(false);
171 }
172
173 int vertex_id = 0;
174 for (size_t i = 0; i < 15; ++i) {
175 Vector3d trans(i * 0.04 - 1., 0, 0);
176 Eigen::Quaterniond q;
177 q.setIdentity();
178 g2o::SE3Quat T_me_from_world(q, trans);
180 v_se3->setId(vertex_id);
181 v_se3->setEstimate(T_me_from_world);
182
183 if (i < 2) {
184 v_se3->setFixed(true);
185 }
186
187 optimizer.addVertex(v_se3);
188 true_poses.push_back(T_me_from_world);
189 vertex_id++;
190 }
191 int point_id = vertex_id;
192 int point_num = 0;
193 double sum_diff2 = 0;
194
195 cout << endl;
196 unordered_map<int, int> pointid_2_trueid;
197 unordered_map<int, int> pointid_2_anchorid;
198 unordered_set<int> inliers;
199
200 for (size_t i = 0; i < true_points.size(); ++i) {
202 int num_obs = 0;
203 for (size_t j = 0; j < true_poses.size(); ++j) {
204 Vector2d z = cam_params->cam_map(true_poses.at(j).map(true_points.at(i)));
205 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
206 ++num_obs;
207 }
208 }
209
210 if (num_obs >= 2) {
211 int anchor_frame_id = -1;
212 bool inlier = true;
213 for (size_t j = 0; j < true_poses.size(); ++j) {
214 Vector2d z =
215 cam_params->cam_map(true_poses.at(j).map(true_points.at(i)));
216
217 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
218 if (anchor_frame_id == -1) {
219 anchor_frame_id = j;
220 pointid_2_anchorid.insert(make_pair(point_id, anchor_frame_id));
221 g2o::SE3Quat T_anchor_from_world = true_poses[anchor_frame_id];
222 v_p->setId(point_id);
223 if (SCHUR_TRICK) {
224 v_p->setMarginalized(true);
225 }
226 Vector3d point_w =
227 true_points.at(i) + Vector3d(g2o::Sampler::gaussRand(0., 1),
230
231 Vector3d point_anchor = T_anchor_from_world * point_w;
232 v_p->setEstimate(invert_depth(point_anchor));
233 optimizer.addVertex(v_p);
234 }
235
236 double sam = g2o::Sampler::uniformRand(0., 1.);
237 if (sam < OUTLIER_RATIO) {
238 z = Vector2d(Sample::uniform(0, 640), Sample::uniform(0, 480));
239 inlier = false;
240 }
241 z += Vector2d(g2o::Sampler::gaussRand(0., PIXEL_NOISE),
242 g2o::Sampler::gaussRand(0., PIXEL_NOISE));
244
245 e->resize(3);
246 e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(v_p));
247 e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(
248 optimizer.vertices().find(j)->second));
249 e->setVertex(2,
250 dynamic_cast<g2o::OptimizableGraph::Vertex*>(
251 optimizer.vertices().find(anchor_frame_id)->second));
252
253 e->setMeasurement(z);
254 e->information() = Matrix2d::Identity();
255
256 if (ROBUST_KERNEL) {
258 e->setRobustKernel(rk);
259 }
260
261 e->setParameterId(0, 0);
262 optimizer.addEdge(e);
263 }
264 }
265 if (inlier) {
266 inliers.insert(point_id);
267 Vector3d diff = true_poses[anchor_frame_id].inverse() *
268 invert_depth(v_p->estimate()) -
269 true_points[i];
270 sum_diff2 += diff.dot(diff);
271 }
272 pointid_2_trueid.insert(make_pair(point_id, i));
273 ++point_id;
274 ++point_num;
275 }
276 }
277 cout << endl;
278 optimizer.initializeOptimization();
279 optimizer.setVerbose(true);
280 cout << endl;
281 cout << "Performing full BA:" << endl;
282
283 optimizer.optimize(10);
284
285 cout << endl;
286 cout << "Point error before optimisation (inliers only): "
287 << sqrt(sum_diff2 / point_num) << endl;
288 point_num = 0;
289 sum_diff2 = 0;
290 for (unordered_map<int, int>::iterator it = pointid_2_trueid.begin();
291 it != pointid_2_trueid.end(); ++it) {
292 g2o::HyperGraph::VertexIDMap::iterator v_it =
293 optimizer.vertices().find(it->first);
294 if (v_it == optimizer.vertices().end()) {
295 cerr << "Vertex " << it->first << " not in graph!" << endl;
296 exit(-1);
297 }
298 g2o::VertexPointXYZ* v_p = dynamic_cast<g2o::VertexPointXYZ*>(v_it->second);
299 if (v_p == 0) {
300 cerr << "Vertex " << it->first << "is not a PointXYZ!" << endl;
301 exit(-1);
302 }
303 int anchorframe_id = pointid_2_anchorid.find(it->first)->second;
304 v_it = optimizer.vertices().find(anchorframe_id);
305 if (v_it == optimizer.vertices().end()) {
306 cerr << "Vertex " << it->first << " not in graph!" << endl;
307 exit(-1);
308 }
309 g2o::VertexSE3Expmap* v_anchor =
310 dynamic_cast<g2o::VertexSE3Expmap*>(v_it->second);
311 if (v_anchor == 0) {
312 cerr << "Vertex " << it->second << "is not a SE3Expmap!" << endl;
313 exit(-1);
314 }
315 Vector3d diff =
316 v_anchor->estimate().inverse() * invert_depth(v_p->estimate()) -
317 true_points[it->second];
318 if (inliers.find(it->first) == inliers.end()) continue;
319 sum_diff2 += diff.dot(diff);
320 ++point_num;
321 }
322 cout << "Point error after optimisation (inliers only): "
323 << sqrt(sum_diff2 / point_num) << endl;
324 cout << endl;
325}
Vector2d project2d(const Vector3d &v)
Vector3d invert_depth(const Vector3d &x)
Vector3d unproject2d(const Vector2d &v)
static int uniform(int from, int to)
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
virtual void resize(size_t size)
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()
Vector2 cam_map(const Vector3 &trans_xyz) const
void setVertex(size_t i, Vertex *v)
const VertexIDMap & vertices() const
basic solver for Ax = b which has to reimplemented for different linear algebra libraries
linear solver which uses the sparse Cholesky solver from Eigen
void setRobustKernel(RobustKernel *ptr)
bool setParameterId(int argNum, int paramId)
A general case Vertex for optimization.
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
Implementation of the Levenberg Algorithm.
void setId(int id_)
Definition parameter.cpp:33
Huber Cost Function.
SE3Quat inverse() const
Definition se3quat.h:114
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)
Vertex for a tracked point in space.
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
int main()
Definition gicp_demo.cpp:44
Definition jet.h:938
Definition jet.h:876
virtual bool addEdge(HyperGraph::Edge *e)
bool addParameter(Parameter *p)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)