StereoVOExample_large.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 
27 #include <gtsam/geometry/Pose3.h>
29 #include <gtsam/nonlinear/Values.h>
34 #include <gtsam/inference/Symbol.h>
36 #include <gtsam/slam/dataset.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) {
46  Values initial_estimate;
48  const auto model = noiseModel::Isotropic::Sigma(3, 1);
49 
50  string calibration_loc = findExampleDataFile("VO_calibration.txt");
51  string pose_loc = findExampleDataFile("VO_camera_poses_large.txt");
52  string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt");
53 
54  // read camera calibration info from file
55  // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
56  double fx, fy, s, u0, v0, b;
57  ifstream calibration_file(calibration_loc.c_str());
58  cout << "Reading calibration info" << endl;
59  calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
60 
61  // create stereo camera calibration object
63 
64  ifstream pose_file(pose_loc.c_str());
65  cout << "Reading camera poses" << endl;
66  int pose_id;
67  MatrixRowMajor m(4, 4);
68  // read camera pose parameters and use to make initial estimates of camera
69  // poses
70  while (pose_file >> pose_id) {
71  for (int i = 0; i < 16; i++) {
72  pose_file >> m.data()[i];
73  }
74  initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
75  }
76 
77  // camera and landmark keys
78  size_t x, l;
79 
80  // pixel coordinates uL, uR, v (same for left/right images due to
81  // rectification) landmark coordinates X, Y, Z in camera frame, resulting from
82  // triangulation
83  double uL, uR, v, X, Y, Z;
84  ifstream factor_file(factor_loc.c_str());
85  cout << "Reading stereo factors" << endl;
86  // read stereo measurement details from file and use to create and add
87  // GenericStereoFactor objects to the graph representation
88  while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) {
90  StereoPoint2(uL, uR, v), model, Symbol('x', x), Symbol('l', l), K);
91  // if the landmark variable included in this factor has not yet been added
92  // to the initial variable value estimate, add it
93  if (!initial_estimate.exists(Symbol('l', l))) {
94  Pose3 camPose = initial_estimate.at<Pose3>(Symbol('x', x));
95  // transformFrom() transforms the input Point3 from the camera pose space,
96  // camPose, to the global space
97  Point3 worldPoint = camPose.transformFrom(Point3(X, Y, Z));
98  initial_estimate.insert(Symbol('l', l), worldPoint);
99  }
100  }
101 
102  Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x', 1));
103  // constrain the first pose such that it cannot change from its original value
104  // during optimization
105  // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
106  // QR is much slower than Cholesky, but numerically more stable
107  graph.emplace_shared<NonlinearEquality<Pose3> >(Symbol('x', 1), first_pose);
108 
109  cout << "Optimizing" << endl;
110  // create Levenberg-Marquardt optimizer to optimize the factor graph
112  params.orderingType = Ordering::METIS;
113  LevenbergMarquardtOptimizer optimizer(graph, initial_estimate, params);
114  Values result = optimizer.optimize();
115 
116  cout << "Final result sample:" << endl;
117  Values pose_values = utilities::allPose3s(result);
118  pose_values.print("Final camera poses:\n");
119 
120  return 0;
121 }
utilities.h
Contains generic global functions designed particularly for the matlab interface.
gtsam::utilities::allPose3s
Values allPose3s(const Values &values)
Extract all Pose3 values.
Definition: nonlinear/utilities.h:150
gtsam::Values::exists
bool exists(Key j) const
Definition: Values.cpp:93
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
s
RealScalar s
Definition: level1_cplx_impl.h:126
v0
static const double v0
Definition: testCal3DFisheye.cpp:31
fx
const double fx
Definition: testSmartStereoFactor_iSAM2.cpp:47
b
Scalar * b
Definition: benchVecAdd.cpp:17
main
int main(int argc, char **argv)
Definition: StereoVOExample_large.cpp:45
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
gtsam::Y
GaussianFactorGraphValuePair Y
Definition: HybridGaussianProductFactor.cpp:29
x
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
Definition: gnuplot_common_settings.hh:12
X
#define X
Definition: icosphere.cpp:20
gtsam::GenericStereoFactor
Definition: StereoFactor.h:32
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::NonlinearEquality
Definition: NonlinearEquality.h:43
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
dataset.h
utility functions for loading datasets
gtsam::Pose3
Definition: Pose3.h:37
StereoFactor.h
A non-linear factor for stereo measurements.
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
l
static const Line3 l(Rot3(), 1, 1)
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
Symbol.h
camPose
static Pose3 camPose(Rot3((Matrix3()<< 1., 0., 0., 0.,-1., 0., 0., 0.,-1.).finished()), Point3(0, 0, 6.25))
gtsam::Cal3_S2Stereo::shared_ptr
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
Cal3_S2Stereo.h
The most common 5DOF 3D->2D calibration + Stereo baseline.
NonlinearEquality.h
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
u0
static const double u0
Definition: testCal3DFisheye.cpp:31
gtsam::Values::print
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:66
gtsam
traits
Definition: SFMdata.h:40
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
gtsam::StereoPoint2
Definition: StereoPoint2.h:34
std
Definition: BFloat16.h:88
gtsam::Pose3::transformFrom
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:347
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::findExampleDataFile
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
Z
#define Z
Definition: icosphere.cpp:21
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::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
fy
const double fy
Definition: testSmartStereoFactor_iSAM2.cpp:48
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:05:00