| 
									
										
										
										
											2013-08-30 21:13:45 +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    SelfCalibrationExample.cpp | 
					
						
							|  |  |  |  * @brief   Based on VisualSLAMExample, but with unknown (yet fixed) calibration. | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /*
 | 
					
						
							|  |  |  |  * See the detailed documentation in Visual SLAM. | 
					
						
							|  |  |  |  * The only documentation below with deal with the self-calibration. | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // For loading the data
 | 
					
						
							| 
									
										
										
										
											2013-10-18 13:31:55 +08:00
										 |  |  | #include "SFMdata.h"
 | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Inference and optimization
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/DoglegOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // SFM-specific factors
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  | #include <gtsam/slam/GeneralSFMFactor.h>  // does calibration !
 | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Standard headers
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  |   // Create the set of ground-truth
 | 
					
						
							| 
									
										
										
										
											2013-08-31 00:53:21 +08:00
										 |  |  |   vector<Point3> points = createPoints(); | 
					
						
							|  |  |  |   vector<Pose3> poses = createPoses(); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create the factor graph
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add a prior on pose x1.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto poseNoise = noiseModel::Diagonal::Sigmas( | 
					
						
							|  |  |  |       (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)) | 
					
						
							|  |  |  |           .finished());  // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
 | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph.addPrior(Symbol('x', 0), poses[0], poseNoise); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // Simulated measurements from each camera pose, adding them to the factor
 | 
					
						
							|  |  |  |   // graph
 | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |   Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto measurementNoise = | 
					
						
							|  |  |  |       noiseModel::Isotropic::Sigma(2, 1.0); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |   for (size_t i = 0; i < poses.size(); ++i) { | 
					
						
							|  |  |  |     for (size_t j = 0; j < points.size(); ++j) { | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  |       PinholeCamera<Cal3_S2> camera(poses[i], K); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |       Point2 measurement = camera.project(points[j]); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |       // The only real difference with the Visual SLAM example is that here we
 | 
					
						
							|  |  |  |       // use a different factor type, that also calculates the Jacobian with
 | 
					
						
							|  |  |  |       // respect to calibration
 | 
					
						
							|  |  |  |       graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >( | 
					
						
							|  |  |  |           measurement, measurementNoise, Symbol('x', i), Symbol('l', j), | 
					
						
							|  |  |  |           Symbol('K', 0)); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add a prior on the position of the first landmark.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto pointNoise = | 
					
						
							|  |  |  |       noiseModel::Isotropic::Sigma(3, 0.1); | 
					
						
							|  |  |  |   graph.addPrior(Symbol('l', 0), points[0], | 
					
						
							|  |  |  |                  pointNoise);  // add directly to graph
 | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-31 00:18:41 +08:00
										 |  |  |   // Add a prior on the calibration.
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto calNoise = noiseModel::Diagonal::Sigmas( | 
					
						
							|  |  |  |       (Vector(5) << 500, 500, 0.1, 100, 100).finished()); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph.addPrior(Symbol('K', 0), K, calNoise); | 
					
						
							| 
									
										
										
										
											2013-08-31 00:18:41 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |   // Create the initial estimate to the solution
 | 
					
						
							| 
									
										
										
										
											2013-08-31 00:18:41 +08:00
										 |  |  |   // now including an estimate on the camera calibration parameters
 | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |   Values initialEstimate; | 
					
						
							|  |  |  |   initialEstimate.insert(Symbol('K', 0), Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0)); | 
					
						
							|  |  |  |   for (size_t i = 0; i < poses.size(); ++i) | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |     initialEstimate.insert( | 
					
						
							|  |  |  |         Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), | 
					
						
							|  |  |  |                                                Point3(0.05, -0.10, 0.20)))); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  |   for (size_t j = 0; j < points.size(); ++j) | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |     initialEstimate.insert<Point3>(Symbol('l', j), | 
					
						
							|  |  |  |                                    points[j] + Point3(-0.25, 0.20, 0.15)); | 
					
						
							| 
									
										
										
										
											2013-08-30 21:13:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* Optimize the graph and print results */ | 
					
						
							|  |  |  |   Values result = DoglegOptimizer(graph, initialEstimate).optimize(); | 
					
						
							|  |  |  |   result.print("Final results:\n"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 |