g2o
ba_anchored_inverse_depth_demo.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2012 H. Strasdat
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #include <Eigen/StdVector>
28 #include <iostream>
29 #include <stdint.h>
30 
31 #include <unordered_set>
32 
34 #include "g2o/core/block_solver.h"
35 #include "g2o/core/solver.h"
41 //#include "g2o/math_groups/se3quat.h"
43 
44 using namespace Eigen;
45 using namespace std;
46 
47 
48 class Sample{
49 public:
50  static int uniform(int from, int to);
51  static double uniform();
52  static double gaussian(double sigma);
53 };
54 
55 static double uniform_rand(double lowerBndr, double upperBndr){
56  return lowerBndr + ((double) std::rand() / (RAND_MAX + 1.0)) * (upperBndr - lowerBndr);
57 }
58 
59 static double gauss_rand(double mean, double sigma){
60  double x, y, r2;
61  do {
62  x = -1.0 + 2.0 * uniform_rand(0.0, 1.0);
63  y = -1.0 + 2.0 * uniform_rand(0.0, 1.0);
64  r2 = x * x + y * y;
65  } while (r2 > 1.0 || r2 == 0.0);
66  return mean + sigma * y * std::sqrt(-2.0 * log(r2) / r2);
67 }
68 
69 int Sample::uniform(int from, int to){
70  return static_cast<int>(uniform_rand(from, to));
71 }
72 
73 double Sample::uniform(){
74  return uniform_rand(0., 1.);
75 }
76 
77 double Sample::gaussian(double sigma){
78  return gauss_rand(0., sigma);
79 }
80 
81 Vector2d project2d(const Vector3d& v){
82  Vector2d res;
83  res(0) = v(0)/v(2);
84  res(1) = v(1)/v(2);
85  return res;
86 }
87 
88 Vector3d unproject2d(const Vector2d& v){
89  Vector3d res;
90  res(0) = v(0);
91  res(1) = v(1);
92  res(2) = 1;
93  return res;
94 }
95 
96 inline Vector3d invert_depth(const Vector3d & x){
97  return unproject2d(x.head<2>())/x[2];
98 }
99 
100 int main(int argc, const char* argv[]){
101  if (argc<2)
102  {
103  cout << endl;
104  cout << "Please type: " << endl;
105  cout << "ba_demo [PIXEL_NOISE] [OUTLIER RATIO] [ROBUST_KERNEL] [SCHUR-TRICK]" << endl;
106  cout << 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;
111  cout << endl;
112  cout << "Note, if OUTLIER_RATIO is above 0, ROBUST_KERNEL should be set to 1==true." << endl;
113  cout << endl;
114  exit(0);
115  }
116 
117  double PIXEL_NOISE = atof(argv[1]);
118 
119  double OUTLIER_RATIO = 0.0;
120  if (argc>2){
121  OUTLIER_RATIO = atof(argv[2]);
122  }
123 
124  bool ROBUST_KERNEL = false;
125  if (argc>3){
126  ROBUST_KERNEL = atoi(argv[3]) != 0;
127  }
128 
129  bool SCHUR_TRICK = true;
130  if (argc>4){
131  SCHUR_TRICK = atoi(argv[4]) != 0;
132  }
133 
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;
138 
139  g2o::SparseOptimizer optimizer;
140  optimizer.setVerbose(false);
142  if (SCHUR_TRICK){
144 
145  linearSolver
148  g2o::BlockSolver_6_3 * solver_ptr
149  = new g2o::BlockSolver_6_3(linearSolver);
150  solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr);
151  } else {
153  linearSolver
156  g2o::BlockSolverX * solver_ptr
157  = new g2o::BlockSolverX(linearSolver);
158  solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr);
159  }
160 
161  optimizer.setAlgorithm(solver);
162 
163  vector<Vector3d> true_points;
164  for (size_t i=0;i<500; ++i){
165  true_points.push_back(Vector3d((Sample::uniform()-0.5)*3,
166  Sample::uniform()-0.5,
167  Sample::uniform()+3));
168  }
169 
170  double focal_length= 1000.;
171  Vector2d principal_point(320., 240.);
172 
173  vector<g2o::SE3Quat,
174  aligned_allocator<g2o::SE3Quat> > true_poses;
175 
176  g2o::CameraParameters * cam_params
177  = new g2o::CameraParameters (focal_length, principal_point, 0.);
178  cam_params->setId(0);
179 
180  if (!optimizer.addParameter(cam_params)){
181  assert(false);
182  }
183 
184  int vertex_id = 0;
185  for (size_t i=0; i<15; ++i){
186  Vector3d trans(i*0.04-1.,0,0);
187  Eigen:: Quaterniond q;
188  q.setIdentity();
189  g2o::SE3Quat T_me_from_world(q,trans);
190  g2o::VertexSE3Expmap * v_se3
191  = new g2o::VertexSE3Expmap();
192  v_se3->setId(vertex_id);
193  v_se3->setEstimate(T_me_from_world);
194 
195  if (i<2){
196  v_se3->setFixed(true);
197  }
198 
199  optimizer.addVertex(v_se3);
200  true_poses.push_back(T_me_from_world);
201  vertex_id++;
202  }
203  int point_id=vertex_id;
204  int point_num = 0;
205  double sum_diff2 = 0;
206 
207  cout << endl;
208  unordered_map<int,int> pointid_2_trueid;
209  unordered_map<int,int> pointid_2_anchorid;
210  unordered_set<int> inliers;
211 
212  for (size_t i=0; i<true_points.size(); ++i){
214  = new g2o::VertexSBAPointXYZ();
215  int num_obs = 0;
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)));
218 
219  if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480) {
220  ++num_obs;
221  }
222  }
223 
224  int anchor_frame_id = -1;
225  if (num_obs>=2){
226  bool inlier = true;
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)));
229 
230  if (z[0]>=0 && z[1]>=0 && z[0]<640 && z[1]<480) {
231  if (anchor_frame_id==-1){
232  anchor_frame_id = j;
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);
236  if (SCHUR_TRICK){
237  v_p->setMarginalized(true);
238  }
239  Vector3d point_w = true_points.at(i)
240  + Vector3d(Sample::gaussian(1),
241  Sample::gaussian(1),
242  Sample::gaussian(1));
243 
244  Vector3d point_anchor = T_anchor_from_world*point_w;
245  v_p->setEstimate(invert_depth(point_anchor));
246  optimizer.addVertex(v_p);
247  }
248 
249  double sam = Sample::uniform();
250  if (sam<OUTLIER_RATIO){
251  z = Vector2d(Sample::uniform(0,640),
252  Sample::uniform(0,480));
253  inlier= false;
254  }
255  z += Vector2d(Sample::gaussian(PIXEL_NOISE),
256  Sample::gaussian(PIXEL_NOISE));
258  = new g2o::EdgeProjectPSI2UV();
259 
260  e->resize(3);
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));
266 
267  e->setMeasurement(z);
268  e->information() = Matrix2d::Identity();
269 
270  if (ROBUST_KERNEL) {
272  e->setRobustKernel(rk);
273  }
274 
275  e->setParameterId(0, 0);
276  optimizer.addEdge(e);
277  }
278  }
279  if (inlier){
280  inliers.insert(point_id);
281  Vector3d diff = true_poses[anchor_frame_id].inverse()*invert_depth(v_p->estimate())
282  - true_points[i];
283 
284  sum_diff2 += diff.dot(diff);
285  }
286  pointid_2_trueid.insert(make_pair(point_id,i));
287  ++point_id;
288  ++point_num;
289  }
290  }
291  cout << endl;
292  optimizer.initializeOptimization();
293  optimizer.setVerbose(true);
294  cout << endl;
295  cout << "Performing full BA:" << endl;
296 
297  optimizer.optimize(10);
298 
299  cout << endl;
300  cout << "Point error before optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
301  point_num = 0;
302  sum_diff2 = 0;
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;
309  exit(-1);
310  }
312  = dynamic_cast< g2o::VertexSBAPointXYZ * > (v_it->second);
313  if (v_p==0){
314  cerr << "Vertex " << it->first << "is not a PointXYZ!" << endl;
315  exit(-1);
316  }
317  int anchorframe_id = pointid_2_anchorid.find(it->first)->second;
318  v_it
319  = optimizer.vertices().find(anchorframe_id);
320  if (v_it==optimizer.vertices().end()){
321  cerr << "Vertex " << it->first << " not in graph!" << endl;
322  exit(-1);
323  }
324  g2o::VertexSE3Expmap * v_anchor
325  = dynamic_cast< g2o::VertexSE3Expmap * > (v_it->second);
326  if (v_p==0){
327  cerr << "Vertex " << it->first << "is not a SE3Expmap!" << endl;
328  exit(-1);
329  }
330  Vector3d diff = v_anchor->estimate().inverse()*invert_depth(v_p->estimate())-true_points[it->second];
331  if (inliers.find(it->first)==inliers.end())
332  continue;
333  sum_diff2 += diff.dot(diff);
334  ++point_num;
335  }
336  cout << "Point error after optimisation (inliers only): " << sqrt(sum_diff2/point_num) << endl;
337  cout << endl;
338 }
Vector2D cam_map(const Vector3D &trans_xyz) const
BlockSolver< BlockSolverTraits< 6, 3 > > BlockSolver_6_3
Definition: block_solver.h:181
Huber Cost Function.
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)
Definition: base_edge.h:76
void setRobustKernel(RobustKernel *ptr)
Traits::PoseMatrixType PoseMatrixType
Definition: block_solver.h:101
void setVertex(size_t i, Vertex *v)
Definition: hyper_graph.h:194
SE3Quat inverse() const
Definition: se3quat.h:120
const VertexIDMap & vertices() const
Definition: hyper_graph.h:225
Point vertex, XYZ.
Definition: types_sba.h:137
void setId(int id_)
Definition: parameter.cpp:35
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
Traits::LinearSolverType LinearSolverType
Definition: block_solver.h:110
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()
Definition: ba_demo.cpp:73
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 $
Definition: CMakeLists.txt:2
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()
Definition: base_vertex.h:101
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
Definition: base_edge.h:67
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
Definition: base_vertex.h:99
Implementation of a solver operating on the blocks of the Hessian.
Definition: block_solver.h:96
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)
Definition: ba_demo.cpp:77
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX
Definition: block_solver.h:179