| 
									
										
										
										
											2014-07-31 06:51:12 +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    testGaussMarkov1stOrderFactor.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for the GaussMarkov1stOrder factor | 
					
						
							|  |  |  |  * @author  Vadim Indelman | 
					
						
							|  |  |  |  * @date    Jan 17, 2012 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-07 01:11:27 +08:00
										 |  |  | #include <gtsam_unstable/slam/GaussMarkov1stOrderFactor.h>
 | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/Key.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2015-07-10 02:28:59 +08:00
										 |  |  | #include <gtsam/base/deprecated/LieVector.h>
 | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | //! Factors
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  | typedef GaussMarkov1stOrderFactor<LieVector> GaussMarkovFactor; | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  | LieVector predictionError(const LieVector& v1, const LieVector& v2, const GaussMarkovFactor factor) { | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  |   return factor.evaluateError(v1, v2); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussMarkovFactor, equals ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   // Create two identical factors and make sure they're equal
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   Key x1(1); | 
					
						
							|  |  |  |   Key x2(2); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  |   double delta_t = 0.10; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector tau = Vector3(100.0, 150.0, 10.0); | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   SharedGaussian model = noiseModel::Isotropic::Sigma(3, 1.0); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   GaussMarkovFactor factor1(x1, x2, delta_t, tau, model); | 
					
						
							|  |  |  |   GaussMarkovFactor factor2(x1, x2, delta_t, tau, model); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   CHECK(assert_equal(factor1, factor2)); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussMarkovFactor, error ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   Values linPoint; | 
					
						
							|  |  |  |   Key x1(1); | 
					
						
							|  |  |  |   Key x2(2); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  |   double delta_t = 0.10; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector tau = Vector3(100.0, 150.0, 10.0); | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   SharedGaussian model = noiseModel::Isotropic::Sigma(3, 1.0); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   LieVector v1 = LieVector(Vector3(10.0, 12.0, 13.0)); | 
					
						
							|  |  |  |   LieVector v2 = LieVector(Vector3(10.0, 15.0, 14.0)); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create two nodes
 | 
					
						
							|  |  |  |   linPoint.insert(x1, v1); | 
					
						
							|  |  |  |   linPoint.insert(x2, v2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   GaussMarkovFactor factor(x1, x2, delta_t, tau, model); | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   Vector Err1( factor.evaluateError(v1, v2) ); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Manually calculate the error
 | 
					
						
							|  |  |  |   Vector alpha(tau.size()); | 
					
						
							|  |  |  |   Vector alpha_v1(tau.size()); | 
					
						
							|  |  |  |   for(int i=0; i<tau.size(); i++){ | 
					
						
							|  |  |  |     alpha(i) = exp(- 1/tau(i)*delta_t ); | 
					
						
							|  |  |  |     alpha_v1(i) = alpha(i) * v1(i); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   Vector Err2( v2 - alpha_v1 ); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   CHECK(assert_equal(Err1, Err2, 1e-9)); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (GaussMarkovFactor, jacobian ) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   Values linPoint; | 
					
						
							|  |  |  |   Key x1(1); | 
					
						
							|  |  |  |   Key x2(2); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  |   double delta_t = 0.10; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector tau = Vector3(100.0, 150.0, 10.0); | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   SharedGaussian model = noiseModel::Isotropic::Sigma(3, 1.0); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   GaussMarkovFactor factor(x1, x2, delta_t, tau, model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Update the linearization point
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   LieVector v1_upd = LieVector(Vector3(0.5, -0.7, 0.3)); | 
					
						
							|  |  |  |   LieVector v2_upd = LieVector(Vector3(-0.7, 0.4, 0.9)); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Calculate the Jacobian matrix using the factor
 | 
					
						
							|  |  |  |   Matrix computed_H1, computed_H2; | 
					
						
							|  |  |  |   factor.evaluateError(v1_upd, v2_upd, computed_H1, computed_H2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Calculate the Jacobian matrices H1 and H2 using the numerical derivative function
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   Matrix numerical_H1, numerical_H2; | 
					
						
							|  |  |  |   numerical_H1 = numericalDerivative21<Vector3, Vector3, Vector3>( | 
					
						
							|  |  |  |       boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd); | 
					
						
							|  |  |  |   numerical_H2 = numericalDerivative22<Vector3, Vector3, Vector3>( | 
					
						
							|  |  |  |       boost::bind(&predictionError, _1, _2, factor), v1_upd, v2_upd); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Verify they are equal for this choice of state
 | 
					
						
							| 
									
										
										
										
											2014-11-05 00:04:57 +08:00
										 |  |  |   CHECK( assert_equal(numerical_H1, computed_H1, 1e-9)); | 
					
						
							|  |  |  |   CHECK( assert_equal(numerical_H2, computed_H2, 1e-9)); | 
					
						
							| 
									
										
										
										
											2014-07-31 06:51:12 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   TestResult tr; return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 |