SmartStereoProjectionFactorExample.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 
29 #include <gtsam/geometry/Pose3.h>
31 #include <gtsam/nonlinear/Values.h>
35 #include <gtsam/inference/Symbol.h>
36 #include <gtsam/slam/dataset.h>
37 
39 
40 #include <string>
41 #include <fstream>
42 #include <iostream>
43 
44 using namespace std;
45 using namespace gtsam;
46 
47 int main(int argc, char** argv){
48 
50 
51  bool output_poses = true;
52  string poseOutput("../../../examples/data/optimized_poses.txt");
53  string init_poseOutput("../../../examples/data/initial_poses.txt");
56  const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1);
57  ofstream pose3Out, init_pose3Out;
58 
59  bool add_initial_noise = true;
60 
61  string calibration_loc = findExampleDataFile("VO_calibration.txt");
62  string pose_loc = findExampleDataFile("VO_camera_poses_large.txt");
63  string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt");
64 
65  //read camera calibration info from file
66  // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
67  cout << "Reading calibration info" << endl;
68  ifstream calibration_file(calibration_loc.c_str());
69 
70  double fx, fy, s, u0, v0, b;
71  calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
72  const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx, fy, s, u0, v0,b));
73 
74  cout << "Reading camera poses" << endl;
75  ifstream pose_file(pose_loc.c_str());
76 
77  int pose_id;
78  MatrixRowMajor m(4,4);
79  //read camera pose parameters and use to make initial estimates of camera poses
80  while (pose_file >> pose_id) {
81  for (int i = 0; i < 16; i++) {
82  pose_file >> m.data()[i];
83  }
84  if(add_initial_noise){
85  m(1,3) += (pose_id % 10)/10.0;
86  }
87  initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
88  }
89 
90  Values initial_pose_values = initial_estimate.filter<Pose3>();
91  if (output_poses) {
92  init_pose3Out.open(init_poseOutput.c_str(), ios::out);
93  for (size_t i = 1; i <= initial_pose_values.size(); i++) {
94  init_pose3Out
95  << i << " "
96  << initial_pose_values.at<Pose3>(Symbol('x', i)).matrix().format(
97  Eigen::IOFormat(Eigen::StreamPrecision, 0, " ", " ")) << endl;
98  }
99  }
100 
101  // camera and landmark keys
102  size_t x, l;
103 
104  // pixel coordinates uL, uR, v (same for left/right images due to rectification)
105  // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
106  double uL, uR, v, X, Y, Z;
107  ifstream factor_file(factor_loc.c_str());
108  cout << "Reading stereo factors" << endl;
109 
110  //read stereo measurements and construct smart factors
111 
112  SmartFactor::shared_ptr factor(new SmartFactor(model));
113  size_t current_l = 3; // hardcoded landmark ID from first measurement
114 
115  while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) {
116 
117  if(current_l != l) {
118  graph.push_back(factor);
119  factor = SmartFactor::shared_ptr(new SmartFactor(model));
120  current_l = l;
121  }
122  factor->add(StereoPoint2(uL,uR,v), Symbol('x',x), K);
123  }
124 
125  Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x',1));
126  //constrain the first pose such that it cannot change from its original value during optimization
127  // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
128  // QR is much slower than Cholesky, but numerically more stable
129  graph.emplace_shared<NonlinearEquality<Pose3> >(Symbol('x',1),first_pose);
130 
132  params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
133  params.verbosity = NonlinearOptimizerParams::ERROR;
134 
135  cout << "Optimizing" << endl;
136  //create Levenberg-Marquardt optimizer to optimize the factor graph
137  LevenbergMarquardtOptimizer optimizer(graph, initial_estimate, params);
138  Values result = optimizer.optimize();
139 
140  cout << "Final result sample:" << endl;
141  Values pose_values = result.filter<Pose3>();
142  pose_values.print("Final camera poses:\n");
143 
144  if(output_poses){
145  pose3Out.open(poseOutput.c_str(),ios::out);
146  for(size_t i = 1; i<=pose_values.size(); i++){
147  pose3Out << i << " " << pose_values.at<Pose3>(Symbol('x',i)).matrix().format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
148  " ", " ")) << endl;
149  }
150  cout << "Writing output" << endl;
151  }
152 
153  return 0;
154 }
Matrix3f m
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
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
Smart stereo factor on poses, assuming camera calibration is fixed.
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
static const Line3 l(Rot3(), 1, 1)
const double fy
boost::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
size_t size() const
Definition: Values.h:236
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
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
The most common 5DOF 3D->2D calibration + Stereo baseline.
static const double v0
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
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
#define X
Definition: icosphere.cpp:20
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
3D Pose
utility functions for loading datasets
Stores a set of parameters controlling the way matrices are printed.
Definition: IO.h:50
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