ViewGraphExample.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/Cal3_S2.h>
21 #include <gtsam/geometry/Point2.h>
22 #include <gtsam/geometry/Point3.h>
23 #include <gtsam/geometry/Pose3.h>
27 #include <gtsam/nonlinear/Values.h>
29 
30 #include <vector>
31 
32 #include "SFMdata.h"
33 #include "gtsam/inference/Key.h"
34 
35 using namespace std;
36 using namespace gtsam;
37 
38 /* ************************************************************************* */
39 int main(int argc, char* argv[]) {
40  // Define the camera calibration parameters
41  Cal3_S2 cal(50.0, 50.0, 0.0, 50.0, 50.0);
42 
43  // Create the set of 8 ground-truth landmarks
44  vector<Point3> points = createPoints();
45 
46  // Create the set of 4 ground-truth poses
47  vector<Pose3> poses = posesOnCircle(4, 30);
48 
49  // Calculate ground truth fundamental matrices, 1 and 2 poses apart
50  auto F1 = FundamentalMatrix(cal.K(), poses[0].between(poses[1]), cal.K());
51  auto F2 = FundamentalMatrix(cal.K(), poses[0].between(poses[2]), cal.K());
52 
53  // Simulate measurements from each camera pose
54  std::array<std::array<Point2, 8>, 4> p;
55  for (size_t i = 0; i < 4; ++i) {
57  for (size_t j = 0; j < 8; ++j) {
58  p[i][j] = camera.project(points[j]);
59  }
60  }
61 
62  // This section of the code is inspired by the work of Sweeney et al.
63  // [link](sites.cs.ucsb.edu/~holl/pubs/Sweeney-2015-ICCV.pdf) on view-graph
64  // calibration. The graph is made up of transfer factors that enforce the
65  // epipolar constraint between corresponding points across three views, as
66  // described in the paper. Rather than adding one ternary error term per point
67  // in a triplet, we add three binary factors for sparsity during optimization.
68  // In this version, we only include triplets between 3 successive cameras.
71 
72  for (size_t a = 0; a < 4; ++a) {
73  size_t b = (a + 1) % 4; // Next camera
74  size_t c = (a + 2) % 4; // Camera after next
75 
76  // Vectors to collect tuples for each factor
77  std::vector<std::tuple<Point2, Point2, Point2>> tuples1, tuples2, tuples3;
78 
79  // Collect data for the three factors
80  for (size_t j = 0; j < 8; ++j) {
81  tuples1.emplace_back(p[a][j], p[b][j], p[c][j]);
82  tuples2.emplace_back(p[a][j], p[c][j], p[b][j]);
83  tuples3.emplace_back(p[c][j], p[b][j], p[a][j]);
84  }
85 
86  // Add transfer factors between views a, b, and c. Note that the EdgeKeys
87  // are crucial in performing the transfer in the right direction. We use
88  // exactly 8 unique EdgeKeys, corresponding to 8 unknown fundamental
89  // matrices we will optimize for.
90  graph.emplace_shared<Factor>(EdgeKey(a, c), EdgeKey(b, c), tuples1);
91  graph.emplace_shared<Factor>(EdgeKey(a, b), EdgeKey(b, c), tuples2);
92  graph.emplace_shared<Factor>(EdgeKey(a, c), EdgeKey(a, b), tuples3);
93  }
94 
95  auto formatter = [](Key key) {
96  EdgeKey edge(key);
97  return (std::string)edge;
98  };
99 
100  graph.print("Factor Graph:\n", formatter);
101 
102  // Create a delta vector to perturb the ground truth
103  // We can't really go far before convergence becomes problematic :-(
104  Vector7 delta;
105  delta << 1, 2, 3, 4, 5, 6, 7;
106  delta *= 1e-5;
107 
108  // Create the data structure to hold the initial estimate to the solution
109  Values initialEstimate;
110  for (size_t a = 0; a < 4; ++a) {
111  size_t b = (a + 1) % 4; // Next camera
112  size_t c = (a + 2) % 4; // Camera after next
113  initialEstimate.insert(EdgeKey(a, b), F1.retract(delta));
114  initialEstimate.insert(EdgeKey(a, c), F2.retract(delta));
115  }
116  initialEstimate.print("Initial Estimates:\n", formatter);
117  graph.printErrors(initialEstimate, "errors: ", formatter);
118 
119  /* Optimize the graph and print results */
121  params.setlambdaInitial(1000.0); // Initialize lambda to a high value
122  params.setVerbosityLM("SUMMARY");
123  Values result =
124  LevenbergMarquardtOptimizer(graph, initialEstimate, params).optimize();
125 
126  cout << "initial error = " << graph.error(initialEstimate) << endl;
127  cout << "final error = " << graph.error(result) << endl;
128 
129  result.print("Final results:\n", formatter);
130 
131  cout << "Ground Truth F1:\n" << F1.matrix() << endl;
132  cout << "Ground Truth F2:\n" << F2.matrix() << endl;
133 
134  return 0;
135 }
136 /* ************************************************************************* */
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.)
Cal3_S2.h
The most common 5DOF 3D->2D calibration.
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.
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::Factor
Definition: Factor.h:70
Point3.h
3D Point
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
Key.h
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
gtsam::Cal3::K
virtual Matrix3 K() const
return calibration matrix K
Definition: Cal3.h:167
TransferFactor.h
gtsam::TransferFactor
Definition: TransferFactor.h:87
F1
const Matrix26 F1
Definition: testRegularImplicitSchurFactor.cpp:37
main
int main(int argc, char *argv[])
Definition: ViewGraphExample.cpp:39
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
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::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
EdgeKey.h
camera
static const CalibratedCamera camera(kDefaultPose)
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::FundamentalMatrix
Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two v...
Definition: FundamentalMatrix.h:28
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
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::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:09:42