| 
									
										
										
										
											2010-10-14 12:54:38 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  |  * @file    testGaussianBayesNet.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for GaussianBayesNet | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // STL/C++
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include <sstream>
 | 
					
						
							| 
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							|  |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-09 06:50:26 +08:00
										 |  |  | #include <boost/assign/std/list.hpp> // for operator +=
 | 
					
						
							|  |  |  | using namespace boost::assign; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-08-18 21:18:26 +08:00
										 |  |  | // Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | #define GTSAM_MAGIC_KEY
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/GaussianBayesNet.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/BayesNet.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | #include <gtsam/linear/GaussianSequentialSolver.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/slam/smallExample.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-02 11:50:30 +08:00
										 |  |  | using namespace std; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  | using namespace example; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | static const Index _x_=0, _y_=1, _z_=2; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  | TEST( GaussianBayesNet, constructor ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   // small Bayes Net x <- y
 | 
					
						
							|  |  |  |   // x y d
 | 
					
						
							|  |  |  |   // 1 1 9
 | 
					
						
							|  |  |  |   //   1 5
 | 
					
						
							|  |  |  |   Matrix R11 = Matrix_(1,1,1.0), S12 = Matrix_(1,1,1.0); | 
					
						
							|  |  |  |   Matrix                         R22 = Matrix_(1,1,1.0); | 
					
						
							|  |  |  |   Vector d1(1), d2(1); | 
					
						
							|  |  |  |   d1(0) = 9; d2(0) = 5; | 
					
						
							| 
									
										
										
										
											2009-11-09 06:50:26 +08:00
										 |  |  |   Vector sigmas(1); | 
					
						
							|  |  |  |   sigmas(0) = 1.; | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |   // define nodes and specify in reverse topological sort (i.e. parents last)
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   GaussianConditional x(_x_,d1,R11,_y_,S12, sigmas), y(_y_,d2,R22, sigmas); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // check small example which uses constructor
 | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  |   GaussianBayesNet cbn = createSmallGaussianBayesNet(); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT( x.equals(*cbn[_x_]) ); | 
					
						
							|  |  |  |   EXPECT( y.equals(*cbn[_y_]) ); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  | TEST( GaussianBayesNet, matrix ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   // Create a test graph
 | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  |   GaussianBayesNet cbn = createSmallGaussianBayesNet(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix R; Vector d; | 
					
						
							| 
									
										
										
										
											2009-11-09 15:04:26 +08:00
										 |  |  |   boost::tie(R,d) = matrix(cbn); // find matrix and RHS
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix R1 = Matrix_(2,2, | 
					
						
							|  |  |  | 		      1.0, 1.0, | 
					
						
							|  |  |  | 		      0.0, 1.0 | 
					
						
							|  |  |  |     ); | 
					
						
							|  |  |  |   Vector d1 = Vector_(2, 9.0, 5.0); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(R,R1)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(d,d1)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  | TEST( GaussianBayesNet, optimize ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2009-11-01 03:53:20 +08:00
										 |  |  |   GaussianBayesNet cbn = createSmallGaussianBayesNet(); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues actual = optimize(cbn); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues expected(vector<size_t>(2,1)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   expected[_x_] = Vector_(1,4.); | 
					
						
							|  |  |  |   expected[_y_] = Vector_(1,5.); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussianBayesNet, optimize2 ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Create empty graph
 | 
					
						
							|  |  |  | 	GaussianFactorGraph fg; | 
					
						
							| 
									
										
										
										
											2010-02-23 13:28:39 +08:00
										 |  |  | 	SharedDiagonal noise = noiseModel::Unit::Create(1); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	fg.add(_y_, eye(1), 2*ones(1), noise); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	fg.add(_x_, eye(1),_y_, -eye(1), -ones(1), noise); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	fg.add(_y_, eye(1),_z_, -eye(1), -ones(1), noise); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	fg.add(_x_, -eye(1), _z_, eye(1), 2*ones(1), noise); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  |   VectorValues actual = *GaussianSequentialSolver(fg).optimize(); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues expected(vector<size_t>(3,1)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   expected[_x_] = Vector_(1,1.); | 
					
						
							|  |  |  |   expected[_y_] = Vector_(1,2.); | 
					
						
							|  |  |  |   expected[_z_] = Vector_(1,3.); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2010-02-22 14:42:58 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-31 12:39:41 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussianBayesNet, backSubstitute ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2010-02-18 22:29:40 +08:00
										 |  |  | 	// y=R*x, x=inv(R)*y
 | 
					
						
							|  |  |  | 	// 2 = 1 1  -1
 | 
					
						
							|  |  |  | 	// 3     1   3
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	// NOTE: we are supplying a new RHS here
 | 
					
						
							| 
									
										
										
										
											2010-01-31 12:39:41 +08:00
										 |  |  |   GaussianBayesNet cbn = createSmallGaussianBayesNet(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues y(vector<size_t>(2,1)), x(vector<size_t>(2,1)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   y[_x_] = Vector_(1,2.); | 
					
						
							|  |  |  |   y[_y_] = Vector_(1,3.); | 
					
						
							|  |  |  |   x[_x_] = Vector_(1,-1.); | 
					
						
							|  |  |  |   x[_y_] = Vector_(1, 3.); | 
					
						
							| 
									
										
										
										
											2010-01-31 12:39:41 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // test functional version
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues actual = backSubstitute(cbn,y); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(x,actual)); | 
					
						
							| 
									
										
										
										
											2010-01-31 12:39:41 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // test imperative version
 | 
					
						
							|  |  |  |   backSubstituteInPlace(cbn,y); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(x,y)); | 
					
						
							| 
									
										
										
										
											2010-02-18 22:29:40 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-08 11:56:49 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussianBayesNet, rhs ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	// y=R*x, x=inv(R)*y
 | 
					
						
							|  |  |  | 	// 2 = 1 1  -1
 | 
					
						
							|  |  |  | 	// 3     1   3
 | 
					
						
							|  |  |  |   GaussianBayesNet cbn = createSmallGaussianBayesNet(); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorValues expected = gtsam::optimize(cbn); | 
					
						
							|  |  |  | 	VectorValues d = rhs(cbn); | 
					
						
							|  |  |  | 	VectorValues actual = backSubstitute(cbn, d); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2010-03-08 11:56:49 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussianBayesNet, rhs_with_sigmas ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	Matrix R11 = Matrix_(1, 1, 1.0), S12 = Matrix_(1, 1, 1.0); | 
					
						
							|  |  |  | 	Matrix R22 = Matrix_(1, 1, 1.0); | 
					
						
							|  |  |  | 	Vector d1(1), d2(1); | 
					
						
							|  |  |  | 	d1(0) = 9; | 
					
						
							|  |  |  | 	d2(0) = 5; | 
					
						
							|  |  |  | 	Vector tau(1); | 
					
						
							|  |  |  | 	tau(0) = 0.25; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// define nodes and specify in reverse topological sort (i.e. parents last)
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	GaussianConditional::shared_ptr Px_y(new GaussianConditional(_x_, d1, R11, | 
					
						
							|  |  |  | 			_y_, S12, tau)), Py(new GaussianConditional(_y_, d2, R22, tau)); | 
					
						
							| 
									
										
										
										
											2010-03-08 11:56:49 +08:00
										 |  |  | 	GaussianBayesNet cbn; | 
					
						
							|  |  |  | 	cbn.push_back(Px_y); | 
					
						
							|  |  |  | 	cbn.push_back(Py); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorValues expected = gtsam::optimize(cbn); | 
					
						
							|  |  |  | 	VectorValues d = rhs(cbn); | 
					
						
							|  |  |  | 	VectorValues actual = backSubstitute(cbn, d); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2010-03-08 11:56:49 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-18 22:29:40 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussianBayesNet, backSubstituteTranspose ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	// x=R'*y, y=inv(R')*x
 | 
					
						
							|  |  |  | 	// 2 = 1    2
 | 
					
						
							|  |  |  | 	// 5   1 1  3
 | 
					
						
							|  |  |  |   GaussianBayesNet cbn = createSmallGaussianBayesNet(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues y(vector<size_t>(2,1)), x(vector<size_t>(2,1)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   x[_x_] = Vector_(1,2.); | 
					
						
							|  |  |  |   x[_y_] = Vector_(1,5.); | 
					
						
							|  |  |  |   y[_x_] = Vector_(1,2.); | 
					
						
							|  |  |  |   y[_y_] = Vector_(1,3.); | 
					
						
							| 
									
										
										
										
											2010-02-18 22:29:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // test functional version
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues actual = backSubstituteTranspose(cbn,x); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(y,actual)); | 
					
						
							| 
									
										
										
										
											2010-01-31 12:39:41 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr);} | 
					
						
							|  |  |  | /* ************************************************************************* */ |