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
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
136
137
138 vector<Vector3d> true_points;
139 for (size_t i = 0; i < 500; ++i) {
140 true_points.push_back(
144 }
145
146 Vector2d focal_length(500, 500);
147 Vector2d principal_point(320, 240);
148 double baseline = 0.075;
149
150 vector<Eigen::Isometry3d, aligned_allocator<Eigen::Isometry3d>> true_poses;
151
152
154 principal_point[1], baseline);
155
156
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
168
169 v_se3->
setId(vertex_id);
172
174
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
188 for (size_t i = 0; i < true_points.size(); ++i) {
190
191 v_p->
setId(point_id);
197
198 int num_obs = 0;
199
200 for (size_t j = 0; j < true_poses.size(); ++j) {
201 Vector3d z;
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) {
212
213 bool inlier = true;
214 for (size_t j = 0; j < true_poses.size(); ++j) {
215 Vector3d z;
217 ->mapPoint(z, true_points.at(i));
218
219 if (z[0] >= 0 && z[1] >= 0 && z[0] < 640 && z[1] < 480) {
221 if (sam < OUTLIER_RATIO) {
224 z(2) = z(0) - z(2);
225
226 inlier = false;
227 }
228
232
234
236
238 optimizer.
vertices().find(j)->second);
239
241
243
244 if (ROBUST_KERNEL) {
247 }
248
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
260
261
262
263 pointid_2_trueid.insert(make_pair(point_id, i));
264
265 ++point_id;
266 }
267 }
268
269 cout << endl;
271
273
274 if (STRUCTURE_ONLY) {
275 cout << "Performing structure-only BA:" << endl;
278 for (g2o::OptimizableGraph::VertexIDMap::const_iterator it =
280 it != optimizer.
vertices().end(); ++it) {
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;
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
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)
virtual void setMeasurement(const Measurement &m)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
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.
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
virtual void setId(int id)
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.
static double gaussRand(double mean, double sigma)
static double uniformRand(double lowerBndr, double upperBndr)
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...
static void setKcam(double fx, double fy, double cx, double cy, double tx)
Jet< T, N > sqrt(const Jet< T, N > &f)
std::vector< OptimizableGraph::Vertex * > VertexContainer
vector container for vertices
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)