EssentialViewGraphExample.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 <gtsam/geometry/Cal3f.h>
22 #include <gtsam/geometry/Point2.h>
23 #include <gtsam/geometry/Point3.h>
24 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/inference/Symbol.h>
29 #include <gtsam/nonlinear/Values.h>
30 #include <gtsam/sfm/TransferFactor.h> // Contains EssentialTransferFactorK
31 
32 #include <vector>
33 
34 #include "SFMdata.h" // For createPoints() and posesOnCircle()
35 
36 using namespace std;
37 using namespace gtsam;
38 using namespace symbol_shorthand; // For K(symbol)
39 
40 // Main function
41 int main(int argc, char* argv[]) {
42  // Define the camera calibration parameters
43  Cal3f cal(50.0, 50.0, 50.0);
44 
45  // Create the set of 8 ground-truth landmarks
46  vector<Point3> points = createPoints();
47 
48  // Create the set of 4 ground-truth poses
49  vector<Pose3> poses = posesOnCircle(4, 30);
50 
51  // Calculate ground truth essential matrices, 1 and 2 poses apart
52  auto E1 = EssentialMatrix::FromPose3(poses[0].between(poses[1]));
53  auto E2 = EssentialMatrix::FromPose3(poses[0].between(poses[2]));
54 
55  // Simulate measurements from each camera pose
56  std::array<std::array<Point2, 8>, 4> p;
57  for (size_t i = 0; i < 4; ++i) {
59  for (size_t j = 0; j < 8; ++j) {
60  p[i][j] = camera.project(points[j]);
61  }
62  }
63 
64  // Create the factor graph
67 
68  for (size_t a = 0; a < 4; ++a) {
69  size_t b = (a + 1) % 4; // Next camera
70  size_t c = (a + 2) % 4; // Camera after next
71 
72  // Vectors to collect tuples for each factor
73  std::vector<std::tuple<Point2, Point2, Point2>> tuples1, tuples2, tuples3;
74 
75  // Collect data for the three factors
76  for (size_t j = 0; j < 8; ++j) {
77  tuples1.emplace_back(p[a][j], p[b][j], p[c][j]);
78  tuples2.emplace_back(p[a][j], p[c][j], p[b][j]);
79  tuples3.emplace_back(p[c][j], p[b][j], p[a][j]);
80  }
81 
82  // Add transfer factors between views a, b, and c.
83  graph.emplace_shared<Factor>(EdgeKey(a, c), EdgeKey(b, c), tuples1);
84  graph.emplace_shared<Factor>(EdgeKey(a, b), EdgeKey(b, c), tuples2);
85  graph.emplace_shared<Factor>(EdgeKey(a, c), EdgeKey(a, b), tuples3);
86  }
87 
88  // Formatter for printing keys
89  auto formatter = [](Key key) {
90  if (Symbol(key).chr() == 'k') {
91  return (string)Symbol(key);
92  } else {
93  EdgeKey edge(key);
94  return (std::string)edge;
95  }
96  };
97 
98  graph.print("Factor Graph:\n", formatter);
99 
100  // Create a delta vector to perturb the ground truth (small perturbation)
101  Vector5 delta;
102  delta << 1, 1, 1, 1, 1;
103  delta *= 1e-2;
104 
105  // Create the initial estimate for essential matrices
106  Values initialEstimate;
107  for (size_t a = 0; a < 4; ++a) {
108  size_t b = (a + 1) % 4; // Next camera
109  size_t c = (a + 2) % 4; // Camera after next
110  initialEstimate.insert(EdgeKey(a, b), E1.retract(delta));
111  initialEstimate.insert(EdgeKey(a, c), E2.retract(delta));
112  }
113 
114  // Insert initial calibrations (using K symbol)
115  for (size_t i = 0; i < 4; ++i) {
116  initialEstimate.insert(K(i), cal);
117  }
118 
119  initialEstimate.print("Initial Estimates:\n", formatter);
120  graph.printErrors(initialEstimate, "Initial Errors:\n", formatter);
121 
122  // Optimize the graph and print results
124  params.setlambdaInitial(1000.0); // Initialize lambda to a high value
125  params.setVerbosityLM("SUMMARY");
126  Values result =
127  LevenbergMarquardtOptimizer(graph, initialEstimate, params).optimize();
128 
129  cout << "Initial error = " << graph.error(initialEstimate) << endl;
130  cout << "Final error = " << graph.error(result) << endl;
131 
132  result.print("Final Results:\n", formatter);
133 
134  E1.print("Ground Truth E1:\n");
135  E2.print("Ground Truth E2:\n");
136 
137  return 0;
138 }
EssentialMatrix.h
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
gtsam::createPoints
std::vector< Point3 > createPoints()
Create a set of ground-truth landmarks.
Definition: SFMdata.h:43
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
gtsam::Cal3f
Calibration model with a single focal length and zero skew.
Definition: Cal3f.h:35
E2
E2
Definition: test_numpy_dtypes.cpp:103
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::Factor
Definition: Factor.h:70
Point3.h
3D Point
gtsam::EssentialTransferFactorK
Transfers points between views using essential matrices, optimizes for calibrations of the views,...
Definition: TransferFactor.h:224
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
result
Values result
Definition: OdometryOptimize.cpp:8
fixture::cal
const Cal3_S2 cal(focalLength, focalLength, 0.0, principalPoint.x(), principalPoint.y())
Point2.h
2D Point
gtsam::Symbol::chr
unsigned char chr() const
Definition: inference/Symbol.h:75
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Cal3f.h
Calibration model with a single focal length and zero skew.
Symbol.h
TransferFactor.h
main
int main(int argc, char *argv[])
Definition: EssentialViewGraphExample.cpp:41
key
const gtsam::Symbol key('X', 0)
gtsam::posesOnCircle
std::vector< Pose3 > posesOnCircle(int num_cameras=8, double R=30)
Definition: SFMdata.h:81
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::EdgeKey
Definition: EdgeKey.h:25
gtsam::NonlinearFactorGraph::printErrors
void printErrors(const Values &values, const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) {return true;}) const
Definition: NonlinearFactorGraph.cpp:71
gtsam::Values::print
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:66
gtsam
traits
Definition: SFMdata.h:40
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::testing::between
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
EdgeKey.h
camera
static const CalibratedCamera camera(kDefaultPose)
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
SFMdata.h
Simple example for the structure-from-motion problems.
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Values.h
A non-templated config holding any types of Manifold-group elements.
Pose3.h
3D Pose
E1
E1
Definition: test_numpy_dtypes.cpp:102
gtsam::CalibratedCamera::project
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
Definition: CalibratedCamera.cpp:188
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Symbol
Definition: inference/Symbol.h:37
gtsam::NonlinearFactorGraph::print
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactorGraph.cpp:55


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:16