| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * testNoiseModel.cpp | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Jan 13, 2010 | 
					
						
							| 
									
										
										
										
											2010-01-17 08:37:34 +08:00
										 |  |  |  *      Author: Richard Roberts | 
					
						
							|  |  |  |  *      Author: Frank Dellaert | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | #include <boost/foreach.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include "NoiseModel.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | #include "SharedGaussian.h"
 | 
					
						
							|  |  |  | #include "SharedDiagonal.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | using namespace noiseModel; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | static double sigma = 2, s_1=1.0/sigma, var = sigma*sigma, prc = 1.0/var; | 
					
						
							|  |  |  | static Matrix R = Matrix_(3, 3, | 
					
						
							|  |  |  | 		s_1, 0.0, 0.0, | 
					
						
							|  |  |  | 		0.0, s_1, 0.0, | 
					
						
							|  |  |  | 		0.0, 0.0, s_1); | 
					
						
							|  |  |  | static Matrix Sigma = Matrix_(3, 3, | 
					
						
							|  |  |  | 		var, 0.0, 0.0, | 
					
						
							|  |  |  | 		0.0, var, 0.0, | 
					
						
							|  |  |  | 		0.0, 0.0, var); | 
					
						
							|  |  |  | static Matrix Q = Matrix_(3, 3, | 
					
						
							|  |  |  | 		prc, 0.0, 0.0, | 
					
						
							|  |  |  | 		0.0, prc, 0.0, | 
					
						
							|  |  |  | 		0.0, 0.0, prc); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | static double inf = std::numeric_limits<double>::infinity(); | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 08:37:34 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, constructors) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Vector whitened = Vector_(3,5.0,10.0,15.0); | 
					
						
							|  |  |  | 	Vector unwhitened = Vector_(3,10.0,20.0,30.0); | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 08:37:34 +08:00
										 |  |  | 	// Construct noise models
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	vector<Gaussian::shared_ptr> m; | 
					
						
							|  |  |  | 	m.push_back(Gaussian::SqrtInformation(R)); | 
					
						
							|  |  |  | 	m.push_back(Gaussian::Covariance(Sigma)); | 
					
						
							|  |  |  | 	m.push_back(Gaussian::Information(Q)); | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 	m.push_back(Diagonal::Sigmas(Vector_(3, sigma, sigma, sigma))); | 
					
						
							|  |  |  | 	m.push_back(Diagonal::Variances(Vector_(3, var, var, var))); | 
					
						
							|  |  |  | 	m.push_back(Diagonal::Precisions(Vector_(3, prc, prc, prc))); | 
					
						
							|  |  |  | 	m.push_back(Isotropic::Sigma(3, sigma)); | 
					
						
							|  |  |  | 	m.push_back(Isotropic::Variance(3, var)); | 
					
						
							|  |  |  | 	m.push_back(Isotropic::Precision(3, prc)); | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 08:37:34 +08:00
										 |  |  | 	// test whiten
 | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 	int i=0; | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	BOOST_FOREACH(Gaussian::shared_ptr mi, m) | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 		CHECK(assert_equal(whitened,mi->whiten(unwhitened))); | 
					
						
							| 
									
										
										
										
											2010-01-17 08:37:34 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// test unwhiten
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	BOOST_FOREACH(Gaussian::shared_ptr mi, m) | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 		CHECK(assert_equal(unwhitened,mi->unwhiten(whitened))); | 
					
						
							| 
									
										
										
										
											2010-01-17 09:28:15 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	// test Mahalanobis distance
 | 
					
						
							|  |  |  | 	double distance = 5*5+10*10+15*15; | 
					
						
							|  |  |  | 	BOOST_FOREACH(Gaussian::shared_ptr mi, m) | 
					
						
							|  |  |  | 		DOUBLES_EQUAL(distance,mi->Mahalanobis(unwhitened),1e-9); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 11:29:23 +08:00
										 |  |  | 	// test R matrix
 | 
					
						
							|  |  |  | 	Matrix expectedR(Matrix_(3, 3, | 
					
						
							|  |  |  | 			s_1, 0.0, 0.0, | 
					
						
							|  |  |  | 			0.0, s_1, 0.0, | 
					
						
							|  |  |  | 			0.0, 0.0, s_1)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	BOOST_FOREACH(Gaussian::shared_ptr mi, m) | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 		CHECK(assert_equal(expectedR,mi->R())); | 
					
						
							| 
									
										
										
										
											2010-01-17 11:29:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// test Whiten operator
 | 
					
						
							| 
									
										
										
										
											2010-01-17 09:28:15 +08:00
										 |  |  | 	Matrix H(Matrix_(3, 4, | 
					
						
							| 
									
										
										
										
											2010-01-17 11:29:23 +08:00
										 |  |  | 			0.0, 0.0, 1.0, 1.0, | 
					
						
							| 
									
										
										
										
											2010-01-17 09:28:15 +08:00
										 |  |  | 			0.0, 1.0, 0.0, 1.0, | 
					
						
							| 
									
										
										
										
											2010-01-17 11:29:23 +08:00
										 |  |  | 			1.0, 0.0, 0.0, 1.0)); | 
					
						
							| 
									
										
										
										
											2010-01-17 09:28:15 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Matrix expected(Matrix_(3, 4, | 
					
						
							| 
									
										
										
										
											2010-01-17 11:29:23 +08:00
										 |  |  | 			0.0, 0.0, s_1, s_1, | 
					
						
							|  |  |  | 			0.0, s_1, 0.0, s_1, | 
					
						
							|  |  |  | 			s_1, 0.0, 0.0, s_1)); | 
					
						
							| 
									
										
										
										
											2010-01-17 09:28:15 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	BOOST_FOREACH(Gaussian::shared_ptr mi, m) | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 		CHECK(assert_equal(expected,mi->Whiten(H))); | 
					
						
							| 
									
										
										
										
											2010-01-17 23:10:10 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// can only test inplace version once :-)
 | 
					
						
							| 
									
										
										
										
											2010-01-18 01:47:23 +08:00
										 |  |  | 	m[0]->WhitenInPlace(H); | 
					
						
							| 
									
										
										
										
											2010-01-17 23:10:10 +08:00
										 |  |  | 	CHECK(assert_equal(expected,H)); | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, Unit) { | 
					
						
							|  |  |  | 	Vector v = Vector_(3,5.0,10.0,15.0); | 
					
						
							|  |  |  | 	Gaussian::shared_ptr u(Unit::Create(3)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(v,u->whiten(v))); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, equals) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Gaussian::shared_ptr g = Gaussian::SqrtInformation(R); | 
					
						
							|  |  |  | 	Diagonal::shared_ptr d = Diagonal::Sigmas(Vector_(3, sigma, sigma, sigma)); | 
					
						
							|  |  |  | 	Isotropic::shared_ptr i = Isotropic::Sigma(3, sigma); | 
					
						
							|  |  |  | 	CHECK(assert_equal(*g,*g)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, ConstrainedMixed ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Vector feasible = Vector_(3, 1.0, 0.0, 1.0), | 
					
						
							|  |  |  | 			infeasible = Vector_(3, 1.0, 1.0, 1.0); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 	Constrained::shared_ptr d = Constrained::MixedSigmas(Vector_(3, sigma, 0.0, sigma)); | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	CHECK(assert_equal(Vector_(3, 0.5, inf, 0.5),d->whiten(infeasible))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3, 0.5, 0.0, 0.5),d->whiten(feasible))); | 
					
						
							|  |  |  | 	DOUBLES_EQUAL(inf,d->Mahalanobis(infeasible),1e-9); | 
					
						
							|  |  |  | 	DOUBLES_EQUAL(0.5,d->Mahalanobis(feasible),1e-9); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, ConstrainedAll ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Vector feasible = Vector_(3, 0.0, 0.0, 0.0), | 
					
						
							|  |  |  | 			infeasible = Vector_(3, 1.0, 1.0, 1.0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Constrained::shared_ptr i = Constrained::All(3); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3, inf, inf, inf),i->whiten(infeasible))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(Vector_(3, 0.0, 0.0, 0.0),i->whiten(feasible))); | 
					
						
							|  |  |  | 	DOUBLES_EQUAL(inf,i->Mahalanobis(infeasible),1e-9); | 
					
						
							|  |  |  | 	DOUBLES_EQUAL(0.0,i->Mahalanobis(feasible),1e-9); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NoiseModel, QR ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	// create a matrix to eliminate
 | 
					
						
							|  |  |  | 	Matrix Ab1 = Matrix_(4, 6+1, | 
					
						
							|  |  |  | 		   -1.,  0.,  1.,  0.,  0.,  0., -0.2, | 
					
						
							|  |  |  | 			0., -1.,  0.,  1.,  0.,  0.,  0.3, | 
					
						
							|  |  |  | 			1.,  0.,  0.,  0., -1.,  0.,  0.2, | 
					
						
							|  |  |  | 			0.,  1.,  0.,  0.,  0., -1., -0.1); | 
					
						
							|  |  |  | 	Matrix Ab2 = Ab1; // otherwise overwritten !
 | 
					
						
							|  |  |  | 	Vector sigmas = Vector_(4, 0.2, 0.2, 0.1, 0.1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Expected result
 | 
					
						
							|  |  |  | 	Vector expectedSigmas = Vector_(4, 0.0894427, 0.0894427, 0.223607, 0.223607); | 
					
						
							|  |  |  | 	SharedDiagonal expectedModel = noiseModel::Diagonal::Sigmas(expectedSigmas); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Call Gaussian version
 | 
					
						
							|  |  |  | 	SharedDiagonal diagonal = noiseModel::Diagonal::Sigmas(sigmas); | 
					
						
							|  |  |  | 	SharedDiagonal actual1 = diagonal->QR(Ab1); | 
					
						
							|  |  |  | 	SharedDiagonal expected = noiseModel::Unit::Create(4); | 
					
						
							|  |  |  | 	CHECK(assert_equal(*expected,*actual1)); | 
					
						
							|  |  |  | 	Matrix expectedRd1 = Matrix_(4, 6+1, | 
					
						
							|  |  |  | 			11.1803,   0.0,   -2.23607, 0.0,    -8.94427, 0.0,     2.23607, | 
					
						
							|  |  |  | 			0.0,   11.1803,    0.0,    -2.23607, 0.0,    -8.94427,-1.56525, | 
					
						
							|  |  |  | 			0.0,       0.0,    4.47214, 0.0,    -4.47214, 0.0,     0.0, | 
					
						
							|  |  |  | 			0.0,       0.0,   0.0,     4.47214, 0.0,    -4.47214, 0.894427); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expectedRd1,Ab1,1e-4)); // Ab was modified in place !!!
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Call Constrained version
 | 
					
						
							|  |  |  | 	SharedDiagonal constrained = noiseModel::Constrained::MixedSigmas(sigmas); | 
					
						
							|  |  |  | 	SharedDiagonal actual2 = constrained->QR(Ab2); | 
					
						
							|  |  |  | 	SharedDiagonal expectedModel2 = noiseModel::Diagonal::Sigmas(expectedSigmas); | 
					
						
							|  |  |  | 	CHECK(assert_equal(*expectedModel2,*actual2)); | 
					
						
							|  |  |  | 	Matrix expectedRd2 = Matrix_(4, 6+1, | 
					
						
							|  |  |  | 			1.,  0., -0.2,  0., -0.8, 0.,  0.2, | 
					
						
							|  |  |  | 			0.,  1.,  0.,-0.2,   0., -0.8,-0.14, | 
					
						
							|  |  |  | 			0.,  0.,  1.,   0., -1.,  0.,  0.0, | 
					
						
							|  |  |  | 			0.,  0.,  0.,   1.,  0., -1.,  0.2); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expectedRd2,Ab2,1e-6)); // Ab was modified in place !!!
 | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-20 03:06:02 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | TEST(NoiseModel, QRNan ) | 
					
						
							| 
									
										
										
										
											2010-01-20 03:06:02 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 	SharedDiagonal constrained = noiseModel::Constrained::All(2); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 	Matrix Ab = Matrix_(2, 5, 1., 2., 1., 2., 3., 2., 1., 2., 4., 4.); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 	SharedDiagonal expected = noiseModel::Constrained::All(2); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 	Matrix expectedAb = Matrix_(2, 5, 1., 2., 1., 2., 3., 0., 1., 0., 0., 2.0/3); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 	SharedDiagonal actual = constrained->QR(Ab); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 	CHECK(assert_equal(*expected,*actual)); | 
					
						
							|  |  |  | 	CHECK(assert_equal(expectedAb,Ab)); | 
					
						
							| 
									
										
										
										
											2010-01-20 03:06:02 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-20 08:26:49 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, SmartCovariance ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	bool smart = true; | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 	SharedGaussian expected = Unit::Create(3); | 
					
						
							|  |  |  | 	SharedGaussian actual = Gaussian::Covariance(eye(3), smart); | 
					
						
							| 
									
										
										
										
											2010-01-20 08:26:49 +08:00
										 |  |  | 	CHECK(assert_equal(*expected,*actual)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NoiseModel, ScalarOrVector ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-01-20 09:05:18 +08:00
										 |  |  | 	bool smart = true; | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 	SharedGaussian expected = Unit::Create(3); | 
					
						
							|  |  |  | 	SharedGaussian actual = Gaussian::Covariance(eye(3), smart); | 
					
						
							| 
									
										
										
										
											2010-01-20 08:26:49 +08:00
										 |  |  | 	CHECK(assert_equal(*expected,*actual)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							| 
									
										
										
										
											2010-01-17 08:37:34 +08:00
										 |  |  | 	TestResult tr; | 
					
						
							|  |  |  | 	return TestRegistry::runAllTests(tr); | 
					
						
							| 
									
										
										
										
											2010-01-17 02:39:39 +08:00
										 |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |