| 
									
										
										
										
											2013-09-07 04:07:40 +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 Pose2SLAMExample_graphviz.cpp | 
					
						
							|  |  |  |  * @brief Save factor graph as graphviz dot file | 
					
						
							|  |  |  |  * @date Sept 6, 2013 | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | // For an explanation of headers below, please see Pose2SLAMExample.cpp
 | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | #include <fstream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  | int main(int argc, char** argv) { | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  |   // 1. Create a factor graph container and add factors to it
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // 2a. Add a prior on the first pose, setting it to the origin
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph.addPrior(1, Pose2(0, 0, 0), priorNoise); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // For simplicity, we will use the same noise model for odometry and loop
 | 
					
						
							|  |  |  |   // closures
 | 
					
						
							|  |  |  |   auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 2b. Add odometry factors
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2, 0, 0), model); | 
					
						
							| 
									
										
										
										
											2016-09-09 20:33:51 +08:00
										 |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2, 0, M_PI_2), model); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2, 0, M_PI_2), model); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2, 0, M_PI_2), model); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 2c. Add the loop closure constraint
 | 
					
						
							| 
									
										
										
										
											2016-09-09 20:33:51 +08:00
										 |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(5, 2, Pose2(2, 0, M_PI_2), model); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 3. Create the data structure to hold the initial estimate to the solution
 | 
					
						
							|  |  |  |   // For illustrative purposes, these have been deliberately set to incorrect values
 | 
					
						
							|  |  |  |   Values initial; | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   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, M_PI_2)); | 
					
						
							|  |  |  |   initial.insert(4, Pose2(4.0, 2.0, M_PI)); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  |   initial.insert(5, Pose2(2.1, 2.1, -M_PI_2)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Single Step Optimization using Levenberg-Marquardt
 | 
					
						
							|  |  |  |   Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // save factor graph as graphviz dot file
 | 
					
						
							| 
									
										
										
										
											2013-09-07 05:27:27 +08:00
										 |  |  |   // Render to PDF using "fdp Pose2SLAMExample.dot -Tpdf > graph.pdf"
 | 
					
						
							| 
									
										
										
										
											2021-12-21 23:17:36 +08:00
										 |  |  |   graph.saveGraph("Pose2SLAMExample.dot", result); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Also print out to console
 | 
					
						
							| 
									
										
										
										
											2021-12-21 23:17:36 +08:00
										 |  |  |   graph.dot(cout, result); | 
					
						
							| 
									
										
										
										
											2013-09-07 04:07:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } |