| 
									
										
										
										
											2013-02-28 04:23:47 +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    testIncrementalFixedLagSmoother.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for the Incremental Fixed-Lag Smoother | 
					
						
							|  |  |  |  * @author  Stephen Williams (swilliams8@gatech.edu) | 
					
						
							|  |  |  |  * @date    May 23, 2012 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							| 
									
										
										
										
											2015-05-14 13:26:24 +08:00
										 |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							| 
									
										
										
										
											2015-05-14 13:26:24 +08:00
										 |  |  | #include <gtsam/linear/GaussianBayesNet.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Key.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Ordering.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2015-05-14 13:26:24 +08:00
										 |  |  | #include <gtsam/base/debug.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | Key MakeKey(size_t index) { return Symbol('x', index); } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | bool check_smoother(const NonlinearFactorGraph& fullgraph, const Values& fullinit, const IncrementalFixedLagSmoother& smoother, const Key& key) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:26 +08:00
										 |  |  |   GaussianFactorGraph linearized = *fullgraph.linearize(fullinit); | 
					
						
							|  |  |  |   VectorValues delta = linearized.optimize(); | 
					
						
							|  |  |  |   Values fullfinal = fullinit.retract(delta); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Point2 expected = fullfinal.at<Point2>(key); | 
					
						
							|  |  |  |   Point2 actual = smoother.calculateEstimate<Point2>(key); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return assert_equal(expected, actual); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-07 02:04:40 +08:00
										 |  |  | TEST( IncrementalFixedLagSmoother, Example ) | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   // Test the IncrementalFixedLagSmoother in a pure linear environment. Thus, full optimization and
 | 
					
						
							|  |  |  |   // the IncrementalFixedLagSmoother should be identical (even with the linearized approximations at
 | 
					
						
							|  |  |  |   // the end of the smoothing lag)
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   SETDEBUG("IncrementalFixedLagSmoother update", true); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Set up parameters
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   SharedDiagonal odometerNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); | 
					
						
							|  |  |  |   SharedDiagonal loopNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create a Fixed-Lag Smoother
 | 
					
						
							|  |  |  |   typedef IncrementalFixedLagSmoother::KeyTimestampMap Timestamps; | 
					
						
							|  |  |  |   IncrementalFixedLagSmoother smoother(7.0, ISAM2Params()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create containers to keep the full graph
 | 
					
						
							|  |  |  |   Values fullinit; | 
					
						
							|  |  |  |   NonlinearFactorGraph fullgraph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // i keeps track of the time step
 | 
					
						
							|  |  |  |   size_t i = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add a prior at time 0 and update the HMF
 | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     Key key0 = MakeKey(0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     NonlinearFactorGraph newFactors; | 
					
						
							|  |  |  |     Values newValues; | 
					
						
							|  |  |  |     Timestamps newTimestamps; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-15 03:12:24 +08:00
										 |  |  |     newFactors.push_back(PriorFactor<Point2>(key0, Point2(0.0, 0.0), odometerNoise)); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |     newValues.insert(key0, Point2(0.01, 0.01)); | 
					
						
							|  |  |  |     newTimestamps[key0] = 0.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     fullgraph.push_back(newFactors); | 
					
						
							|  |  |  |     fullinit.insert(newValues); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Update the smoother
 | 
					
						
							|  |  |  |     smoother.update(newFactors, newValues, newTimestamps); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check
 | 
					
						
							|  |  |  |     CHECK(check_smoother(fullgraph, fullinit, smoother, key0)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     ++i; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add odometry from time 0 to time 5
 | 
					
						
							|  |  |  |   while(i <= 5) { | 
					
						
							|  |  |  |     Key key1 = MakeKey(i-1); | 
					
						
							|  |  |  |     Key key2 = MakeKey(i); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     NonlinearFactorGraph newFactors; | 
					
						
							|  |  |  |     Values newValues; | 
					
						
							|  |  |  |     Timestamps newTimestamps; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-15 03:12:24 +08:00
										 |  |  |     newFactors.push_back(BetweenFactor<Point2>(key1, key2, Point2(1.0, 0.0), odometerNoise)); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |     newValues.insert(key2, Point2(double(i)+0.1, -0.1)); | 
					
						
							|  |  |  |     newTimestamps[key2] = double(i); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     fullgraph.push_back(newFactors); | 
					
						
							|  |  |  |     fullinit.insert(newValues); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Update the smoother
 | 
					
						
							|  |  |  |     smoother.update(newFactors, newValues, newTimestamps); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check
 | 
					
						
							|  |  |  |     CHECK(check_smoother(fullgraph, fullinit, smoother, key2)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     ++i; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add odometry from time 5 to 6 to the HMF and a loop closure at time 5 to the TSM
 | 
					
						
							|  |  |  |   { | 
					
						
							|  |  |  |     // Add the odometry factor to the HMF
 | 
					
						
							|  |  |  |     Key key1 = MakeKey(i-1); | 
					
						
							|  |  |  |     Key key2 = MakeKey(i); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     NonlinearFactorGraph newFactors; | 
					
						
							|  |  |  |     Values newValues; | 
					
						
							|  |  |  |     Timestamps newTimestamps; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-15 03:12:24 +08:00
										 |  |  |     newFactors.push_back(BetweenFactor<Point2>(key1, key2, Point2(1.0, 0.0), odometerNoise)); | 
					
						
							|  |  |  |     newFactors.push_back(BetweenFactor<Point2>(MakeKey(2), MakeKey(5), Point2(3.5, 0.0), loopNoise)); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |     newValues.insert(key2, Point2(double(i)+0.1, -0.1)); | 
					
						
							|  |  |  |     newTimestamps[key2] = double(i); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     fullgraph.push_back(newFactors); | 
					
						
							|  |  |  |     fullinit.insert(newValues); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Update the smoother
 | 
					
						
							|  |  |  |     smoother.update(newFactors, newValues, newTimestamps); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check
 | 
					
						
							|  |  |  |     CHECK(check_smoother(fullgraph, fullinit, smoother, key2)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     ++i; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add odometry from time 6 to time 15
 | 
					
						
							|  |  |  |   while(i <= 15) { | 
					
						
							|  |  |  |     Key key1 = MakeKey(i-1); | 
					
						
							|  |  |  |     Key key2 = MakeKey(i); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     NonlinearFactorGraph newFactors; | 
					
						
							|  |  |  |     Values newValues; | 
					
						
							|  |  |  |     Timestamps newTimestamps; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-15 03:12:24 +08:00
										 |  |  |     newFactors.push_back(BetweenFactor<Point2>(key1, key2, Point2(1.0, 0.0), odometerNoise)); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |     newValues.insert(key2, Point2(double(i)+0.1, -0.1)); | 
					
						
							|  |  |  |     newTimestamps[key2] = double(i); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     fullgraph.push_back(newFactors); | 
					
						
							|  |  |  |     fullinit.insert(newValues); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Update the smoother
 | 
					
						
							|  |  |  |     smoother.update(newFactors, newValues, newTimestamps); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check
 | 
					
						
							|  |  |  |     CHECK(check_smoother(fullgraph, fullinit, smoother, key2)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     ++i; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr);} | 
					
						
							|  |  |  | /* ************************************************************************* */ |