g2o
Loading...
Searching...
No Matches
Classes | Functions
sba_demo.cpp File Reference
#include <stdint.h>
#include <iostream>
#include <unordered_set>
#include "g2o/config.h"
#include "g2o/core/block_solver.h"
#include "g2o/core/optimization_algorithm_levenberg.h"
#include "g2o/core/robust_kernel_impl.h"
#include "g2o/core/solver.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/solvers/dense/linear_solver_dense.h"
#include "g2o/solvers/structure_only/structure_only_solver.h"
#include "g2o/stuff/sampler.h"
#include "g2o/types/icp/types_icp.h"
#include "g2o/solvers/eigen/linear_solver_eigen.h"
Include dependency graph for sba_demo.cpp:

Go to the source code of this file.

Classes

class  Sample
 

Functions

int main (int argc, const char *argv[])
 

Function Documentation

◆ main()

int main ( int  argc,
const char *  argv[] 
)

Definition at line 59 of file sba_demo.cpp.

59 {
60 if (argc < 2) {
61 cout << endl;
62 cout << "Please type: " << endl;
63 cout << "ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] "
64 "[STRUCTURE_ONLY] [DENSE]"
65 << endl;
66 cout << endl;
67 cout << "PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
68 cout << "OUTLIER_RATIO: probability of spuroius observation (default: 0.0)"
69 << endl;
70 cout << "ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)"
71 << endl;
72 cout << "STRUCTURE_ONLY: performed structure-only BA to get better point "
73 "initializations (0 or 1; default: 0==false)"
74 << endl;
75 cout << "DENSE: Use dense solver (0 or 1; default: 0==false)" << endl;
76 cout << endl;
77 cout << "Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to "
78 "1==true."
79 << endl;
80 cout << endl;
81 exit(0);
82 }
83
84 double PIXEL_NOISE = atof(argv[1]);
85
86 double OUTLIER_RATIO = 0.0;
87
88 if (argc > 2) {
89 OUTLIER_RATIO = atof(argv[2]);
90 }
91
92 bool ROBUST_KERNEL = false;
93 if (argc > 3) {
94 ROBUST_KERNEL = atoi(argv[3]) != 0;
95 }
96 bool STRUCTURE_ONLY = false;
97 if (argc > 4) {
98 STRUCTURE_ONLY = atoi(argv[4]) != 0;
99 }
100
101 bool DENSE = false;
102 if (argc > 5) {
103 DENSE = atoi(argv[5]) != 0;
104 }
105
106 cout << "PIXEL_NOISE: " << PIXEL_NOISE << endl;
107 cout << "OUTLIER_RATIO: " << OUTLIER_RATIO << endl;
108 cout << "ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
109 cout << "STRUCTURE_ONLY: " << STRUCTURE_ONLY << endl;
110 cout << "DENSE: " << DENSE << endl;
111
112 g2o::SparseOptimizer optimizer;
113 optimizer.setVerbose(false);
114 std::unique_ptr<g2o::BlockSolver_6_3::LinearSolverType> linearSolver;
115 if (DENSE) {
116 linearSolver = std::make_unique<
118 cerr << "Using DENSE" << endl;
119 } else {
120#ifdef G2O_HAVE_CHOLMOD
121 cerr << "Using CHOLMOD" << endl;
122 linearSolver = std::make_unique<
124#else
125 linearSolver = std::make_unique<
127 cerr << "Using CSPARSE" << endl;
128#endif
129 }
130
133 std::make_unique<g2o::BlockSolver_6_3>(std::move(linearSolver)));
134
135 optimizer.setAlgorithm(solver);
136
137 // set up 500 points
138 vector<Vector3d> true_points;
139 for (size_t i = 0; i < 500; ++i) {
140 true_points.push_back(
141 Vector3d((g2o::Sampler::uniformRand(0., 1.) - 0.5) * 3,
142 g2o::Sampler::uniformRand(0., 1.) - 0.5,
143 g2o::Sampler::uniformRand(0., 1.) + 10));
144 }
145
146 Vector2d focal_length(500, 500); // pixels
147 Vector2d principal_point(320, 240); // 640x480 image
148 double baseline = 0.075; // 7.5 cm baseline
149
150 vector<Eigen::Isometry3d, aligned_allocator<Eigen::Isometry3d>> true_poses;
151
152 // set up camera params
153 g2o::VertexSCam::setKcam(focal_length[0], focal_length[1], principal_point[0],
154 principal_point[1], baseline);
155
156 // set up 5 vertices, first 2 fixed
157 int vertex_id = 0;
158 for (size_t i = 0; i < 5; ++i) {
159 Vector3d trans(i * 0.04 - 1., 0, 0);
160
161 Eigen::Quaterniond q;
162 q.setIdentity();
163 Eigen::Isometry3d pose;
164 pose = q;
165 pose.translation() = trans;
166
167 g2o::VertexSCam* v_se3 = new g2o::VertexSCam();
168
169 v_se3->setId(vertex_id);
170 v_se3->setEstimate(pose);
171 v_se3->setAll(); // set aux transforms
172
173 if (i < 2) v_se3->setFixed(true);
174
175 optimizer.addVertex(v_se3);
176 true_poses.push_back(pose);
177 vertex_id++;
178 }
179
180 int point_id = vertex_id;
181 double sum_diff2 = 0;
182
183 cout << endl;
184 unordered_map<int, int> pointid_2_trueid;
185 unordered_set<int> inliers;
186
187 // add point projections to this vertex
188 for (size_t i = 0; i < true_points.size(); ++i) {
190
191 v_p->setId(point_id);
192 v_p->setMarginalized(true);
193 v_p->setEstimate(true_points.at(i) +
194 Vector3d(g2o::Sampler::gaussRand(0., 1),
197
198 int num_obs = 0;
199
200 for (size_t j = 0; j < true_poses.size(); ++j) {
201 Vector3d z;
202 dynamic_cast<g2o::VertexSCam*>(optimizer.vertices().find(j)->second)
203 ->mapPoint(z, true_points.at(i));
204
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 optimizer.addVertex(v_p);
212
213 bool inlier = true;
214 for (size_t j = 0; j < true_poses.size(); ++j) {
215 Vector3d z;
216 dynamic_cast<g2o::VertexSCam*>(optimizer.vertices().find(j)->second)
217 ->mapPoint(z, true_points.at(i));
218
219 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
220 double sam = g2o::Sampler::uniformRand(0., 1.);
221 if (sam < OUTLIER_RATIO) {
222 z = Vector3d(Sample::uniform(64, 640), Sample::uniform(0, 480),
223 Sample::uniform(0, 64)); // disparity
224 z(2) = z(0) - z(2); // px' now
225
226 inlier = false;
227 }
228
229 z += Vector3d(g2o::Sampler::gaussRand(0., PIXEL_NOISE),
230 g2o::Sampler::gaussRand(0., PIXEL_NOISE),
231 g2o::Sampler::gaussRand(0., PIXEL_NOISE / 16.0));
232
234
235 e->vertices()[0] = dynamic_cast<g2o::OptimizableGraph::Vertex*>(v_p);
236
237 e->vertices()[1] = dynamic_cast<g2o::OptimizableGraph::Vertex*>(
238 optimizer.vertices().find(j)->second);
239
240 e->setMeasurement(z);
241 // e->inverseMeasurement() = -z;
242 e->information() = Matrix3d::Identity();
243
244 if (ROBUST_KERNEL) {
246 e->setRobustKernel(rk);
247 }
248
249 optimizer.addEdge(e);
250 }
251 }
252
253 if (inlier) {
254 inliers.insert(point_id);
255 Vector3d diff = v_p->estimate() - true_points[i];
256
257 sum_diff2 += diff.dot(diff);
258 }
259 // else
260 // cout << "Point: " << point_id << "has at least one spurious
261 // observation" <<endl;
262
263 pointid_2_trueid.insert(make_pair(point_id, i));
264
265 ++point_id;
266 }
267 }
268
269 cout << endl;
270 optimizer.initializeOptimization();
271
272 optimizer.setVerbose(true);
273
274 if (STRUCTURE_ONLY) {
275 cout << "Performing structure-only BA:" << endl;
276 g2o::StructureOnlySolver<3> structure_only_ba;
278 for (g2o::OptimizableGraph::VertexIDMap::const_iterator it =
279 optimizer.vertices().begin();
280 it != optimizer.vertices().end(); ++it) {
282 static_cast<g2o::OptimizableGraph::Vertex*>(it->second);
283 if (v->dimension() == 3) points.push_back(v);
284 }
285
286 structure_only_ba.calc(points, 10);
287 }
288
289 cout << endl;
290 cout << "Performing full BA:" << endl;
291 optimizer.optimize(10);
292
293 cout << endl;
294 cout << "Point error before optimisation (inliers only): "
295 << sqrt(sum_diff2 / inliers.size()) << endl;
296
297 sum_diff2 = 0;
298
299 for (unordered_map<int, int>::iterator it = pointid_2_trueid.begin();
300 it != pointid_2_trueid.end(); ++it) {
301 g2o::HyperGraph::VertexIDMap::iterator v_it =
302 optimizer.vertices().find(it->first);
303
304 if (v_it == optimizer.vertices().end()) {
305 cerr << "Vertex " << it->first << " not in graph!" << endl;
306 exit(-1);
307 }
308
309 g2o::VertexPointXYZ* v_p = dynamic_cast<g2o::VertexPointXYZ*>(v_it->second);
310
311 if (v_p == 0) {
312 cerr << "Vertex " << it->first << "is not a PointXYZ!" << endl;
313 exit(-1);
314 }
315
316 Vector3d diff = v_p->estimate() - true_points[it->second];
317
318 if (inliers.find(it->first) == inliers.end()) continue;
319
320 sum_diff2 += diff.dot(diff);
321 }
322
323 cout << "Point error after optimisation (inliers only): "
324 << sqrt(sum_diff2 / inliers.size()) << endl;
325 cout << endl;
326}
static int uniform(int from, int to)
Definition ba_demo.cpp:53
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()
Point vertex, XYZ, is in types_sba.
Definition types_icp.h:342
const VertexContainer & vertices() const
const VertexIDMap & vertices() const
basic solver for Ax = b which has to reimplemented for different linear algebra libraries
linear solver using dense cholesky decomposition
linear solver which uses the sparse Cholesky solver from Eigen
void setRobustKernel(RobustKernel *ptr)
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
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
Implementation of the Levenberg Algorithm.
Huber Cost Function.
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)
This is a solver for "structure-only" optimization".
OptimizationAlgorithm::SolverResult calc(OptimizableGraph::VertexContainer &vertices, int num_iters, int num_max_trials=10)
Vertex for a tracked point in space.
Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its p...
Definition types_icp.h:228
static void setKcam(double fx, double fy, double cx, double cy, double tx)
Definition types_icp.h:276
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition jet.h:444
std::vector< OptimizableGraph::Vertex * > VertexContainer
vector container for vertices
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)

References g2o::OptimizableGraph::addEdge(), g2o::OptimizableGraph::addVertex(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::OptimizableGraph::Vertex::dimension(), g2o::BaseVertex< D, T >::estimate(), g2o::Sampler::gaussRand(), g2o::BaseEdge< D, E >::information(), g2o::SparseOptimizer::initializeOptimization(), g2o::SparseOptimizer::optimize(), g2o::SparseOptimizer::setAlgorithm(), g2o::VertexSCam::setAll(), g2o::BaseVertex< D, T >::setEstimate(), g2o::OptimizableGraph::Vertex::setFixed(), g2o::OptimizableGraph::Vertex::setId(), g2o::VertexSCam::setKcam(), g2o::OptimizableGraph::Vertex::setMarginalized(), g2o::BaseEdge< D, E >::setMeasurement(), g2o::OptimizableGraph::Edge::setRobustKernel(), g2o::SparseOptimizer::setVerbose(), Sample::uniform(), g2o::Sampler::uniformRand(), g2o::HyperGraph::Edge::vertices(), and g2o::HyperGraph::vertices().