ConcurrentCalibration.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 
21 #include <gtsam/geometry/Pose3.h>
22 #include <gtsam/nonlinear/Values.h>
26 #include <gtsam/inference/Symbol.h>
29 #include <gtsam/slam/dataset.h>
30 
31 #include <string>
32 #include <fstream>
33 #include <iostream>
34 #include <boost/lexical_cast.hpp>
35 
36 using namespace std;
37 using namespace gtsam;
38 
39 int main(int argc, char** argv){
40 
43  const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1);
44 
45  string calibration_loc = findExampleDataFile("VO_calibration00s.txt");
46  string pose_loc = findExampleDataFile("VO_camera_poses00s.txt");
47  string factor_loc = findExampleDataFile("VO_stereo_factors00s.txt");
48 
49  //read camera calibration info from file
50  // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
51  double fx, fy, s, u0, v0, b;
52  ifstream calibration_file(calibration_loc.c_str());
53  cout << "Reading calibration info" << endl;
54  calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
55 
56  //create stereo camera calibration object
57  const Cal3_S2::shared_ptr K(new Cal3_S2(fx,fy,s,u0,v0));
58  const Cal3_S2::shared_ptr noisy_K(new Cal3_S2(fx*1.2,fy*1.2,s,u0-10,v0+10));
59 
60  initial_estimate.insert(Symbol('K', 0), *noisy_K);
61 
62  noiseModel::Diagonal::shared_ptr calNoise = noiseModel::Diagonal::Sigmas((Vector(5) << 500, 500, 1e-5, 100, 100).finished());
63  graph.addPrior(Symbol('K', 0), *noisy_K, calNoise);
64 
65 
66  ifstream pose_file(pose_loc.c_str());
67  cout << "Reading camera poses" << endl;
68  int pose_id;
69  MatrixRowMajor m(4,4);
70  //read camera pose parameters and use to make initial estimates of camera poses
71  while (pose_file >> pose_id) {
72  for (int i = 0; i < 16; i++) {
73  pose_file >> m.data()[i];
74  }
75  initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
76  }
77 
78  noiseModel::Isotropic::shared_ptr poseNoise = noiseModel::Isotropic::Sigma(6, 0.01);
79  graph.addPrior(Symbol('x', pose_id), Pose3(m), poseNoise);
80 
81  // camera and landmark keys
82  size_t x, l;
83 
84  // pixel coordinates uL, uR, v (same for left/right images due to rectification)
85  // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
86  double uL, uR, v, X, Y, Z;
87  ifstream factor_file(factor_loc.c_str());
88  cout << "Reading stereo factors" << endl;
89  //read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation
90  while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) {
91 // graph.emplace_shared<GenericStereoFactor<Pose3, Point3> >(StereoPoint2(uL, uR, v), model, Symbol('x', x), Symbol('l', l), K);
92 
93  graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >(Point2(uL,v), model, Symbol('x', x), Symbol('l', l), Symbol('K', 0));
94 
95 
96  //if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it
97  if (!initial_estimate.exists(Symbol('l', l))) {
98  Pose3 camPose = initial_estimate.at<Pose3>(Symbol('x', x));
99  //transformFrom() transforms the input Point3 from the camera pose space, camPose, to the global space
100  Point3 worldPoint = camPose.transformFrom(Point3(X, Y, Z));
101  initial_estimate.insert(Symbol('l', l), worldPoint);
102  }
103  }
104 
105  Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x',1));
106  //constrain the first pose such that it cannot change from its original value during optimization
107  // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
108  // QR is much slower than Cholesky, but numerically more stable
109  graph.emplace_shared<NonlinearEquality<Pose3> >(Symbol('x',1),first_pose);
110 
111  cout << "Optimizing" << endl;
113  params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
114  params.verbosity = NonlinearOptimizerParams::ERROR;
115 
116  //create Levenberg-Marquardt optimizer to optimize the factor graph
117  LevenbergMarquardtOptimizer optimizer(graph, initial_estimate,params);
118 // Values result = optimizer.optimize();
119 
120  string K_values_file = "K_values.txt";
121  ofstream stream_K(K_values_file.c_str());
122 
123  double currentError;
124 
125 
126  stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(Symbol('K',0)).vector().transpose() << endl;
127 
128 
129  // Iterative loop
130  do {
131  // Do next iteration
132  currentError = optimizer.error();
133  optimizer.iterate();
134 
135  stream_K << optimizer.iterations() << " " << optimizer.values().at<Cal3_S2>(Symbol('K',0)).vector().transpose() << endl;
136 
137  if(params.verbosity >= NonlinearOptimizerParams::ERROR) cout << "newError: " << optimizer.error() << endl;
138  } while(optimizer.iterations() < params.maxIterations &&
140  params.errorTol, currentError, optimizer.error(), params.verbosity));
141 
142  Values result = optimizer.values();
143 
144  cout << "Final result sample:" << endl;
145  Values pose_values = result.filter<Pose3>();
146  pose_values.print("Final camera poses:\n");
147 
148  Values(result.filter<Cal3_S2>()).print("Final K\n");
149 
150  noisy_K->print("Initial noisy K\n");
151  K->print("Initial correct K\n");
152 
153  return 0;
154 }
Matrix3f m
bool exists(Key j) const
Definition: Values.cpp:104
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)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Definition: Half.h:150
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
double errorTol
The maximum total error to stop iterating (default 0.0)
#define Z
Definition: icosphere.cpp:21
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:298
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)
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
const double fy
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
const Values & values() const
return values in current optimizer state
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
static const double u0
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
Basic bearing factor from 2D measurement.
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
std::vector< float > Values
static Pose3 camPose(Rot3((Matrix3()<< 1., 0., 0., 0.,-1., 0., 0., 0.,-1.).finished()), Point3(0, 0, 6.25))
static const double v0
GaussianFactorGraph::shared_ptr iterate() override
int main(int argc, char **argv)
boost::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:541
Vector3 Point3
Definition: Point3.h:35
const double fx
The matrix class, also used for vectors and row-vectors.
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
#define X
Definition: icosphere.cpp:20
a general SFM factor with an unknown calibration
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
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
utility functions for loading datasets
size_t maxIterations
The maximum iterations to stop iterating (default 100)
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)
Definition: Values-inl.h:237
size_t iterations() const
return number of iterations in current optimizer state


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:49