SFMExampleExpressions_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 
24 // The two new headers that allow using our Automatic Differentiation Expression framework
25 #include <gtsam/slam/expressions.h>
27 
28 // Header order is close to far
29 #include <gtsam/inference/Symbol.h>
31 #include <gtsam/slam/dataset.h> // for loading BAL datasets !
32 #include <vector>
33 
34 using namespace std;
35 using namespace gtsam;
36 using namespace noiseModel;
39 
40 // An SfmCamera is defined in datase.h as a camera with unknown Cal3Bundler calibration
41 // and has a total of 9 free parameters
42 
43 int main(int argc, char* argv[]) {
44  // Find default file, but if an argument is given, try loading a file
45  string filename = findExampleDataFile("dubrovnik-3-7-pre");
46  if (argc > 1) filename = string(argv[1]);
47 
48  // Load the SfM data from file
49  SfmData mydata;
50  readBAL(filename, mydata);
51  cout << boost::format("read %1% tracks on %2% cameras\n") %
52  mydata.number_tracks() % mydata.number_cameras();
53 
54  // Create a factor graph
56 
57  // Here we don't use a PriorFactor but directly the ExpressionFactor class
58  // First, we create an expression to the pose from the first camera
59  Expression<SfmCamera> camera0_(C(0));
60  // Then, to get its pose:
61  Pose3_ pose0_(&SfmCamera::getPose, camera0_);
62  // Finally, we say it should be equal to first guess
63  graph.addExpressionFactor(pose0_, mydata.cameras[0].pose(),
64  noiseModel::Isotropic::Sigma(6, 0.1));
65 
66  // similarly, we create a prior on the first point
67  Point3_ point0_(P(0));
68  graph.addExpressionFactor(point0_, mydata.tracks[0].p,
69  noiseModel::Isotropic::Sigma(3, 0.1));
70 
71  // We share *one* noiseModel between all projection factors
72  auto noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
73 
74  // Simulated measurements from each camera pose, adding them to the factor
75  // graph
76  size_t j = 0;
77  for (const SfmTrack& track : mydata.tracks) {
78  // Leaf expression for j^th point
79  Point3_ point_('p', j);
80  for (const SfmMeasurement& m : track.measurements) {
81  size_t i = m.first;
82  Point2 uv = m.second;
83  // Leaf expression for i^th camera
84  Expression<SfmCamera> camera_(C(i));
85  // Below an expression for the prediction of the measurement:
86  Point2_ predict_ = project2<SfmCamera>(camera_, point_);
87  // Again, here we use an ExpressionFactor
88  graph.addExpressionFactor(predict_, uv, noise);
89  }
90  j += 1;
91  }
92 
93  // Create initial estimate
95  size_t i = 0;
96  j = 0;
97  for (const SfmCamera& camera : mydata.cameras) initial.insert(C(i++), camera);
98  for (const SfmTrack& track : mydata.tracks) initial.insert(P(j++), track.p);
99 
100  /* Optimize the graph and print results */
101  Values result;
102  try {
104  params.setVerbosity("ERROR");
105  LevenbergMarquardtOptimizer lm(graph, initial, params);
106  result = lm.optimize();
107  } catch (exception& e) {
108  cout << e.what();
109  }
110  cout << "final error: " << graph.error(result) << endl;
111 
112  return 0;
113 }
Matrix3f m
virtual const Values & optimize()
Define the structure for SfM data.
Definition: dataset.h:326
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
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
Define the structure for the 3D points.
Definition: dataset.h:220
Values result
Factor graph that supports adding ExpressionFactors directly.
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
void addExpressionFactor(const Expression< T > &h, const T &z, const SharedNoiseModel &R)
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
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