27 #include <Eigen/StdVector> 31 #include <unordered_set> 44 using namespace Eigen;
50 static int uniform(
int from,
int to);
51 static double uniform();
52 static double gaussian(
double sigma);
56 return lowerBndr + ((double) std::rand() / (RAND_MAX + 1.0)) * (upperBndr - lowerBndr);
65 }
while (r2 > 1.0 || r2 == 0.0);
66 return mean + sigma * y * std::sqrt(-2.0 * log(r2) / r2);
81 int main(
int argc,
const char* argv[]){
85 cout <<
"Please type: " << endl;
86 cout <<
"ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [STRUCTURE_ONLY] [DENSE]" << endl;
88 cout <<
"PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
89 cout <<
"OUTLIER_RATIO: probability of spuroius observation (default: 0.0)" << endl;
90 cout <<
"ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)" << endl;
91 cout <<
"STRUCTURE_ONLY: performe structure-only BA to get better point initializations (0 or 1; default: 0==false)" << endl;
92 cout <<
"DENSE: Use dense solver (0 or 1; default: 0==false)" << endl;
94 cout <<
"Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to 1==true." << endl;
99 double PIXEL_NOISE = atof(argv[1]);
100 double OUTLIER_RATIO = 0.0;
103 OUTLIER_RATIO = atof(argv[2]);
106 bool ROBUST_KERNEL =
false;
108 ROBUST_KERNEL = atoi(argv[3]) != 0;
110 bool STRUCTURE_ONLY =
false;
112 STRUCTURE_ONLY = atoi(argv[4]) != 0;
117 DENSE = atoi(argv[5]) != 0;
120 cout <<
"PIXEL_NOISE: " << PIXEL_NOISE << endl;
121 cout <<
"OUTLIER_RATIO: " << OUTLIER_RATIO<< endl;
122 cout <<
"ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
123 cout <<
"STRUCTURE_ONLY: " << STRUCTURE_ONLY<< endl;
124 cout <<
"DENSE: "<< DENSE << endl;
147 vector<Vector3d> true_points;
148 for (
size_t i=0;i<500; ++i)
155 double focal_length= 1000.;
156 Vector2d principal_point(320., 240.);
159 aligned_allocator<g2o::SE3Quat> > true_poses;
162 cam_params->
setId(0);
169 for (
size_t i=0; i<15; ++i) {
170 Vector3d trans(i*0.04-1.,0,0);
172 Eigen:: Quaterniond q;
174 g2o::SE3Quat pose(q,trans);
177 v_se3->
setId(vertex_id);
183 true_poses.push_back(pose);
186 int point_id=vertex_id;
188 double sum_diff2 = 0;
191 unordered_map<int,int> pointid_2_trueid;
192 unordered_set<int> inliers;
194 for (
size_t i=0; i<true_points.size(); ++i){
197 v_p->
setId(point_id);
204 for (
size_t j=0; j<true_poses.size(); ++j){
205 Vector2d z = cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
206 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480){
213 for (
size_t j=0; j<true_poses.size(); ++j){
215 = cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
217 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480){
219 if (sam<OUTLIER_RATIO){
228 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(v_p));
229 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>
230 (optimizer.
vertices().find(j)->second));
243 inliers.insert(point_id);
244 Vector3d diff = v_p->
estimate() - true_points[i];
246 sum_diff2 += diff.dot(diff);
248 pointid_2_trueid.insert(make_pair(point_id,i));
258 cout <<
"Performing structure-only BA:" << endl;
260 for (g2o::OptimizableGraph::VertexIDMap::const_iterator it = optimizer.
vertices().begin(); it != optimizer.
vertices().end(); ++it) {
265 structure_only_ba.
calc(points, 10);
269 cout <<
"Performing full BA:" << endl;
272 cout <<
"Point error before optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
275 for (unordered_map<int,int>::iterator it=pointid_2_trueid.begin();
276 it!=pointid_2_trueid.end(); ++it){
277 g2o::HyperGraph::VertexIDMap::iterator v_it
278 = optimizer.
vertices().find(it->first);
279 if (v_it==optimizer.
vertices().end()){
280 cerr <<
"Vertex " << it->first <<
" not in graph!" << endl;
286 cerr <<
"Vertex " << it->first <<
"is not a PointXYZ!" << endl;
289 Vector3d diff = v_p->
estimate()-true_points[it->second];
290 if (inliers.find(it->first)==inliers.end())
292 sum_diff2 += diff.dot(diff);
295 cout <<
"Point error after optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
std::vector< OptimizableGraph::Vertex * > VertexContainer
vector container for vertices
Vector2D cam_map(const Vector3D &trans_xyz) const
BlockSolver< BlockSolverTraits< 6, 3 > > BlockSolver_6_3
Implementation of the Levenberg Algorithm.
int optimize(int iterations, bool online=false)
int main(int argc, const char *argv[])
This is a solver for "structure-only" optimization".
virtual void setMeasurement(const Measurement &m)
void setRobustKernel(RobustKernel *ptr)
linear solver using dense cholesky decomposition
Traits::PoseMatrixType PoseMatrixType
void setVertex(size_t i, Vertex *v)
static double gauss_rand(double mean, double sigma)
const VertexIDMap & vertices() const
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
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 ...
static double uniform_rand(double lowerBndr, double upperBndr)
int dimension() const
dimension of the estimated state belonging to this node
bool setParameterId(int argNum, int paramId)
void setVerbose(bool verbose)
void setAlgorithm(OptimizationAlgorithm *algorithm)
basic solver for Ax = b which has to reimplemented for different linear algebra libraries ...
bool addParameter(Parameter *p)
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)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
static double gaussian(double sigma)
OptimizationAlgorithm::SolverResult calc(OptimizableGraph::VertexContainer &vertices, int num_iters, int num_max_trials=10)