Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include <Eigen/StdVector>
00018 #include <tr1/random>
00019 #include <iostream>
00020 #include <stdint.h>
00021 #include <tr1/unordered_set>
00022
00023 #include "g2o/core/graph_optimizer_sparse.h"
00024 #include "g2o/core/block_solver.h"
00025 #include "g2o/core/solver.h"
00026 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
00027 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
00028 #include "g2o/solvers/dense/linear_solver_dense.h"
00029 #include "g2o/types/sba/types_six_dof_expmap.h"
00030 #include "g2o/math_groups/se3quat.h"
00031 #include "g2o/core/structure_only_solver.h"
00032
00033 using namespace Eigen;
00034 using namespace std;
00035
00036
00037 class Sample
00038 {
00039
00040 static tr1::ranlux_base_01 gen_real;
00041 static tr1::mt19937 gen_int;
00042 public:
00043 static int uniform(int from, int to);
00044
00045 static double uniform();
00046
00047 static double gaussian(double sigma);
00048 };
00049
00050
00051 tr1::ranlux_base_01 Sample::gen_real;
00052 tr1::mt19937 Sample::gen_int;
00053
00054 int Sample::uniform(int from, int to)
00055 {
00056 tr1::uniform_int<int> unif(from, to);
00057 int sam = unif(gen_int);
00058 return sam;
00059 }
00060
00061 double Sample::uniform()
00062 {
00063 std::tr1::uniform_real<double> unif(0.0, 1.0);
00064 double sam = unif(gen_real);
00065 return sam;
00066 }
00067
00068 double Sample::gaussian(double sigma)
00069 {
00070 std::tr1::normal_distribution<double> gauss(0.0, sigma);
00071 double sam = gauss(gen_real);
00072 return sam;
00073 }
00074
00075 int main(int argc, const char* argv[])
00076 {
00077 if (argc<2)
00078 {
00079 cout << endl;
00080 cout << "Please type: " << endl;
00081 cout << "ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [STRUCTURE_ONLY] [DENSE]" << endl;
00082 cout << endl;
00083 cout << "PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
00084 cout << "OUTLIER_RATIO: probability of spuroius observation (default: 0.0)" << endl;
00085 cout << "ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)" << endl;
00086 cout << "STRUCTURE_ONLY: performe structure-only BA to get better point initializations (0 or 1; default: 0==false)" << endl;
00087 cout << "DENSE: Use dense solver (0 or 1; default: 0==false)" << endl;
00088 cout << endl;
00089 cout << "Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to 1==true." << endl;
00090 cout << endl;
00091 exit(0);
00092 }
00093
00094 double PIXEL_NOISE = atof(argv[1]);
00095
00096 double OUTLIER_RATIO = 0.0;
00097
00098 if (argc>2)
00099 {
00100 OUTLIER_RATIO = atof(argv[2]);
00101 }
00102
00103 bool ROBUST_KERNEL = false;
00104 if (argc>3)
00105 {
00106 ROBUST_KERNEL = atof(argv[3]);
00107 }
00108 bool STRUCTURE_ONLY = false;
00109 if (argc>4)
00110 {
00111 STRUCTURE_ONLY = atof(argv[4]);
00112 }
00113
00114 bool DENSE = false;
00115 if (argc>5)
00116 {
00117 DENSE = atof(argv[5]);
00118 }
00119
00120 cout << "PIXEL_NOISE: " << PIXEL_NOISE << endl;
00121 cout << "OUTLIER_RATIO: " << OUTLIER_RATIO<< endl;
00122 cout << "ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
00123 cout << "STRUCTURE_ONLY: " << STRUCTURE_ONLY<< endl;
00124 cout << "DENSE: "<< DENSE << endl;
00125
00126
00127
00128 g2o::SparseOptimizer optimizer;
00129 optimizer.setMethod(g2o::SparseOptimizer::LevenbergMarquardt);
00130 optimizer.setVerbose(false);
00131 g2o::BlockSolver_6_3::LinearSolverType * linearSolver;
00132 if (DENSE)
00133 {
00134 linearSolver= new g2o::LinearSolverDense<g2o
00135 ::BlockSolver_6_3::PoseMatrixType>();
00136 }
00137 else
00138 {
00139 linearSolver
00140 = new g2o::LinearSolverCholmod<g2o
00141 ::BlockSolver_6_3::PoseMatrixType>();
00142 }
00143
00144
00145 g2o::BlockSolver_6_3 * solver_ptr
00146 = new g2o::BlockSolver_6_3(&optimizer,linearSolver);
00147
00148
00149 optimizer.setSolver(solver_ptr);
00150
00151
00152 vector<Vector3d> true_points;
00153 for (size_t i=0;i<500; ++i)
00154 {
00155 true_points.push_back(Vector3d((Sample::uniform()-0.5)*3,
00156 Sample::uniform()-0.5,
00157 Sample::uniform()+10));
00158 }
00159
00160
00161 Vector2d focal_length(1000,1000);
00162 Vector2d principal_point(320,240);
00163
00164
00165 vector<g2o::SE3Quat,
00166 aligned_allocator<g2o::SE3Quat> > true_poses;
00167
00168 int vertex_id = 0;
00169 for (size_t i=0; i<5; ++i)
00170 {
00171
00172
00173 Vector3d trans(i*0.04-1.,0,0);
00174
00175 Eigen:: Quaterniond q;
00176 q.setIdentity();
00177 g2o::SE3Quat pose(q,trans);
00178
00179
00180 g2o::VertexSE3Expmap * v_se3
00181 = new g2o::VertexSE3Expmap();
00182
00183 v_se3->setId(vertex_id);
00184
00185 v_se3->estimate() = pose;
00186
00187
00188 if (i<2)
00189 {
00190 v_se3->setFixed(true);
00191 }
00192
00193 v_se3->_focal_length[0] = focal_length[0];
00194 v_se3->_focal_length[1] = focal_length[1];
00195
00196 v_se3->_principle_point[0] = principal_point[0];
00197 v_se3->_principle_point[1] = principal_point[1];
00198
00199
00200 optimizer.addVertex(v_se3);
00201
00202 true_poses.push_back(pose);
00203
00204 vertex_id++;
00205
00206 }
00207 int point_id=vertex_id;
00208
00209
00210
00211 int point_num = 0;
00212 double sum_diff2 = 0;
00213
00214 cout << endl;
00215 tr1::unordered_map<int,int> pointid_2_trueid;
00216 tr1::unordered_set<int> inliers;
00217
00218 for (size_t i=0; i<true_points.size(); ++i)
00219 {
00220 g2o::VertexPointXYZ * v_p
00221 = new g2o::VertexPointXYZ();
00222
00223
00224 v_p->setId(point_id);
00225 v_p->setMarginalized(true);
00226 v_p->estimate() = true_points.at(i)
00227 + Vector3d(Sample::gaussian(1),
00228 Sample::gaussian(1),
00229 Sample::gaussian(1));
00230
00231
00232
00233 int num_obs = 0;
00234
00235 for (size_t j=0; j<true_poses.size(); ++j)
00236 {
00237 Vector2d z
00238 = dynamic_cast<g2o::VertexSE3Expmap*>
00239 (optimizer.vertices().find(j)->second)
00240 ->cam_map(true_poses.at(j).map(true_points.at(i)));
00241
00242 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480)
00243 {
00244 ++num_obs;
00245 }
00246 }
00247
00248 if (num_obs>=2)
00249 {
00250
00251 bool inlier = true;
00252 for (size_t j=0; j<true_poses.size(); ++j)
00253 {
00254 Vector2d z
00255 = dynamic_cast<g2o::VertexSE3Expmap*>
00256 (optimizer.vertices().find(j)->second)
00257 ->cam_map(true_poses.at(j).map(true_points.at(i)));
00258
00259 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480)
00260 {
00261 double sam = Sample::uniform();
00262 if (sam<OUTLIER_RATIO)
00263 {
00264 z = Vector2d(Sample::uniform(0,640),
00265 Sample::uniform(0,480));
00266
00267 inlier= false;
00268 }
00269
00270 z += Vector2d(Sample::gaussian(PIXEL_NOISE),
00271 Sample::gaussian(PIXEL_NOISE));
00272
00273 g2o::EdgeProjectXYZ2UV * e
00274 = new g2o::EdgeProjectXYZ2UV();
00275
00276
00277 e->vertices()[0]
00278 = dynamic_cast<g2o::OptimizableGraph::Vertex*>(v_p);
00279
00280 e->vertices()[1]
00281 = dynamic_cast<g2o::OptimizableGraph::Vertex*>
00282 (optimizer.vertices().find(j)->second);
00283
00284 e->measurement() = z;
00285 e->inverseMeasurement() = -z;
00286 e->information() = Matrix2d::Identity();
00287
00288 e->setRobustKernel(ROBUST_KERNEL);
00289 e->setHuberWidth(1);
00290
00291 optimizer.addEdge(e);
00292
00293
00294 }
00295
00296 }
00297
00298 if (inlier)
00299 {
00300 inliers.insert(point_id);
00301 Vector3d diff = v_p->estimate() - true_points[i];
00302
00303 sum_diff2 += diff.dot(diff);
00304 }
00305
00306
00307
00308
00309 optimizer.addVertex(v_p);
00310
00311
00312
00313
00314 pointid_2_trueid.insert(make_pair(point_id,i));
00315
00316 ++point_id;
00317 ++point_num;
00318
00319
00320 }
00321
00322 }
00323
00324
00325 cout << endl;
00326 optimizer.initializeOptimization();
00327
00328 optimizer.setVerbose(true);
00329
00330
00331 g2o::StructureOnlySolver<3> structure_only_ba;
00332
00333 if (STRUCTURE_ONLY)
00334 {
00335 cout << "Performing structure-only BA:" << endl;
00336 structure_only_ba.setVerbose(true);
00337 structure_only_ba.calc(optimizer.vertices(),
00338 10);
00339
00340
00341 }
00342
00343 cout << endl;
00344 cout << "Performing full BA:" << endl;
00345 optimizer.optimize(10);
00346
00347 cout << endl;
00348 cout << "Point error before optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
00349
00350
00351 point_num = 0;
00352 sum_diff2 = 0;
00353
00354
00355 for (tr1::unordered_map<int,int>::iterator it=pointid_2_trueid.begin();
00356 it!=pointid_2_trueid.end(); ++it)
00357 {
00358
00359 g2o::HyperGraph::VertexIDMap::iterator v_it
00360 = optimizer.vertices().find(it->first);
00361
00362 if (v_it==optimizer.vertices().end())
00363 {
00364 cerr << "Vertex " << it->first << " not in graph!" << endl;
00365 exit(-1);
00366 }
00367
00368 g2o::VertexPointXYZ * v_p
00369 = dynamic_cast< g2o::VertexPointXYZ * > (v_it->second);
00370
00371 if (v_p==0)
00372 {
00373 cerr << "Vertex " << it->first << "is not a PointXYZ!" << endl;
00374 exit(-1);
00375 }
00376
00377 Vector3d diff = v_p->estimate()-true_points[it->second];
00378
00379 if (inliers.find(it->first)==inliers.end())
00380 continue;
00381
00382 sum_diff2 += diff.dot(diff);
00383
00384 ++point_num;
00385 }
00386
00387 cout << "Point error after optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
00388 cout << endl;
00389
00390 }