| 
									
										
										
										
											2014-10-22 01:15:48 +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 METISOrdering.cpp | 
					
						
							|  |  |  |  * @brief Simple robot motion example, with prior and two odometry measurements, using a METIS ordering | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  * @author Andrew Melim | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2014-11-18 01:06:59 +08:00
										 |  |  |  * Example of a simple 2D localization example optimized using METIS ordering | 
					
						
							|  |  |  |  * - For more details on the full optimization pipeline, see OdometryExample.cpp | 
					
						
							| 
									
										
										
										
											2014-10-22 01:15:48 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Marginals.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char** argv) { | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
 | 
					
						
							| 
									
										
										
										
											2014-11-25 07:15:56 +08:00
										 |  |  |   noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); | 
					
						
							| 
									
										
										
										
											2014-10-22 01:15:48 +08:00
										 |  |  |   graph.add(PriorFactor<Pose2>(1, priorMean, priorNoise)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Pose2 odometry(2.0, 0.0, 0.0); | 
					
						
							| 
									
										
										
										
											2014-11-25 07:15:56 +08:00
										 |  |  |   noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2014-10-22 01:15:48 +08:00
										 |  |  |   graph.add(BetweenFactor<Pose2>(1, 2, odometry, odometryNoise)); | 
					
						
							|  |  |  |   graph.add(BetweenFactor<Pose2>(2, 3, odometry, odometryNoise)); | 
					
						
							|  |  |  |   graph.print("\nFactor Graph:\n"); // print
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   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
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // optimize using Levenberg-Marquardt optimization
 | 
					
						
							| 
									
										
										
										
											2014-10-22 03:56:40 +08:00
										 |  |  |   LevenbergMarquardtParams params; | 
					
						
							| 
									
										
										
										
											2014-11-18 01:06:59 +08:00
										 |  |  |   // In order to specify the ordering type, we need to se the NonlinearOptimizerParameter "orderingType"
 | 
					
						
							|  |  |  |   // By default this parameter is set to OrderingType::COLAMD
 | 
					
						
							| 
									
										
										
										
											2014-11-18 05:16:52 +08:00
										 |  |  |   params.orderingType = Ordering::METIS; | 
					
						
							| 
									
										
										
										
											2014-10-22 03:56:40 +08:00
										 |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initial, params); | 
					
						
							|  |  |  |   Values result = optimizer.optimize(); | 
					
						
							| 
									
										
										
										
											2014-10-22 01:15:48 +08:00
										 |  |  |   result.print("Final Result:\n"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							| 
									
										
										
										
											2014-11-18 05:16:52 +08:00
										 |  |  | } |