timeSFMBAL.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 #include "timeSFMBAL.h"
20 
24 #include <gtsam/geometry/Point3.h>
25 
26 
27 using namespace std;
28 using namespace gtsam;
29 
32 
33 int main(int argc, char* argv[]) {
34  // parse options and read BAL file
35  SfmData db = preamble(argc, argv);
36 
37  // Build graph using conventional GeneralSFMFactor
39  for (size_t j = 0; j < db.number_tracks(); j++) {
40  for (const SfmMeasurement& m: db.tracks[j].measurements) {
41  size_t i = m.first;
42  Point2 z = m.second;
43  graph.emplace_shared<SfmFactor>(z, gNoiseModel, C(i), P(j));
44  }
45  }
46 
48  size_t i = 0, j = 0;
49  for (const SfmCamera& camera: db.cameras)
50  initial.insert(C(i++), camera);
51  for (const SfmTrack& track: db.tracks)
52  initial.insert(P(j++), track.p);
53 
54  return optimize(db, graph, initial);
55 }
Matrix3f m
static SharedNoiseModel gNoiseModel
Definition: timeSFMBAL.h:38
Define the structure for SfM data.
Definition: dataset.h:326
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
Common code for timeSFMBAL scripts.
Base class for all pinhole cameras.
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
PinholeCamera< Cal3Bundler > Camera
Definition: timeSFMBAL.cpp:30
GeneralSFMFactor< Camera, Point3 > SfmFactor
Definition: timeSFMBAL.cpp:31
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
int main(int argc, char *argv[])
Definition: timeSFMBAL.cpp:33
traits
Definition: chartTesting.h:28
std::vector< SfmCamera > cameras
Set of cameras.
Definition: dataset.h:327
SfmData preamble(int argc, char *argv[])
Definition: timeSFMBAL.h:41
Point3 p
3D position of the point
Definition: dataset.h:224
3D Point
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:63
static const CalibratedCamera camera(kDefaultPose)
a general SFM factor with an unknown calibration
Calibration used by Bundler.
std::ptrdiff_t j


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:42