| 
									
										
										
										
											2013-06-24 16:24:56 +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  testSmartRangeFactor.cpp | 
					
						
							|  |  |  |  *  @brief Unit tests for SmartRangeFactor Class | 
					
						
							|  |  |  |  *  @author Frank Dellaert | 
					
						
							|  |  |  |  *  @date Nov 2013 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/SmartRangeFactor.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  | static const double sigma = 2.0; | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  | // Test situation:
 | 
					
						
							|  |  |  | static const Point2 p(0, 10); | 
					
						
							|  |  |  | static const Pose2 pose1(0, 0, 0), pose2(5, 0, 0), pose3(5, 5, 0); | 
					
						
							|  |  |  | static const double r1 = pose1.range(p), r2 = pose2.range(p), r3 = pose3.range( | 
					
						
							|  |  |  |     p); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | TEST( SmartRangeFactor, constructor ) { | 
					
						
							|  |  |  |   SmartRangeFactor f1; | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |   LONGS_EQUAL(0, f1.size()) | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   SmartRangeFactor f2(sigma); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |   LONGS_EQUAL(0, f2.size()) | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | TEST( SmartRangeFactor, addRange ) { | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   SmartRangeFactor f(sigma); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   f.addRange(1, 10); | 
					
						
							|  |  |  |   f.addRange(1, 12); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |   LONGS_EQUAL(2, f.size()) | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  | TEST( SmartRangeFactor, scenario ) { | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   DOUBLES_EQUAL(10, r1, 1e-9); | 
					
						
							| 
									
										
										
										
											2013-11-06 00:06:10 +08:00
										 |  |  |   DOUBLES_EQUAL(sqrt(100.0+25.0), r2, 1e-9); | 
					
						
							|  |  |  |   DOUBLES_EQUAL(sqrt(50.0), r3, 1e-9); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  | TEST( SmartRangeFactor, unwhitenedError ) { | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   Values values; // all correct
 | 
					
						
							|  |  |  |   values.insert(1, pose1); | 
					
						
							|  |  |  |   values.insert(2, pose2); | 
					
						
							|  |  |  |   values.insert(3, pose3); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   SmartRangeFactor f(sigma); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   f.addRange(1, r1); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |   // Check Jacobian for n==1
 | 
					
						
							|  |  |  |   vector<Matrix> H1(1); | 
					
						
							|  |  |  |   f.unwhitenedError(values, H1); // with H now !
 | 
					
						
							|  |  |  |   CHECK(assert_equal(zeros(3,1), H1.front())); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   // Whenever there are two ranges or less, error should be zero
 | 
					
						
							|  |  |  |   Vector actual1 = f.unwhitenedError(values); | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   EXPECT(assert_equal((Vector(1) << 0.0).finished(), actual1)); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   f.addRange(2, r2); | 
					
						
							|  |  |  |   Vector actual2 = f.unwhitenedError(values); | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   EXPECT(assert_equal((Vector(1) << 0.0).finished(), actual2)); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   f.addRange(3, r3); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   vector<Matrix> H(3); | 
					
						
							|  |  |  |   Vector actual3 = f.unwhitenedError(values); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   EXPECT_LONGS_EQUAL(3, f.keys().size()); | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   EXPECT(assert_equal((Vector(1) << 0.0).finished(), actual3)); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:07:21 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Check keys and Jacobian
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   Vector actual4 = f.unwhitenedError(values, H); // with H now !
 | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   EXPECT(assert_equal((Vector(1) << 0.0).finished(), actual4)); | 
					
						
							|  |  |  |   CHECK(assert_equal((Matrix(1, 3) << 0.0,-1.0,0.0).finished(), H.front())); | 
					
						
							|  |  |  |   CHECK(assert_equal((Matrix(1, 3) << sqrt(2.0)/2,-sqrt(2.0)/2,0.0).finished(), H.back())); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Test clone
 | 
					
						
							|  |  |  |   NonlinearFactor::shared_ptr clone = f.clone(); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   EXPECT_LONGS_EQUAL(3, clone->keys().size()); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | TEST( SmartRangeFactor, optimization ) { | 
					
						
							|  |  |  |   SmartRangeFactor f(sigma); | 
					
						
							|  |  |  |   f.addRange(1, r1); | 
					
						
							|  |  |  |   f.addRange(2, r2); | 
					
						
							|  |  |  |   f.addRange(3, r3); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create initial value for optimization
 | 
					
						
							|  |  |  |   Values initial; | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  |   initial.insert(1, pose1); | 
					
						
							|  |  |  |   initial.insert(2, pose2); | 
					
						
							|  |  |  |   initial.insert(3, Pose2(5, 6, 0)); // does not satisfy range measurement
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   Vector actual5 = f.unwhitenedError(initial); | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   EXPECT(assert_equal((Vector(1) << sqrt(25.0+16.0)-sqrt(50.0)).finished(), actual5)); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  |   // Create Factor graph
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2013-08-09 04:08:54 +08:00
										 |  |  |   graph.push_back(f); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   const noiseModel::Base::shared_ptr //
 | 
					
						
							|  |  |  |   priorNoise = noiseModel::Diagonal::Sigmas(Vector3(1, 1, M_PI)); | 
					
						
							| 
									
										
										
										
											2013-08-09 04:08:54 +08:00
										 |  |  |   graph.push_back(PriorFactor<Pose2>(1, pose1, priorNoise)); | 
					
						
							|  |  |  |   graph.push_back(PriorFactor<Pose2>(2, pose2, priorNoise)); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Try optimizing
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   LevenbergMarquardtParams params; | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   //  params.setVerbosity("ERROR");
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:02:17 +08:00
										 |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initial, params); | 
					
						
							|  |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(initial.at<Pose2>(1), result.at<Pose2>(1))); | 
					
						
							|  |  |  |   EXPECT(assert_equal(initial.at<Pose2>(2), result.at<Pose2>(2))); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   // only the third pose will be changed, converges on following:
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   EXPECT(assert_equal(Pose2(5.52159, 5.582727, 0), result.at<Pose2>(3),1e-5)); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  |   TestResult tr; | 
					
						
							|  |  |  |   return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 |