| 
									
										
										
										
											2012-06-04 16:31:26 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2012-06-05 00:05:13 +08:00
										 |  |  |  * @file    VisualISAMExample.cpp | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  |  * @brief   A visualSLAM example for the structure-from-motion problem on a simulated dataset | 
					
						
							|  |  |  |  * This version uses iSAM to solve the problem incrementally | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  |  * @author  Duy-Nguyen Ta | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |  * @author  Frank Dellaert | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * A structure-from-motion example with landmarks | 
					
						
							|  |  |  |  *  - The landmarks form a 10 meter cube | 
					
						
							|  |  |  |  *  - The robot rotates around the landmarks, always facing towards the cube | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | // For loading the data
 | 
					
						
							| 
									
										
										
										
											2013-10-18 13:31:55 +08:00
										 |  |  | #include "SFMdata.h"
 | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Each variable in the system (poses and landmarks) must be identified with a unique key.
 | 
					
						
							|  |  |  | // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
 | 
					
						
							|  |  |  | // Here we will use Symbols
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // In GTSAM, measurement functions are represented as 'factors'. Several common factors
 | 
					
						
							|  |  |  | // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
 | 
					
						
							|  |  |  | // Here we will use Projection factors to model the camera's landmark observations.
 | 
					
						
							|  |  |  | // Also, we will initialize the robot at some location using a Prior factor.
 | 
					
						
							|  |  |  | #include <gtsam/slam/ProjectionFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // We want to use iSAM to solve the structure-from-motion problem incrementally, so
 | 
					
						
							|  |  |  | // include iSAM here
 | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearISAM.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // iSAM requires as input a set set of new factors to be added stored in a factor graph,
 | 
					
						
							|  |  |  | // and initial guesses for any new variables used in the added factors
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  |   // Define the camera calibration parameters
 | 
					
						
							|  |  |  |   Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Define the camera observation noise model
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto noise = noiseModel::Isotropic::Sigma(2, 1.0);  // one pixel in u and v
 | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create the set of ground-truth landmarks
 | 
					
						
							| 
									
										
										
										
											2013-08-31 00:53:21 +08:00
										 |  |  |   vector<Point3> points = createPoints(); | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create the set of ground-truth poses
 | 
					
						
							| 
									
										
										
										
											2013-08-31 00:53:21 +08:00
										 |  |  |   vector<Pose3> poses = createPoses(); | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |   // Create a NonlinearISAM object which will relinearize and reorder the variables
 | 
					
						
							|  |  |  |   // every "relinearizeInterval" updates
 | 
					
						
							| 
									
										
										
										
											2012-07-22 22:59:22 +08:00
										 |  |  |   int relinearizeInterval = 3; | 
					
						
							| 
									
										
										
										
											2012-06-08 01:47:19 +08:00
										 |  |  |   NonlinearISAM isam(relinearizeInterval); | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  |   // Create a Factor Graph and Values to hold the new data
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   Values initialEstimate; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Loop over the different poses, adding the observations to iSAM incrementally
 | 
					
						
							|  |  |  |   for (size_t i = 0; i < poses.size(); ++i) { | 
					
						
							|  |  |  |     // Add factors for each landmark observation
 | 
					
						
							|  |  |  |     for (size_t j = 0; j < points.size(); ++j) { | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |       // Create ground truth measurement
 | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  |       PinholeCamera<Cal3_S2> camera(poses[i], *K); | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  |       Point2 measurement = camera.project(points[j]); | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |       // Add measurement
 | 
					
						
							| 
									
										
										
										
											2016-10-01 23:41:37 +08:00
										 |  |  |       graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(measurement, noise, | 
					
						
							|  |  |  |               Symbol('x', i), Symbol('l', j), K); | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Intentionally initialize the variables off from the ground truth
 | 
					
						
							| 
									
										
										
										
											2015-07-06 07:11:04 +08:00
										 |  |  |     Pose3 noise(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |     Pose3 initial_xi = poses[i].compose(noise); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Add an initial guess for the current pose
 | 
					
						
							|  |  |  |     initialEstimate.insert(Symbol('x', i), initial_xi); | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // If this is the first iteration, add a prior on the first pose to set the coordinate frame
 | 
					
						
							|  |  |  |     // and a prior on the first landmark to set the scale
 | 
					
						
							|  |  |  |     // Also, as iSAM solves incrementally, we must wait until each is observed at least twice before
 | 
					
						
							|  |  |  |     // adding it to iSAM.
 | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |     if (i == 0) { | 
					
						
							|  |  |  |       // Add a prior on pose x0, with 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |       auto poseNoise = noiseModel::Diagonal::Sigmas( | 
					
						
							| 
									
										
										
										
											2020-01-05 08:57:22 +08:00
										 |  |  |           (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished()); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |       graph.addPrior(Symbol('x', 0), poses[0], poseNoise); | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // Add a prior on landmark l0
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |       auto pointNoise = | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |           noiseModel::Isotropic::Sigma(3, 0.1); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |       graph.addPrior(Symbol('l', 0), points[0], pointNoise); | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // Add initial guesses to all observed landmarks
 | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |       Point3 noise(-0.25, 0.20, 0.15); | 
					
						
							|  |  |  |       for (size_t j = 0; j < points.size(); ++j) { | 
					
						
							|  |  |  |         // Intentionally initialize the variables off from the ground truth
 | 
					
						
							| 
									
										
										
										
											2016-02-09 05:27:38 +08:00
										 |  |  |         Point3 initial_lj = points[j] + noise; | 
					
						
							| 
									
										
										
										
											2014-09-25 20:30:41 +08:00
										 |  |  |         initialEstimate.insert(Symbol('l', j), initial_lj); | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2012-07-22 12:52:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     } else { | 
					
						
							|  |  |  |       // Update iSAM with the new factors
 | 
					
						
							|  |  |  |       isam.update(graph, initialEstimate); | 
					
						
							|  |  |  |       Values currentEstimate = isam.estimate(); | 
					
						
							|  |  |  |       cout << "****************************************************" << endl; | 
					
						
							|  |  |  |       cout << "Frame " << i << ": " << endl; | 
					
						
							|  |  |  |       currentEstimate.print("Current estimate: "); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |       // Clear the factor graph and values for the next iteration
 | 
					
						
							|  |  |  |       graph.resize(0); | 
					
						
							|  |  |  |       initialEstimate.clear(); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2012-06-04 16:31:26 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |