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);
100 int main(
int argc,
const char* argv[]){
104 cout <<
"Please type: " << endl;
105 cout <<
"ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [SCHUR-TRICK]" << endl;
107 cout <<
"PIXEL_NOISE: noise in image space (E.g.: 1)" << endl;
108 cout <<
"OUTLIER_RATIO: probability of spuroius observation (default: 0.0)" << endl;
109 cout <<
"ROBUST_KERNEL: use robust kernel (0 or 1; default: 0==false)" << endl;
110 cout <<
"SCHUR-TRICK: Use Schur-complement trick (0 or 1; default: 0==true)" << endl;
112 cout <<
"Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to 1==true." << endl;
117 double PIXEL_NOISE = atof(argv[1]);
119 double OUTLIER_RATIO = 0.0;
121 OUTLIER_RATIO = atof(argv[2]);
124 bool ROBUST_KERNEL =
false;
126 ROBUST_KERNEL = atoi(argv[3]) != 0;
129 bool SCHUR_TRICK =
true;
131 SCHUR_TRICK = atoi(argv[4]) != 0;
134 cout <<
"PIXEL_NOISE: " << PIXEL_NOISE << endl;
135 cout <<
"OUTLIER_RATIO: " << OUTLIER_RATIO<< endl;
136 cout <<
"ROBUST_KERNEL: " << ROBUST_KERNEL << endl;
137 cout <<
"SCHUR-TRICK: " << SCHUR_TRICK << endl;
163 vector<Vector3d> true_points;
164 for (
size_t i=0;i<500; ++i){
170 double focal_length= 1000.;
171 Vector2d principal_point(320., 240.);
174 aligned_allocator<g2o::SE3Quat> > true_poses;
178 cam_params->
setId(0);
185 for (
size_t i=0; i<15; ++i){
186 Vector3d trans(i*0.04-1.,0,0);
187 Eigen:: Quaterniond q;
189 g2o::SE3Quat T_me_from_world(q,trans);
192 v_se3->
setId(vertex_id);
200 true_poses.push_back(T_me_from_world);
203 int point_id=vertex_id;
205 double sum_diff2 = 0;
208 unordered_map<int,int> pointid_2_trueid;
209 unordered_map<int,int> pointid_2_anchorid;
210 unordered_set<int> inliers;
212 for (
size_t i=0; i<true_points.size(); ++i){
216 for (
size_t j=0; j<true_poses.size(); ++j) {
217 Vector2d z = cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
219 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480) {
224 int anchor_frame_id = -1;
227 for (
size_t j=0; j<true_poses.size(); ++j){
228 Vector2d z = cam_params->
cam_map(true_poses.at(j).map(true_points.at(i)));
230 if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480) {
231 if (anchor_frame_id==-1){
233 pointid_2_anchorid.insert(make_pair(point_id, anchor_frame_id));
234 g2o::SE3Quat T_anchor_from_world = true_poses[anchor_frame_id];
235 v_p->
setId(point_id);
239 Vector3d point_w = true_points.at(i)
244 Vector3d point_anchor = T_anchor_from_world*point_w;
250 if (sam<OUTLIER_RATIO){
261 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(v_p));
262 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>
263 (optimizer.
vertices().find(j)->second));
264 e->
setVertex(2, dynamic_cast<g2o::OptimizableGraph::Vertex*>
265 (optimizer.
vertices().find(anchor_frame_id)->second));
280 inliers.insert(point_id);
284 sum_diff2 += diff.dot(diff);
286 pointid_2_trueid.insert(make_pair(point_id,i));
295 cout <<
"Performing full BA:" << endl;
300 cout <<
"Point error before optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
303 for (unordered_map<int,int>::iterator it=pointid_2_trueid.begin();
304 it!=pointid_2_trueid.end(); ++it){
305 g2o::HyperGraph::VertexIDMap::iterator v_it
306 = optimizer.
vertices().find(it->first);
307 if (v_it==optimizer.
vertices().end()){
308 cerr <<
"Vertex " << it->first <<
" not in graph!" << endl;
314 cerr <<
"Vertex " << it->first <<
"is not a PointXYZ!" << endl;
317 int anchorframe_id = pointid_2_anchorid.find(it->first)->second;
319 = optimizer.
vertices().find(anchorframe_id);
320 if (v_it==optimizer.
vertices().end()){
321 cerr <<
"Vertex " << it->first <<
" not in graph!" << endl;
327 cerr <<
"Vertex " << it->first <<
"is not a SE3Expmap!" << endl;
331 if (inliers.find(it->first)==inliers.end())
333 sum_diff2 += diff.dot(diff);
336 cout <<
"Point error after optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
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)
static double uniform_rand(double lowerBndr, double upperBndr)
virtual void setMeasurement(const Measurement &m)
void setRobustKernel(RobustKernel *ptr)
Traits::PoseMatrixType PoseMatrixType
void setVertex(size_t i, Vertex *v)
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 ...
bool setParameterId(int argNum, int paramId)
void setVerbose(bool verbose)
if(POLICY CMP0020) cmake_policy(SET CMP0020 OLD) endif() if(Qt4_FOUND) endif() if(Qt5_FOUND) endif() ADD_LIBRARY(viewer_library $
void setAlgorithm(OptimizationAlgorithm *algorithm)
Vector3d unproject2d(const Vector2d &v)
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()
static double gauss_rand(double mean, double sigma)
int main(int argc, const char *argv[])
virtual void resize(size_t size)
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
Vector2d project2d(const Vector3d &v)
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)
Vector3d invert_depth(const Vector3d &x)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
static double gaussian(double sigma)
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX