| 
									
										
										
										
											2011-08-19 21:11:04 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-14 11:23:14 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file Pose2SLAMExample_easy.cpp | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  |  * | 
					
						
							| 
									
										
										
										
											2011-08-19 21:11:04 +08:00
										 |  |  |  * A 2D Pose SLAM example using the predefined typedefs in gtsam/slam/pose2SLAM.h | 
					
						
							|  |  |  |  * | 
					
						
							| 
									
										
										
										
											2011-10-14 11:23:14 +08:00
										 |  |  |  * @date Oct 21, 2010 | 
					
						
							|  |  |  |  * @author ydjian | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <cmath>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include <boost/shared_ptr.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // pull in the Pose2 SLAM domain with all typedefs and helper functions defined
 | 
					
						
							|  |  |  | #include <gtsam/slam/pose2SLAM.h>
 | 
					
						
							| 
									
										
										
										
											2011-12-21 07:25:43 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearOptimization.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | using namespace pose2SLAM; | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char** argv) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* 1. create graph container and add factors to it */ | 
					
						
							|  |  |  | 	Graph graph ; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* 2.a add prior  */ | 
					
						
							|  |  |  | 	// gaussian for prior
 | 
					
						
							|  |  |  | 	SharedDiagonal prior_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.3, 0.3, 0.1)); | 
					
						
							|  |  |  | 	Pose2 prior_measurement(0.0, 0.0, 0.0); // prior at origin
 | 
					
						
							| 
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 |  |  | 	graph.addPrior(1, prior_measurement, prior_model); // add directly to graph
 | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	/* 2.b add odometry */ | 
					
						
							|  |  |  | 	// general noisemodel for odometry
 | 
					
						
							|  |  |  | 	SharedDiagonal odom_model = noiseModel::Diagonal::Sigmas(Vector_(3, 0.2, 0.2, 0.1)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* Pose2 measurements take (x,y,theta), where theta is taken from the positive x-axis*/ | 
					
						
							|  |  |  | 	Pose2 odom_measurement(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
 | 
					
						
							| 
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 |  |  | 	graph.addOdometry(1, 2, odom_measurement, odom_model); | 
					
						
							|  |  |  | 	graph.addOdometry(2, 3, odom_measurement, odom_model); | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | 	graph.print("full graph"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /* 3. Create the data structure to hold the initial estinmate to the solution
 | 
					
						
							|  |  |  |      * initialize to noisy points */ | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  | 	pose2SLAM::Values initial; | 
					
						
							| 
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 |  |  | 	initial.insertPose(1, Pose2(0.5, 0.0, 0.2)); | 
					
						
							|  |  |  | 	initial.insertPose(2, Pose2(2.3, 0.1,-0.2)); | 
					
						
							|  |  |  | 	initial.insertPose(3, Pose2(4.1, 0.1, 0.1)); | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | 	initial.print("initial estimate"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/* 4 Single Step Optimization
 | 
					
						
							|  |  |  | 	* optimize using Levenberg-Marquardt optimization with an ordering from colamd */ | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  | 	pose2SLAM::Values result = optimize<Graph>(graph, initial); | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | 	result.print("final result"); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	return 0; | 
					
						
							|  |  |  | } |