| 
									
										
										
										
											2012-05-21 04:31:33 +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-12 13:01:12 +08:00
										 |  |  |  * @file OdometryExample.cpp | 
					
						
							|  |  |  |  * @brief Simple robot motion example, with prior and two odometry measurements | 
					
						
							| 
									
										
										
										
											2012-05-21 04:31:33 +08:00
										 |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * Example of a simple 2D localization example | 
					
						
							|  |  |  |  *  - Robot poses are facing along the X axis (horizontal, to the right in 2D) | 
					
						
							|  |  |  |  *  - The robot moves 2 meters each step | 
					
						
							|  |  |  |  *  - We have full odometry between poses | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2012-05-21 04:31:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 00:59:14 +08:00
										 |  |  | // We will use Pose2 variables (x, y, theta) to represent the robot positions
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // 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 Between factors for the relative motion described by odometry measurements.
 | 
					
						
							|  |  |  | // Also, we will initialize the robot at the origin using a Prior factor.
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // When the factors are created, we will add them to a Factor Graph. As the factors we are using
 | 
					
						
							|  |  |  | // are nonlinear factors, we will need a Nonlinear Factor Graph.
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Finally, once all of the factors have been added to our factor graph, we will want to
 | 
					
						
							|  |  |  | // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
 | 
					
						
							|  |  |  | // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
 | 
					
						
							|  |  |  | // Levenberg-Marquardt solver
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Once the optimized values have been calculated, we can also calculate the marginal covariance
 | 
					
						
							|  |  |  | // of desired variables
 | 
					
						
							| 
									
										
										
										
											2012-05-21 06:02:11 +08:00
										 |  |  | #include <gtsam/nonlinear/Marginals.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  | // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
 | 
					
						
							|  |  |  | // nonlinear functions around an initial linearization point, then solve the linear system
 | 
					
						
							|  |  |  | // to update the linearization point. This happens repeatedly until the solver converges
 | 
					
						
							|  |  |  | // to a consistent set of variable values. This requires us to specify an initial guess
 | 
					
						
							|  |  |  | // for each variable, held in a Values container.
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-21 04:31:33 +08:00
										 |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char** argv) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-05 04:18:42 +08:00
										 |  |  |   // Create an empty nonlinear factor graph
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add a prior on the first pose, setting it to the origin
 | 
					
						
							|  |  |  |   // A prior factor consists of a mean and a noise model (covariance matrix)
 | 
					
						
							| 
									
										
										
										
											2012-08-05 04:18:42 +08:00
										 |  |  |   Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); | 
					
						
							| 
									
										
										
										
											2016-10-01 23:41:37 +08:00
										 |  |  |   graph.emplace_shared<PriorFactor<Pose2> >(1, priorMean, priorNoise); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Add odometry factors
 | 
					
						
							| 
									
										
										
										
											2012-08-05 04:18:42 +08:00
										 |  |  |   Pose2 odometry(2.0, 0.0, 0.0); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  |   // For simplicity, we will use the same noise model for each odometry factor
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  |   // Create odometry (Between) factors between consecutive poses
 | 
					
						
							| 
									
										
										
										
											2016-10-01 23:41:37 +08:00
										 |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, odometry, odometryNoise); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, odometry, odometryNoise); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  |   graph.print("\nFactor Graph:\n"); // print
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create the data structure to hold the initialEstimate estimate to the solution
 | 
					
						
							|  |  |  |   // For illustrative purposes, these have been deliberately set to incorrect values
 | 
					
						
							| 
									
										
										
										
											2012-08-05 05:56:21 +08:00
										 |  |  |   Values initial; | 
					
						
							|  |  |  |   initial.insert(1, Pose2(0.5, 0.0, 0.2)); | 
					
						
							|  |  |  |   initial.insert(2, Pose2(2.3, 0.1, -0.2)); | 
					
						
							|  |  |  |   initial.insert(3, Pose2(4.1, 0.1, 0.1)); | 
					
						
							|  |  |  |   initial.print("\nInitial Estimate:\n"); // print
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // optimize using Levenberg-Marquardt optimization
 | 
					
						
							| 
									
										
										
										
											2012-08-05 05:56:21 +08:00
										 |  |  |   Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  |   result.print("Final Result:\n"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Calculate and print marginal covariances for all variables
 | 
					
						
							| 
									
										
										
										
											2012-08-05 05:56:21 +08:00
										 |  |  |   cout.precision(2); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  |   Marginals marginals(graph, result); | 
					
						
							| 
									
										
										
										
											2012-08-05 05:56:21 +08:00
										 |  |  |   cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; | 
					
						
							|  |  |  |   cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; | 
					
						
							|  |  |  |   cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; | 
					
						
							| 
									
										
										
										
											2012-07-22 13:21:32 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							| 
									
										
										
										
											2012-05-21 04:31:33 +08:00
										 |  |  | } |