2010-10-14 12:54:38 +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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-19 21:11:04 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * @file Pose2SLAMExample_advanced.cpp
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @brief Simple Pose2SLAM Example using
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * pre-built pose2SLAM domain
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author Chris Beall
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#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>
							 | 
						
					
						
							
								
									
										
										
										
											2012-03-25 03:53:17 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 08:15:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/Marginals.h>
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-23 05:27:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/Vector.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/Matrix.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace std;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace gtsam;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace boost;
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								using namespace pose2SLAM;
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								int main(int argc, char** argv) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									/* 1. create graph container and add factors to it */
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									Graph graph;
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									/* 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-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									graph.addPrior(1, prior_measurement, prior_model); // add directly to graph
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +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-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									graph.addOdometry(1, 2, odom_measurement, odom_model);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									graph.addOdometry(2, 3, odom_measurement, odom_model);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									graph.print("full graph");
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-23 05:27:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /* 3. Create the data structure to hold the initial estimate to the solution
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * initialize to noisy points */
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									pose2SLAM::Values initial;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									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));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									initial.print("initial estimate");
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									/* 4.2.1 Alternatively, you can go through the process step by step
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 * Choose an ordering */
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									Ordering ordering = *graph.orderingCOLAMD(initial);
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									/* 4.2.2 set up solver and optimize */
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									LevenbergMarquardtParams params;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									params.absoluteErrorTol = 1e-15;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									params.relativeErrorTol = 1e-15;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									params.ordering = ordering;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LevenbergMarquardtOptimizer	optimizer(graph, initial, params);
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 04:25:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									pose2SLAM::Values result = optimizer.optimize();
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									result.print("final result");
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-23 05:27:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-15 08:15:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									/* Get covariances */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									Marginals marginals(graph, result, Marginals::CHOLESKY);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									Matrix covariance1  = marginals.marginalCovariance(PoseKey(1));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									Matrix covariance2  = marginals.marginalCovariance(PoseKey(2));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									print(covariance1, "Covariance1");
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									print(covariance2, "Covariance2");
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-23 05:27:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 09:07:55 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									return 0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 |