SelfCalibrationExample.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 
18 /*
19  * See the detailed documentation in Visual SLAM.
20  * The only documentation below with deal with the self-calibration.
21  */
22 
23 // For loading the data
24 #include "SFMdata.h"
25 
26 // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
27 #include <gtsam/geometry/Point2.h>
28 
29 // Inference and optimization
30 #include <gtsam/inference/Symbol.h>
33 #include <gtsam/nonlinear/Values.h>
34 
35 // SFM-specific factors
36 #include <gtsam/slam/GeneralSFMFactor.h> // does calibration !
37 
38 // Standard headers
39 #include <vector>
40 
41 using namespace std;
42 using namespace gtsam;
43 
44 int main(int argc, char* argv[]) {
45  // Create the set of ground-truth
46  vector<Point3> points = createPoints();
47  vector<Pose3> poses = createPoses();
48 
49  // Create the factor graph
51 
52  // Add a prior on pose x1.
53  auto poseNoise = noiseModel::Diagonal::Sigmas(
54  (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
55  .finished()); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
56  graph.addPrior(Symbol('x', 0), poses[0], poseNoise);
57 
58  // Simulated measurements from each camera pose, adding them to the factor
59  // graph
60  Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
61  auto measurementNoise =
62  noiseModel::Isotropic::Sigma(2, 1.0);
63  for (size_t i = 0; i < poses.size(); ++i) {
64  for (size_t j = 0; j < points.size(); ++j) {
65  PinholeCamera<Cal3_S2> camera(poses[i], K);
66  Point2 measurement = camera.project(points[j]);
67  // The only real difference with the Visual SLAM example is that here we
68  // use a different factor type, that also calculates the Jacobian with
69  // respect to calibration
71  measurement, measurementNoise, Symbol('x', i), Symbol('l', j),
72  Symbol('K', 0));
73  }
74  }
75 
76  // Add a prior on the position of the first landmark.
77  auto pointNoise =
78  noiseModel::Isotropic::Sigma(3, 0.1);
79  graph.addPrior(Symbol('l', 0), points[0],
80  pointNoise); // add directly to graph
81 
82  // Add a prior on the calibration.
83  auto calNoise = noiseModel::Diagonal::Sigmas(
84  (Vector(5) << 500, 500, 0.1, 100, 100).finished());
85  graph.addPrior(Symbol('K', 0), K, calNoise);
86 
87  // Create the initial estimate to the solution
88  // now including an estimate on the camera calibration parameters
89  Values initialEstimate;
90  initialEstimate.insert(Symbol('K', 0), Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0));
91  for (size_t i = 0; i < poses.size(); ++i)
92  initialEstimate.insert(
93  Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25),
94  Point3(0.05, -0.10, 0.20))));
95  for (size_t j = 0; j < points.size(); ++j)
96  initialEstimate.insert<Point3>(Symbol('l', j),
97  points[j] + Point3(-0.25, 0.20, 0.15));
98 
99  /* Optimize the graph and print results */
100  Values result = DoglegOptimizer(graph, initialEstimate).optimize();
101  result.print("Final results:\n");
102 
103  return 0;
104 }
105 
virtual const Values & optimize()
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
double measurement(10.0)
Definition: Half.h:150
NonlinearFactorGraph graph
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:37
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Values result
int main(int argc, char *argv[])
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
std::vector< gtsam::Pose3 > createPoses(const gtsam::Pose3 &init=gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2, 0,-M_PI/2), gtsam::Point3(30, 0, 0)), const gtsam::Pose3 &delta=gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4, 0), gtsam::Point3(sin(M_PI/4)*30, 0, 30 *(1-sin(M_PI/4)))), int steps=8)
Definition: SFMdata.h:54
Simple example for the structure-from-motion problems.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
Vector3 Point3
Definition: Point3.h:35
static const CalibratedCamera camera(kDefaultPose)
a general SFM factor with an unknown calibration
2D Point
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
std::ptrdiff_t j


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:59