| 
									
										
										
										
											2014-10-01 20:10:54 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2014-10-03 02:19:49 +08:00
										 |  |  |  * @file    SFMExampleExpressions.cpp | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  |  * @brief   A structure-from-motion example done with Expressions | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  * @author  Duy-Nguyen Ta | 
					
						
							|  |  |  |  * @date    October 1, 2014 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * This is the Expression version of SFMExample | 
					
						
							|  |  |  |  * See detailed description of headers there, this focuses on explaining the AD part | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // The two new headers that allow using our Automatic Differentiation Expression framework
 | 
					
						
							| 
									
										
										
										
											2014-12-29 02:10:41 +08:00
										 |  |  | #include <gtsam/slam/expressions.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/ExpressionFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Header order is close to far
 | 
					
						
							|  |  |  | #include <examples/SFMdata.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/DoglegOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  | using namespace noiseModel; | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-02 17:21:24 +08:00
										 |  |  |   Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0); | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   Isotropic::shared_ptr measurementNoise = Isotropic::Sigma(2, 1.0); // one pixel in u and v
 | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create the set of ground-truth landmarks and poses
 | 
					
						
							|  |  |  |   vector<Point3> points = createPoints(); | 
					
						
							|  |  |  |   vector<Pose3> poses = createPoses(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create a factor graph
 | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   ExpressionFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Specify uncertainty on first pose prior
 | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   Vector6 sigmas; sigmas << Vector3(0.3,0.3,0.3), Vector3(0.1,0.1,0.1); | 
					
						
							|  |  |  |   Diagonal::shared_ptr poseNoise = Diagonal::Sigmas(sigmas); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-09 19:00:56 +08:00
										 |  |  |   // Here we don't use a PriorFactor but directly the ExpressionFactor class
 | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   // x0 is an Expression, and we create a factor wanting it to be equal to poses[0]
 | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  |   Pose3_ x0('x',0); | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   graph.addExpressionFactor(x0, poses[0], poseNoise); | 
					
						
							| 
									
										
										
										
											2014-10-02 17:21:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // We create a constant Expression for the calibration here
 | 
					
						
							|  |  |  |   Cal3_S2_ cK(K); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Simulated measurements from each camera pose, adding them to the factor graph
 | 
					
						
							|  |  |  |   for (size_t i = 0; i < poses.size(); ++i) { | 
					
						
							| 
									
										
										
										
											2014-10-02 17:44:16 +08:00
										 |  |  |     Pose3_ x('x', i); | 
					
						
							|  |  |  |     SimpleCamera camera(poses[i], K); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  |     for (size_t j = 0; j < points.size(); ++j) { | 
					
						
							|  |  |  |       Point2 measurement = camera.project(points[j]); | 
					
						
							| 
									
										
										
										
											2014-10-02 17:21:24 +08:00
										 |  |  |       // Below an expression for the prediction of the measurement:
 | 
					
						
							|  |  |  |       Point3_ p('l', j); | 
					
						
							| 
									
										
										
										
											2014-10-03 02:19:49 +08:00
										 |  |  |       Point2_ prediction = uncalibrate(cK, project(transform_to(x, p))); | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |       // Again, here we use an ExpressionFactor
 | 
					
						
							|  |  |  |       graph.addExpressionFactor(prediction, measurement, measurementNoise); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-09 19:00:56 +08:00
										 |  |  |   // Add prior on first point to constrain scale, again with ExpressionFactor
 | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   Isotropic::shared_ptr pointNoise = Isotropic::Sigma(3, 0.1); | 
					
						
							|  |  |  |   graph.addExpressionFactor(Point3_('l', 0), points[0], pointNoise); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-02 17:21:24 +08:00
										 |  |  |   // Create perturbed initial
 | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   Values initial; | 
					
						
							| 
									
										
										
										
											2015-07-06 07:11:04 +08:00
										 |  |  |   Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  |   for (size_t i = 0; i < poses.size(); ++i) | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |     initial.insert(Symbol('x', i), poses[i].compose(delta)); | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  |   for (size_t j = 0; j < points.size(); ++j) | 
					
						
							| 
									
										
										
										
											2016-02-09 09:32:25 +08:00
										 |  |  |     initial.insert<Point3>(Symbol('l', j), points[j] + Point3(-0.25, 0.20, 0.15)); | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   cout << "initial error = " << graph.error(initial) << endl; | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* Optimize the graph and print results */ | 
					
						
							| 
									
										
										
										
											2014-12-13 15:35:22 +08:00
										 |  |  |   Values result = DoglegOptimizer(graph, initial).optimize(); | 
					
						
							| 
									
										
										
										
											2014-10-02 17:21:24 +08:00
										 |  |  |   cout << "final error = " << graph.error(result) << endl; | 
					
						
							| 
									
										
										
										
											2014-10-01 20:10:54 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 |