98 cout <<
"Please type: " << endl;
99 cout <<
"ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [STRUCTURE_ONLY] [DENSE]" << endl;
101 cout <<
"PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
102 cout <<
"OUTLIER_RATIO: probability of spuroius observation (default: 0.0)" << endl;
103 cout <<
"ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)" << endl;
104 cout <<
"STRUCTURE_ONLY: performe structure-only BA to get better point initializations (0 or 1; default: 0==false)" << endl;
105 cout <<
"DENSE: Use dense solver (0 or 1; default: 0==false)" << endl;
107 cout <<
"Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to 1==true." << endl;
112 double PIXEL_NOISE = atof(argv[1]);
114 double OUTLIER_RATIO = 0.0;
118 OUTLIER_RATIO = atof(argv[2]);
121 bool ROBUST_KERNEL =
false;
124 ROBUST_KERNEL = atoi(argv[3]) != 0;
126 bool STRUCTURE_ONLY =
false;
129 STRUCTURE_ONLY = atoi(argv[4]) != 0;
135 DENSE = atoi(argv[5]) != 0;
138 cout <<
"PIXEL_NOISE: " << PIXEL_NOISE << endl;
139 cout <<
"OUTLIER_RATIO: " << OUTLIER_RATIO<< endl;
140 cout <<
"ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
141 cout <<
"STRUCTURE_ONLY: " << STRUCTURE_ONLY<< endl;
142 cout <<
"DENSE: "<< DENSE << endl;
152 cerr <<
"Using DENSE" << endl;
156 #ifdef G2O_HAVE_CHOLMOD 157 cerr <<
"Using CHOLMOD" << endl;
159 #elif defined G2O_HAVE_CSPARSE 161 cerr <<
"Using CSPARSE" << endl;
163 #error neither CSparse nor Cholmod are available 176 vector<Vector3d> true_points;
177 for (
size_t i=0;i<500; ++i)
185 Vector2d focal_length(500,500);
186 Vector2d principal_point(320,240);
187 double baseline = 0.075;
190 vector<Eigen::Isometry3d,
191 aligned_allocator<Eigen::Isometry3d> > true_poses;
195 principal_point[0],principal_point[1],
200 for (
size_t i=0; i<5; ++i)
204 Vector3d trans(i*0.04-1.,0,0);
206 Eigen:: Quaterniond q;
208 Eigen::Isometry3d pose;
210 pose.translation() = trans;
216 v_se3->
setId(vertex_id);
224 true_poses.push_back(pose);
228 int point_id=vertex_id;
230 double sum_diff2 = 0;
233 unordered_map<int,int> pointid_2_trueid;
234 unordered_set<int> inliers;
237 for (
size_t i=0; i<true_points.size(); ++i)
243 v_p->
setId(point_id);
252 for (
size_t j=0; j<true_poses.size(); ++j)
256 (optimizer.
vertices().find(j)->second)
257 ->mapPoint(z,true_points.at(i));
259 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480)
270 for (
size_t j=0; j<true_poses.size(); ++j)
274 (optimizer.
vertices().find(j)->second)
275 ->mapPoint(z,true_points.at(i));
277 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480)
280 if (sam<OUTLIER_RATIO)
303 (optimizer.
vertices().find(j)->second);
323 inliers.insert(point_id);
324 Vector3d diff = v_p->
estimate() - true_points[i];
326 sum_diff2 += diff.dot(diff);
331 pointid_2_trueid.insert(make_pair(point_id,i));
346 cout <<
"Performing structure-only BA:" << endl;
349 for (g2o::OptimizableGraph::VertexIDMap::const_iterator it = optimizer.
vertices().begin(); it != optimizer.
vertices().end(); ++it) {
355 structure_only_ba.
calc(points, 10);
359 cout <<
"Performing full BA:" << endl;
363 cout <<
"Point error before optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
370 for (unordered_map<int,int>::iterator it=pointid_2_trueid.begin();
371 it!=pointid_2_trueid.end(); ++it)
374 g2o::HyperGraph::VertexIDMap::iterator v_it
375 = optimizer.
vertices().find(it->first);
377 if (v_it==optimizer.
vertices().end())
379 cerr <<
"Vertex " << it->first <<
" not in graph!" << endl;
388 cerr <<
"Vertex " << it->first <<
"is not a PointXYZ!" << endl;
392 Vector3d diff = v_p->
estimate()-true_points[it->second];
394 if (inliers.find(it->first)==inliers.end())
397 sum_diff2 += diff.dot(diff);
402 cout <<
"Point error after optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
std::vector< OptimizableGraph::Vertex * > VertexContainer
vector container for vertices
BlockSolver< BlockSolverTraits< 6, 3 > > BlockSolver_6_3
Implementation of the Levenberg Algorithm.
int optimize(int iterations, bool online=false)
This is a solver for "structure-only" optimization".
virtual void setMeasurement(const Measurement &m)
void setRobustKernel(RobustKernel *ptr)
linear solver using dense cholesky decomposition
const VertexIDMap & vertices() const
Traits::LinearSolverType LinearSolverType
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
int dimension() const
dimension of the estimated state belonging to this node
const VertexContainer & vertices() const
void setVerbose(bool verbose)
linear solver which uses CSparse
void setAlgorithm(OptimizationAlgorithm *algorithm)
basic solver for Ax = b which has to reimplemented for different linear algebra libraries ...
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
const EstimateType & estimate() const
return the current estimate of the vertex
Implementation of a solver operating on the blocks of the Hessian.
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
static void setKcam(double fx, double fy, double cx, double cy, double tx)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
Point vertex, XYZ, is in types_sba.
Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its p...
static double gaussian(double sigma)
OptimizationAlgorithm::SolverResult calc(OptimizableGraph::VertexContainer &vertices, int num_iters, int num_max_trials=10)