SFMExample_bal_COLAMD_METIS.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 // For an explanation of headers, see SFMExample.cpp
20 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/slam/dataset.h> // for loading BAL datasets !
26 
27 #include <gtsam/base/timing.h>
28 
29 #include <vector>
30 
31 using namespace std;
32 using namespace gtsam;
35 
36 // We will be using a projection factor that ties a SFM_Camera to a 3D point.
37 // An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler
38 // calibration and has a total of 9 free parameters
40 
41 
42 int main(int argc, char* argv[]) {
43  // Find default file, but if an argument is given, try loading a file
44  string filename = findExampleDataFile("dubrovnik-3-7-pre");
45  if (argc > 1) filename = string(argv[1]);
46 
47  // Load the SfM data from file
48  SfmData mydata;
49  readBAL(filename, mydata);
50  cout << boost::format("read %1% tracks on %2% cameras\n") %
51  mydata.number_tracks() % mydata.number_cameras();
52 
53  // Create a factor graph
55 
56  // We share *one* noiseModel between all projection factors
57  auto noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
58 
59  // Add measurements to the factor graph
60  size_t j = 0;
61  for (const SfmTrack& track : mydata.tracks) {
62  for (const SfmMeasurement& m : track.measurements) {
63  size_t i = m.first;
64  Point2 uv = m.second;
65  graph.emplace_shared<MyFactor>(
66  uv, noise, C(i), P(j)); // note use of shorthand symbols C and P
67  }
68  j += 1;
69  }
70 
71  // Add a prior on pose x1. This indirectly specifies where the origin is.
72  // and a prior on the position of the first landmark to fix the scale
73  graph.addPrior(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1));
74  graph.addPrior(P(0), mydata.tracks[0].p,
75  noiseModel::Isotropic::Sigma(3, 0.1));
76 
77  // Create initial estimate
79  size_t i = 0;
80  j = 0;
81  for (const SfmCamera& camera : mydata.cameras) initial.insert(C(i++), camera);
82  for (const SfmTrack& track : mydata.tracks) initial.insert(P(j++), track.p);
83 
87  LevenbergMarquardtParams params_using_COLAMD, params_using_METIS;
88  try {
89  params_using_METIS.setVerbosity("ERROR");
90  gttic_(METIS_ORDERING);
91  params_using_METIS.ordering = Ordering::Create(Ordering::METIS, graph);
92  gttoc_(METIS_ORDERING);
93 
94  params_using_COLAMD.setVerbosity("ERROR");
95  gttic_(COLAMD_ORDERING);
96  params_using_COLAMD.ordering = Ordering::Create(Ordering::COLAMD, graph);
97  gttoc_(COLAMD_ORDERING);
98  } catch (exception& e) {
99  cout << e.what();
100  }
101 
102  // expect they have different ordering results
103  if (params_using_COLAMD.ordering == params_using_METIS.ordering) {
104  cout << "COLAMD and METIS produce the same ordering. "
105  << "Problem here!!!" << endl;
106  }
107 
108  /* Optimize the graph with METIS and COLAMD and time the results */
109 
110  Values result_METIS, result_COLAMD;
111  try {
112  gttic_(OPTIMIZE_WITH_METIS);
113  LevenbergMarquardtOptimizer lm_METIS(graph, initial, params_using_METIS);
114  result_METIS = lm_METIS.optimize();
115  gttoc_(OPTIMIZE_WITH_METIS);
116 
117  gttic_(OPTIMIZE_WITH_COLAMD);
118  LevenbergMarquardtOptimizer lm_COLAMD(graph, initial, params_using_COLAMD);
119  result_COLAMD = lm_COLAMD.optimize();
120  gttoc_(OPTIMIZE_WITH_COLAMD);
121  } catch (exception& e) {
122  cout << e.what();
123  }
124 
125  { // printing the result
126 
127  cout << "COLAMD final error: " << graph.error(result_COLAMD) << endl;
128  cout << "METIS final error: " << graph.error(result_METIS) << endl;
129 
130  cout << endl << endl;
131 
132  cout << "Time comparison by solving " << filename << " results:" << endl;
133  cout << boost::format("%1% point tracks and %2% cameras\n") %
134  mydata.number_tracks() % mydata.number_cameras()
135  << endl;
136 
137  tictoc_print_();
138  }
139 
140  return 0;
141 }
142 
Matrix3f m
virtual const Values & optimize()
#define gttic_(label)
Definition: timing.h:230
Define the structure for SfM data.
Definition: dataset.h:326
Factor Graph consisting of non-linear factors.
int main(int argc, char *argv[])
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
Values initial
Definition: Half.h:150
NonlinearFactorGraph graph
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: dataset.h:328
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
Definition: dataset.h:214
size_t number_tracks() const
The number of reconstructed 3D points.
Definition: dataset.h:333
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Define the structure for the 3D points.
Definition: dataset.h:220
void setVerbosity(const std::string &src)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
void tictoc_print_()
Definition: timing.h:253
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::optional< Ordering > ordering
The optional variable elimination ordering, or empty to use COLAMD (default: empty) ...
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
traits
Definition: chartTesting.h:28
std::vector< SfmCamera > cameras
Set of cameras.
Definition: dataset.h:327
Point3 p
3D position of the point
Definition: dataset.h:224
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
a general SFM factor with an unknown calibration
#define gttoc_(label)
Definition: timing.h:235
utility functions for loading datasets
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
Definition: dataset.h:226
std::ptrdiff_t j
Timing utilities.
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...
Definition: dataset.cpp:1073
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
size_t number_cameras() const
Definition: dataset.h:329


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:01