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 SmartProjectionFactorExample.cpp
14* @brief A stereo visual odometry example
15* @date May 30, 2014
16* @author Stephen Camp
17* @author Chris Beall
18*/
19
20
21/**
22 * A smart projection factor example based on stereo data, throwing away the
23 * measurement from the right camera
24 * -robot starts at origin
25 * -moves forward, taking periodic stereo measurements
26 * -makes monocular observations of many landmarks
27 */
28
29#include <gtsam/slam/SmartProjectionPoseFactor.h>
30#include <gtsam/slam/dataset.h>
31#include <gtsam/geometry/Cal3_S2Stereo.h>
32#include <gtsam/nonlinear/Values.h>
33#include <gtsam/nonlinear/utilities.h>
34#include <gtsam/nonlinear/NonlinearEquality.h>
35#include <gtsam/nonlinear/NonlinearFactorGraph.h>
36#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
37#include <gtsam/inference/Symbol.h>
38
39#include <string>
40#include <fstream>
41#include <iostream>
42
43using namespace std;
44using namespace gtsam;
45
46int main(int argc, char** argv){
47 typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor;
48
49 Values initial_estimate;
50 NonlinearFactorGraph graph;
51 const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(dim: 2,sigma: 1);
52
53 string calibration_loc = findExampleDataFile(name: "VO_calibration.txt");
54 string pose_loc = findExampleDataFile(name: "VO_camera_poses_large.txt");
55 string factor_loc = findExampleDataFile(name: "VO_stereo_factors_large.txt");
56
57 //read camera calibration info from file
58 // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
59 cout << "Reading calibration info" << endl;
60 ifstream calibration_file(calibration_loc.c_str());
61
62 double fx, fy, s, u0, v0, b;
63 calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
64 const Cal3_S2::shared_ptr K(new Cal3_S2(fx, fy, s, u0, v0));
65
66 cout << "Reading camera poses" << endl;
67 ifstream pose_file(pose_loc.c_str());
68
69 int pose_index;
70 MatrixRowMajor m(4,4);
71 //read camera pose parameters and use to make initial estimates of camera poses
72 while (pose_file >> pose_index) {
73 for (int i = 0; i < 16; i++)
74 pose_file >> m.data()[i];
75 initial_estimate.insert(j: pose_index, val: Pose3(m));
76 }
77
78 // landmark keys
79 size_t landmark_key;
80
81 // pixel coordinates uL, uR, v (same for left/right images due to rectification)
82 // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
83 double uL, uR, v, X, Y, Z;
84 ifstream factor_file(factor_loc.c_str());
85 cout << "Reading stereo factors" << endl;
86
87 //read stereo measurements and construct smart factors
88
89 SmartFactor::shared_ptr factor(new SmartFactor(model, K));
90 size_t current_l = 3; // hardcoded landmark ID from first measurement
91
92 while (factor_file >> pose_index >> landmark_key >> uL >> uR >> v >> X >> Y >> Z) {
93
94 if(current_l != landmark_key) {
95 graph.push_back(factor);
96 factor = SmartFactor::shared_ptr(new SmartFactor(model, K));
97 current_l = landmark_key;
98 }
99 factor->add(measured: Point2(uL,v), key: pose_index);
100 }
101
102 Pose3 firstPose = initial_estimate.at<Pose3>(j: 1);
103 //constrain the first pose such that it cannot change from its original value during optimization
104 // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
105 // QR is much slower than Cholesky, but numerically more stable
106 graph.emplace_shared<NonlinearEquality<Pose3> >(args: 1,args&: firstPose);
107
108 LevenbergMarquardtParams params;
109 params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
110 params.verbosity = NonlinearOptimizerParams::ERROR;
111
112 cout << "Optimizing" << endl;
113 //create Levenberg-Marquardt optimizer to optimize the factor graph
114 LevenbergMarquardtOptimizer optimizer(graph, initial_estimate, params);
115 Values result = optimizer.optimize();
116
117 cout << "Final result sample:" << endl;
118 Values pose_values = utilities::allPose3s(values: result);
119 pose_values.print(str: "Final camera poses:\n");
120
121 return 0;
122}
123