forked from borglab/gtsam
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathSFMExample_SmartFactor_bal.cpp
More file actions
82 lines (64 loc) · 2.57 KB
/
SFMExample_SmartFactor_bal.cpp
File metadata and controls
82 lines (64 loc) · 2.57 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file SFMExample_SmartFactor_bal.cpp
* @brief Solve a BAL structure-from-motion problem using smart projection factors.
*/
#include <gtsam/sfm/SfmData.h>
#include <gtsam/slam/SmartProjectionFactor.h>
#include <gtsam/slam/dataset.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/inference/Symbol.h>
#include <vector>
using namespace std;
using namespace gtsam;
using symbol_shorthand::C;
// Smart factor on full SfmCamera state (pose + calibration).
typedef SmartProjectionFactor<SfmCamera> SmartFactor;
/* ************************************************************************* */
int main(int argc, char* argv[]) {
string filename = findExampleDataFile("dubrovnik-3-7-pre");
if (argc > 1) filename = string(argv[1]);
SfmData mydata = SfmData::FromBalFile(filename);
cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
if (mydata.numberCameras() < 2) {
cerr << "Need at least 2 cameras for this example." << endl;
return 1;
}
NonlinearFactorGraph graph;
auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
for (const SfmTrack& track : mydata.tracks) {
SmartFactor::shared_ptr smart(new SmartFactor(measurementNoise));
for (const auto& [i, uv] : track.measurements) {
smart->add(uv, C(i));
}
graph.push_back(smart);
}
// Fix gauge/scale with priors on two cameras.
graph.addPrior(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1));
graph.addPrior(C(1), mydata.cameras[1], noiseModel::Isotropic::Sigma(9, 0.1));
Values initial;
size_t i = 0;
for (const SfmCamera& camera : mydata.cameras) initial.insert(C(i++), camera);
Values result;
size_t iterations = 0;
try {
LevenbergMarquardtParams params;
params.setVerbosity("ERROR");
LevenbergMarquardtOptimizer lm(graph, initial, params);
result = lm.optimize();
iterations = lm.iterations();
} catch (exception& e) {
cout << e.what() << endl;
return 1;
}
cout << "final error: " << graph.error(result) << endl;
cout << "iterations: " << iterations << endl;
return 0;
}
/* ************************************************************************* */