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
12/**
13 * @file SFMExample_SmartFactor.cpp
14 * @brief A structure-from-motion problem on a simulated dataset, using smart projection factor
15 * @author Duy-Nguyen Ta
16 * @author Jing Dong
17 * @author Frank Dellaert
18 */
19
20// In GTSAM, measurement functions are represented as 'factors'.
21// The factor we used here is SmartProjectionPoseFactor.
22// Every smart factor represent a single landmark, seen from multiple cameras.
23// The SmartProjectionPoseFactor only optimizes for the poses of a camera,
24// not the calibration, which is assumed known.
25#include <gtsam/slam/SmartProjectionPoseFactor.h>
26
27// For an explanation of these headers, see SFMExample.cpp
28#include "SFMdata.h"
29#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
30
31using namespace std;
32using namespace gtsam;
33
34// Make the typename short so it looks much cleaner
35typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor;
36
37// create a typedef to the camera type
38typedef PinholePose<Cal3_S2> Camera;
39
40/* ************************************************************************* */
41int main(int argc, char* argv[]) {
42
43 // Define the camera calibration parameters
44 Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
45
46 // Define the camera observation noise model
47 auto measurementNoise =
48 noiseModel::Isotropic::Sigma(dim: 2, sigma: 1.0); // one pixel in u and v
49
50 // Create the set of ground-truth landmarks and poses
51 vector<Point3> points = createPoints();
52 vector<Pose3> poses = createPoses();
53
54 // Create a factor graph
55 NonlinearFactorGraph graph;
56
57 // Simulated measurements from each camera pose, adding them to the factor graph
58 for (size_t j = 0; j < points.size(); ++j) {
59
60 // every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements.
61 SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
62
63 for (size_t i = 0; i < poses.size(); ++i) {
64
65 // generate the 2D measurement
66 Camera camera(poses[i], K);
67 Point2 measurement = camera.project(pw: points[j]);
68
69 // call add() function to add measurement into a single factor, here we need to add:
70 // 1. the 2D measurement
71 // 2. the corresponding camera's key
72 // 3. camera noise model
73 // 4. camera calibration
74 smartfactor->add(measured: measurement, key: i);
75 }
76
77 // insert the smart factor in the graph
78 graph.push_back(factor: smartfactor);
79 }
80
81 // Add a prior on pose x0. This indirectly specifies where the origin is.
82 // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
83 auto noise = noiseModel::Diagonal::Sigmas(
84 sigmas: (Vector(6) << Vector3::Constant(value: 0.1), Vector3::Constant(value: 0.3)).finished());
85 graph.addPrior(key: 0, prior: poses[0], model: noise);
86
87 // Because the structure-from-motion problem has a scale ambiguity, the problem is
88 // still under-constrained. Here we add a prior on the second pose x1, so this will
89 // fix the scale by indicating the distance between x0 and x1.
90 // Because these two are fixed, the rest of the poses will be also be fixed.
91 graph.addPrior(key: 1, prior: poses[1], model: noise); // add directly to graph
92
93 graph.print(str: "Factor Graph:\n");
94
95 // Create the initial estimate to the solution
96 // Intentionally initialize the variables off from the ground truth
97 Values initialEstimate;
98 Pose3 delta(Rot3::Rodrigues(wx: -0.1, wy: 0.2, wz: 0.25), Point3(0.05, -0.10, 0.20));
99 for (size_t i = 0; i < poses.size(); ++i)
100 initialEstimate.insert(j: i, val: poses[i].compose(g: delta));
101 initialEstimate.print(str: "Initial Estimates:\n");
102
103 // Optimize the graph and print results
104 LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
105 Values result = optimizer.optimize();
106 result.print(str: "Final results:\n");
107
108 // A smart factor represent the 3D point inside the factor, not as a variable.
109 // The 3D position of the landmark is not explicitly calculated by the optimizer.
110 // To obtain the landmark's 3D position, we use the "point" method of the smart factor.
111 Values landmark_result;
112 for (size_t j = 0; j < points.size(); ++j) {
113
114 // The graph stores Factor shared_ptrs, so we cast back to a SmartFactor first
115 SmartFactor::shared_ptr smart = std::dynamic_pointer_cast<SmartFactor>(r: graph[j]);
116 if (smart) {
117 // The output of point() is in std::optional<Point3>, as sometimes
118 // the triangulation operation inside smart factor will encounter degeneracy.
119 auto point = smart->point(values: result);
120 if (point) // ignore if std::optional return nullptr
121 landmark_result.insert(j, val: *point);
122 }
123 }
124
125 landmark_result.print(str: "Landmark results:\n");
126 cout << "final error: " << graph.error(values: result) << endl;
127 cout << "number of iterations: " << optimizer.iterations() << endl;
128
129 return 0;
130}
131/* ************************************************************************* */
132
133