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
12/**
13* @file StereoVOExample_large.cpp
14* @brief A stereo visual odometry example
15* @date May 25, 2014
16* @author Stephen Camp
17*/
18
19
20/**
21 * A 3D stereo visual odometry example
22 * - robot starts at origin
23 * -moves forward, taking periodic stereo measurements
24 * -takes stereo readings of many landmarks
25 */
26
27#include <gtsam/geometry/Pose3.h>
28#include <gtsam/geometry/Cal3_S2Stereo.h>
29#include <gtsam/nonlinear/Values.h>
30#include <gtsam/nonlinear/utilities.h>
31#include <gtsam/nonlinear/NonlinearEquality.h>
32#include <gtsam/nonlinear/NonlinearFactorGraph.h>
33#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
34#include <gtsam/inference/Symbol.h>
35#include <gtsam/slam/StereoFactor.h>
36#include <gtsam/slam/dataset.h>
37
38#include <string>
39#include <fstream>
40#include <iostream>
41
42using namespace std;
43using namespace gtsam;
44
45int main(int argc, char** argv) {
46 Values initial_estimate;
47 NonlinearFactorGraph graph;
48 const auto model = noiseModel::Isotropic::Sigma(dim: 3, sigma: 1);
49
50 string calibration_loc = findExampleDataFile(name: "VO_calibration.txt");
51 string pose_loc = findExampleDataFile(name: "VO_camera_poses_large.txt");
52 string factor_loc = findExampleDataFile(name: "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
62 const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx, fy, s, u0, v0, b));
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(j: Symbol('x', pose_id), val: 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) {
89 graph.emplace_shared<GenericStereoFactor<Pose3, Point3> >(
90 args: StereoPoint2(uL, uR, v), args: model, args: Symbol('x', x), args: Symbol('l', l), args: 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(j: Symbol('l', l))) {
94 Pose3 camPose = initial_estimate.at<Pose3>(j: 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(point: Point3(X, Y, Z));
98 initial_estimate.insert(j: Symbol('l', l), val: worldPoint);
99 }
100 }
101
102 Pose3 first_pose = initial_estimate.at<Pose3>(j: 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> >(args: Symbol('x', 1), args&: first_pose);
108
109 cout << "Optimizing" << endl;
110 // create Levenberg-Marquardt optimizer to optimize the factor graph
111 LevenbergMarquardtParams params;
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(values: result);
118 pose_values.print(str: "Final camera poses:\n");
119
120 return 0;
121}
122