| 
									
										
										
										
											2014-05-29 12:04:03 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |  * @file StereoVOExample.cpp | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  |  * @brief A stereo visual odometry example | 
					
						
							|  |  |  |  * @date May 25, 2014 | 
					
						
							|  |  |  |  * @author Stephen Camp | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * A 3D stereo visual odometry example | 
					
						
							|  |  |  |  *  - robot starts at origin | 
					
						
							|  |  |  |  *  -moves forward 1 meter | 
					
						
							|  |  |  |  *  -takes stereo readings on three landmarks | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  | #include <gtsam/geometry/Cal3_S2Stereo.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearEquality.h>
 | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/StereoFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  | int main(int argc, char** argv) { | 
					
						
							|  |  |  |   // create graph object, add first pose at origin with key '1'
 | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  |   Pose3 first_pose; | 
					
						
							| 
									
										
										
										
											2016-10-01 23:17:41 +08:00
										 |  |  |   graph.emplace_shared<NonlinearEquality<Pose3> >(1, Pose3()); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // create factor noise model with 3 sigmas of value 1
 | 
					
						
							|  |  |  |   const auto model = noiseModel::Isotropic::Sigma(3, 1); | 
					
						
							|  |  |  |   // create stereo camera calibration object with .2m between cameras
 | 
					
						
							|  |  |  |   const Cal3_S2Stereo::shared_ptr K( | 
					
						
							|  |  |  |       new Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2)); | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  |   //create and add stereo factors between first pose (key value 1) and the three landmarks
 | 
					
						
							| 
									
										
										
										
											2016-10-01 23:17:41 +08:00
										 |  |  |   graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(520, 480, 440), model, 1, 3, K); | 
					
						
							|  |  |  |   graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(120, 80, 440), model, 1, 4, K); | 
					
						
							|  |  |  |   graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(320, 280, 140), model, 1, 5, K); | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  |   //create and add stereo factors between second pose and the three landmarks
 | 
					
						
							| 
									
										
										
										
											2016-10-01 23:17:41 +08:00
										 |  |  |   graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(570, 520, 490), model, 2, 3, K); | 
					
						
							|  |  |  |   graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(70, 20, 490), model, 2, 4, K); | 
					
						
							|  |  |  |   graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(320, 270, 115), model, 2, 5, K); | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // create Values object to contain initial estimates of camera poses and
 | 
					
						
							|  |  |  |   // landmark locations
 | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  |   Values initial_estimate; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // create and add iniital estimates
 | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  |   initial_estimate.insert(1, first_pose); | 
					
						
							|  |  |  |   initial_estimate.insert(2, Pose3(Rot3(), Point3(0.1, -0.1, 1.1))); | 
					
						
							|  |  |  |   initial_estimate.insert(3, Point3(1, 1, 5)); | 
					
						
							|  |  |  |   initial_estimate.insert(4, Point3(-1, 1, 5)); | 
					
						
							|  |  |  |   initial_estimate.insert(5, Point3(0, -0.5, 5)); | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // create Levenberg-Marquardt optimizer for resulting factor graph, optimize
 | 
					
						
							| 
									
										
										
										
											2016-06-20 03:29:37 +08:00
										 |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initial_estimate); | 
					
						
							| 
									
										
										
										
											2014-05-29 12:04:03 +08:00
										 |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   result.print("Final result:\n"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							| 
									
										
										
										
											2014-06-13 04:09:39 +08:00
										 |  |  | } |