SmartProjectionFactorExample.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 
30 #include <gtsam/slam/dataset.h>
32 #include <gtsam/nonlinear/Values.h>
36 #include <gtsam/inference/Symbol.h>
37 
38 #include <string>
39 #include <fstream>
40 #include <iostream>
41 
42 using namespace std;
43 using namespace gtsam;
44 
45 int main(int argc, char** argv){
47 
50  const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1);
51 
52  string calibration_loc = findExampleDataFile("VO_calibration.txt");
53  string pose_loc = findExampleDataFile("VO_camera_poses_large.txt");
54  string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt");
55 
56  //read camera calibration info from file
57  // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
58  cout << "Reading calibration info" << endl;
59  ifstream calibration_file(calibration_loc.c_str());
60 
61  double fx, fy, s, u0, v0, b;
62  calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
63  const Cal3_S2::shared_ptr K(new Cal3_S2(fx, fy, s, u0, v0));
64 
65  cout << "Reading camera poses" << endl;
66  ifstream pose_file(pose_loc.c_str());
67 
68  int pose_index;
69  MatrixRowMajor m(4,4);
70  //read camera pose parameters and use to make initial estimates of camera poses
71  while (pose_file >> pose_index) {
72  for (int i = 0; i < 16; i++)
73  pose_file >> m.data()[i];
74  initial_estimate.insert(pose_index, Pose3(m));
75  }
76 
77  // landmark keys
78  size_t landmark_key;
79 
80  // pixel coordinates uL, uR, v (same for left/right images due to rectification)
81  // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
82  double uL, uR, v, X, Y, Z;
83  ifstream factor_file(factor_loc.c_str());
84  cout << "Reading stereo factors" << endl;
85 
86  //read stereo measurements and construct smart factors
87 
88  SmartFactor::shared_ptr factor(new SmartFactor(model, K));
89  size_t current_l = 3; // hardcoded landmark ID from first measurement
90 
91  while (factor_file >> pose_index >> landmark_key >> uL >> uR >> v >> X >> Y >> Z) {
92 
93  if(current_l != landmark_key) {
94  graph.push_back(factor);
95  factor = SmartFactor::shared_ptr(new SmartFactor(model, K));
96  current_l = landmark_key;
97  }
98  factor->add(Point2(uL,v), pose_index);
99  }
100 
101  Pose3 firstPose = initial_estimate.at<Pose3>(1);
102  //constrain the first pose such that it cannot change from its original value during optimization
103  // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
104  // QR is much slower than Cholesky, but numerically more stable
105  graph.emplace_shared<NonlinearEquality<Pose3> >(1,firstPose);
106 
108  params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
109  params.verbosity = NonlinearOptimizerParams::ERROR;
110 
111  cout << "Optimizing" << endl;
112  //create Levenberg-Marquardt optimizer to optimize the factor graph
113  LevenbergMarquardtOptimizer optimizer(graph, initial_estimate, params);
114  Values result = optimizer.optimize();
115 
116  cout << "Final result sample:" << endl;
117  Values pose_values = result.filter<Pose3>();
118  pose_values.print("Final camera poses:\n");
119 
120  return 0;
121 }
Matrix3f m
Smart factor on poses, assuming camera calibration is fixed.
virtual const Values & optimize()
Scalar * b
Definition: benchVecAdd.cpp:17
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Definition: Half.h:150
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
#define Z
Definition: icosphere.cpp:21
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
const double fy
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
RealScalar s
static SmartStereoProjectionParams params
static const double u0
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
The most common 5DOF 3D->2D calibration + Stereo baseline.
static const double v0
int main(int argc, char **argv)
boost::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:541
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
const double fx
The matrix class, also used for vectors and row-vectors.
#define X
Definition: icosphere.cpp:20
boost::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
utility functions for loading datasets
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)
Definition: Values-inl.h:237


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:16