SFMExample_bal.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 
18 // For an explanation of headers, see SFMExample.cpp
19 #include <gtsam/inference/Symbol.h>
23 #include <gtsam/slam/dataset.h> // for loading BAL datasets !
24 #include <vector>
25 
26 using namespace std;
27 using namespace gtsam;
30 
31 // We will be using a projection factor that ties a SFM_Camera to a 3D point.
32 // An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler calibration
33 // and has a total of 9 free parameters
35 
36 /* ************************************************************************* */
37 int main (int argc, char* argv[]) {
38 
39  // Find default file, but if an argument is given, try loading a file
40  string filename = findExampleDataFile("dubrovnik-3-7-pre");
41  if (argc>1) filename = string(argv[1]);
42 
43  // Load the SfM data from file
44  SfmData mydata;
45  readBAL(filename, mydata);
46  cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
47 
48  // Create a factor graph
50 
51  // We share *one* noiseModel between all projection factors
52  auto noise =
53  noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
54 
55  // Add measurements to the factor graph
56  size_t j = 0;
57  for(const SfmTrack& track: mydata.tracks) {
58  for(const SfmMeasurement& m: track.measurements) {
59  size_t i = m.first;
60  Point2 uv = m.second;
61  graph.emplace_shared<MyFactor>(uv, noise, C(i), P(j)); // note use of shorthand symbols C and P
62  }
63  j += 1;
64  }
65 
66  // Add a prior on pose x1. This indirectly specifies where the origin is.
67  // and a prior on the position of the first landmark to fix the scale
68  graph.addPrior(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1));
69  graph.addPrior(P(0), mydata.tracks[0].p, noiseModel::Isotropic::Sigma(3, 0.1));
70 
71  // Create initial estimate
73  size_t i = 0; j = 0;
74  for(const SfmCamera& camera: mydata.cameras) initial.insert(C(i++), camera);
75  for(const SfmTrack& track: mydata.tracks) initial.insert(P(j++), track.p);
76 
77  /* Optimize the graph and print results */
78  Values result;
79  try {
81  params.setVerbosity("ERROR");
82  LevenbergMarquardtOptimizer lm(graph, initial, params);
83  result = lm.optimize();
84  } catch (exception& e) {
85  cout << e.what();
86  }
87  cout << "final error: " << graph.error(result) << endl;
88 
89  return 0;
90 }
91 /* ************************************************************************* */
92 
Matrix3f m
virtual const Values & optimize()
Define the structure for SfM data.
Definition: dataset.h:326
Factor Graph consisting of non-linear factors.
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
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
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
Values result
void setVerbosity(const std::string &src)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SmartStereoProjectionParams params
int main(int argc, char *argv[])
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
utility functions for loading datasets
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
Definition: dataset.h:226
std::ptrdiff_t j
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
size_t number_cameras() const
Definition: dataset.h:329


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