| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							|  |  |  | * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  | * All Rights Reserved | 
					
						
							|  |  |  | * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  | * @file SmartProjectionFactorExample.cpp | 
					
						
							|  |  |  | * @brief A stereo visual odometry example | 
					
						
							|  |  |  | * @date May 30, 2014 | 
					
						
							|  |  |  | * @author Stephen Camp | 
					
						
							|  |  |  | * @author Chris Beall | 
					
						
							|  |  |  | */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |  * A smart projection factor example based on stereo data, throwing away the | 
					
						
							|  |  |  |  * measurement from the right camera | 
					
						
							|  |  |  |  *  -robot starts at origin | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |  *  -moves forward, taking periodic stereo measurements | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |  *  -makes monocular observations of many landmarks | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-26 20:55:16 +08:00
										 |  |  | #include <gtsam/slam/SmartProjectionPoseFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | #include <gtsam/geometry/Cal3_S2Stereo.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearEquality.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <string>
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char** argv){ | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor; | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Values initial_estimate; | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(2,1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   string calibration_loc = findExampleDataFile("VO_calibration.txt"); | 
					
						
							|  |  |  |   string pose_loc = findExampleDataFile("VO_camera_poses_large.txt"); | 
					
						
							|  |  |  |   string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt"); | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   //read camera calibration info from file
 | 
					
						
							|  |  |  |   // focal lengths fx, fy, skew s, principal point u0, v0, baseline b
 | 
					
						
							|  |  |  |   cout << "Reading calibration info" << endl; | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |   ifstream calibration_file(calibration_loc.c_str()); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |   double fx, fy, s, u0, v0, b; | 
					
						
							|  |  |  |   calibration_file >> fx >> fy >> s >> u0 >> v0 >> b; | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   const Cal3_S2::shared_ptr K(new Cal3_S2(fx, fy, s, u0, v0)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Reading camera poses" << endl; | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |   ifstream pose_file(pose_loc.c_str()); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |   int pose_index; | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   MatrixRowMajor m(4,4); | 
					
						
							|  |  |  |   //read camera pose parameters and use to make initial estimates of camera poses
 | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |   while (pose_file >> pose_index) { | 
					
						
							| 
									
										
										
										
											2015-02-26 20:55:16 +08:00
										 |  |  |     for (int i = 0; i < 16; i++) | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |       pose_file >> m.data()[i]; | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |     initial_estimate.insert(pose_index, Pose3(m)); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-26 20:55:16 +08:00
										 |  |  |   // landmark keys
 | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |   size_t landmark_key; | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // pixel coordinates uL, uR, v (same for left/right images due to rectification)
 | 
					
						
							|  |  |  |   // landmark coordinates X, Y, Z in camera frame, resulting from triangulation
 | 
					
						
							|  |  |  |   double uL, uR, v, X, Y, Z; | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |   ifstream factor_file(factor_loc.c_str()); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   cout << "Reading stereo factors" << endl; | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   //read stereo measurements and construct smart factors
 | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-08-27 01:25:12 +08:00
										 |  |  |   SmartFactor::shared_ptr factor(new SmartFactor(model, K)); | 
					
						
							| 
									
										
										
										
											2014-05-31 07:37:03 +08:00
										 |  |  |   size_t current_l = 3;   // hardcoded landmark ID from first measurement
 | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |   while (factor_file >> pose_index >> landmark_key >> uL >> uR >> v >> X >> Y >> Z) { | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |     if(current_l != landmark_key) { | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |       graph.push_back(factor); | 
					
						
							| 
									
										
										
										
											2015-08-27 01:25:12 +08:00
										 |  |  |       factor = SmartFactor::shared_ptr(new SmartFactor(model, K)); | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |       current_l = landmark_key; | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |     } | 
					
						
							| 
									
										
										
										
											2015-10-20 06:01:48 +08:00
										 |  |  |     factor->add(Point2(uL,v), pose_index); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-06-20 00:06:45 +08:00
										 |  |  |   Pose3 firstPose = initial_estimate.at<Pose3>(1); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   //constrain the first pose such that it cannot change from its original value during optimization
 | 
					
						
							|  |  |  |   // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
 | 
					
						
							|  |  |  |   // QR is much slower than Cholesky, but numerically more stable
 | 
					
						
							| 
									
										
										
										
											2016-10-01 23:17:41 +08:00
										 |  |  |   graph.emplace_shared<NonlinearEquality<Pose3> >(1,firstPose); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-13 04:24:03 +08:00
										 |  |  |   LevenbergMarquardtParams params; | 
					
						
							|  |  |  |   params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; | 
					
						
							|  |  |  |   params.verbosity = NonlinearOptimizerParams::ERROR; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   cout << "Optimizing" << endl; | 
					
						
							|  |  |  |   //create Levenberg-Marquardt optimizer to optimize the factor graph
 | 
					
						
							| 
									
										
										
										
											2016-06-20 03:29:37 +08:00
										 |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initial_estimate, params); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Final result sample:" << endl; | 
					
						
							| 
									
										
										
										
											2015-06-20 00:06:45 +08:00
										 |  |  |   Values pose_values = result.filter<Pose3>(); | 
					
						
							| 
									
										
										
										
											2014-05-30 23:58:07 +08:00
										 |  |  |   pose_values.print("Final camera poses:\n"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } |