| 
									
										
										
										
											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
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2012-03-15 10:10:37 +08:00
										 |  |  |  *  @file   testGaussianFactorGraphB.cpp | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  *  @brief  Unit tests for Linear Factor Graph | 
					
						
							|  |  |  |  *  @author Christian Potthast | 
					
						
							|  |  |  |  **/ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 04:15:44 +08:00
										 |  |  | #include <tests/smallExample.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:33 +08:00
										 |  |  | #include <gtsam/linear/GaussianBayesNet.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | #include <gtsam/linear/GaussianBayesTree.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:33 +08:00
										 |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:05:38 +08:00
										 |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Matrix.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-06 13:43:03 +08:00
										 |  |  | #include <boost/foreach.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | #include <boost/tuple/tuple.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-10-31 23:24:22 +08:00
										 |  |  | #include <boost/assign/std/list.hpp> // for operator +=
 | 
					
						
							| 
									
										
										
										
											2010-05-24 16:57:22 +08:00
										 |  |  | #include <boost/assign/std/set.hpp> // for operator +=
 | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  | #include <boost/assign/std/vector.hpp> // for operator +=
 | 
					
						
							| 
									
										
										
										
											2009-10-31 23:24:22 +08:00
										 |  |  | using namespace boost::assign; | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | #include <boost/range/adaptor/map.hpp>
 | 
					
						
							|  |  |  | namespace br { using namespace boost::range; using namespace boost::adaptors; } | 
					
						
							| 
									
										
										
										
											2009-10-31 23:24:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:05:38 +08:00
										 |  |  | #include <string.h>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2010-07-08 05:41:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:05:38 +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-01-27 12:39:35 +08:00
										 |  |  | double tol=1e-5; | 
					
						
							| 
									
										
										
										
											2009-10-25 07:14:14 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 |  |  | using symbol_shorthand::X; | 
					
						
							|  |  |  | using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2012-02-21 08:53:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, equals ) { | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(); | 
					
						
							|  |  |  |   GaussianFactorGraph fg2 = createGaussianFactorGraph(); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(fg.equals(fg2)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, error ) { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(); | 
					
						
							|  |  |  |   VectorValues cfg = createZeroDelta(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-09-04 02:00:26 +08:00
										 |  |  |   // note the error is the same as in testNonlinearFactorGraph as a
 | 
					
						
							|  |  |  |   // zero delta config in the linear graph is equivalent to noisy in
 | 
					
						
							|  |  |  |   // non-linear, which is really linear under the hood
 | 
					
						
							|  |  |  |   double actual = fg.error(cfg); | 
					
						
							|  |  |  |   DOUBLES_EQUAL( 5.625, actual, 1e-9 ); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateOne_x1 ) | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianConditional::shared_ptr conditional; | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   pair<GaussianBayesNet::shared_ptr, GaussianFactorGraph::shared_ptr> result = | 
					
						
							|  |  |  |     fg.eliminatePartialSequential(Ordering(list_of(X(1)))); | 
					
						
							|  |  |  |   conditional = result.first->front(); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create expected Conditional Gaussian
 | 
					
						
							|  |  |  |   Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d = Vector2(-0.133333, -0.0222222); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianConditional expected(X(1),15*d,R11,L(1),S12,X(2),S13); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 05:33:10 +08:00
										 |  |  |   EXPECT(assert_equal(expected,*conditional,tol)); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | #if 0
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateOne_x2 ) | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; ordering += X(2),L(1),X(1); | 
					
						
							|  |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ordering); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr actual = fg.eliminateOne(0, EliminateQR).first; | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create expected Conditional Gaussian
 | 
					
						
							|  |  |  |   double sig = 0.0894427; | 
					
						
							|  |  |  |   Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d = Vector2(0.2, -0.14)/sig, sigma = ones(2); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianConditional expected(ordering[X(2)],d,R11,ordering[L(1)],S12,ordering[X(1)],S13,sigma); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected,*actual,tol)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateOne_l1 ) | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; ordering += L(1),X(1),X(2); | 
					
						
							|  |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ordering); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr actual = fg.eliminateOne(0, EliminateQR).first; | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create expected Conditional Gaussian
 | 
					
						
							| 
									
										
										
										
											2012-05-24 02:51:49 +08:00
										 |  |  |   double sig = sqrt(2.0)/10.; | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  |   Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d = Vector2(-0.1, 0.25)/sig, sigma = ones(2); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianConditional expected(ordering[L(1)],d,R11,ordering[X(1)],S12,ordering[X(2)],S13,sigma); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected,*actual,tol)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateOne_x1_fast ) | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; ordering += X(1),L(1),X(2); | 
					
						
							|  |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ordering); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr conditional; | 
					
						
							|  |  |  |   GaussianFactorGraph remaining; | 
					
						
							|  |  |  |   boost::tie(conditional,remaining) = fg.eliminateOne(ordering[X(1)], EliminateQR); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create expected Conditional Gaussian
 | 
					
						
							|  |  |  |   Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d = Vector2(-0.133333, -0.0222222), sigma = ones(2); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianConditional expected(ordering[X(1)],15*d,R11,ordering[L(1)],S12,ordering[X(2)],S13,sigma); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create expected remaining new factor
 | 
					
						
							| 
									
										
										
										
											2013-12-17 05:33:12 +08:00
										 |  |  |   JacobianFactor expectedFactor(1, (Matrix(4,2) << | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  |              4.714045207910318,                   0., | 
					
						
							|  |  |  |                              0.,   4.714045207910318, | 
					
						
							|  |  |  |                              0.,                   0., | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |                              0.,                   0.).finished(), | 
					
						
							| 
									
										
										
										
											2013-12-17 05:33:12 +08:00
										 |  |  |      2, (Matrix(4,2) << | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  |            -2.357022603955159,                   0., | 
					
						
							|  |  |  |                             0.,  -2.357022603955159, | 
					
						
							|  |  |  |             7.071067811865475,                   0., | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |                             0.,   7.071067811865475).finished(), | 
					
						
							|  |  |  |      (Vector(4) << -0.707106781186547, 0.942809041582063, 0.707106781186547, -1.414213562373094).finished(), noiseModel::Unit::Create(4)); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected,*conditional,tol)); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   EXPECT(assert_equal((const GaussianFactor&)expectedFactor,*remaining.back(),tol)); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateOne_x2_fast ) | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; ordering += X(1),L(1),X(2); | 
					
						
							|  |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ordering); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr actual = fg.eliminateOne(ordering[X(2)], EliminateQR).first; | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create expected Conditional Gaussian
 | 
					
						
							|  |  |  |   double sig = 0.0894427; | 
					
						
							|  |  |  |   Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d = Vector2(0.2, -0.14)/sig, sigma = ones(2); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianConditional expected(ordering[X(2)],d,R11,ordering[X(1)],S13,ordering[L(1)],S12,sigma); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected,*actual,tol)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateOne_l1_fast ) | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; ordering += X(1),L(1),X(2); | 
					
						
							|  |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ordering); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr actual = fg.eliminateOne(ordering[L(1)], EliminateQR).first; | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create expected Conditional Gaussian
 | 
					
						
							| 
									
										
										
										
											2012-05-24 02:51:49 +08:00
										 |  |  |   double sig = sqrt(2.0)/10.; | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  |   Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d = Vector2(-0.1, 0.25)/sig, sigma = ones(2); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianConditional expected(ordering[L(1)],d,R11,ordering[X(1)],S12,ordering[X(2)],S13,sigma); | 
					
						
							| 
									
										
										
										
											2012-03-04 04:23:03 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected,*actual,tol)); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, eliminateAll ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create expected Chordal bayes Net
 | 
					
						
							|  |  |  |   Matrix I = eye(2); | 
					
						
							| 
									
										
										
										
											2009-11-12 14:09:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; | 
					
						
							| 
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 |  |  |   ordering += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d1 = Vector2(-0.1,-0.1); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet expected = simpleGaussian(ordering[X(1)],d1,0.1); | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   double sig1 = 0.149071; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d2 = Vector2(0.0, 0.2)/sig1, sigma2 = ones(2); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   push_front(expected,ordering[L(1)],d2, I/sig1,ordering[X(1)], (-1)*I/sig1,sigma2); | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   double sig2 = 0.0894427; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector d3 = Vector2(0.2, -0.14)/sig2, sigma3 = ones(2); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   push_front(expected,ordering[X(2)],d3, I/sig2,ordering[L(1)], (-0.2)*I/sig2, ordering[X(1)], (-0.8)*I/sig2, sigma3); | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // Check one ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg1 = createGaussianFactorGraph(ordering); | 
					
						
							|  |  |  |   GaussianBayesNet actual = *GaussianSequentialSolver(fg1).eliminate(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual,tol)); | 
					
						
							| 
									
										
										
										
											2010-10-15 23:53:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet actualQR = *GaussianSequentialSolver(fg1, true).eliminate(); | 
					
						
							| 
									
										
										
										
											2011-06-14 04:01:58 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actualQR,tol)); | 
					
						
							| 
									
										
										
										
											2010-02-01 01:49:33 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, copying ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   // Create a graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ordering; ordering += X(2),L(1),X(1); | 
					
						
							|  |  |  |   GaussianFactorGraph actual = createGaussianFactorGraph(ordering); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Copy the graph !
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph copy = actual; | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // now eliminate the copy
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet actual1 = *GaussianSequentialSolver(copy).eliminate(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create the same graph, but not by copying
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph expected = createGaussianFactorGraph(ordering); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // and check that original is still the same graph
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; | 
					
						
							| 
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 |  |  |   ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // render with a given ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet CBN = *GaussianSequentialSolver(fg).eliminate(); | 
					
						
							| 
									
										
										
										
											2009-11-05 12:56:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  |   // True GaussianFactorGraph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg2(CBN); | 
					
						
							|  |  |  |   GaussianBayesNet CBN2 = *GaussianSequentialSolver(fg2).eliminate(); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(CBN,CBN2)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, getOrdering) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering original; original += L(1),X(1),X(2); | 
					
						
							|  |  |  |   FactorGraph<IndexFactor> symbolic(createGaussianFactorGraph(original)); | 
					
						
							|  |  |  |   Permutation perm(*inference::PermutationCOLAMD(VariableIndex(symbolic))); | 
					
						
							|  |  |  |   Ordering actual = original; actual.permuteInPlace(perm); | 
					
						
							|  |  |  |   Ordering expected; expected += L(1),X(2),X(1); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, optimize_Cholesky ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // create an ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // create a graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // optimize the graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues actual = *GaussianSequentialSolver(fg, false).optimize(); | 
					
						
							| 
									
										
										
										
											2011-06-14 04:01:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // verify
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues expected = createCorrectDelta(ord); | 
					
						
							| 
									
										
										
										
											2011-06-14 04:01:58 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, optimize_QR ) | 
					
						
							| 
									
										
										
										
											2011-06-14 04:01:58 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   // create an ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2011-06-14 04:01:58 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create a graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2011-06-14 04:01:58 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // optimize the graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues actual = *GaussianSequentialSolver(fg, true).optimize(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // verify
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues expected = createCorrectDelta(ord); | 
					
						
							| 
									
										
										
										
											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
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, combine) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // create an ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create a test graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg1 = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create another factor graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg2 = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // get sizes
 | 
					
						
							|  |  |  |   size_t size1 = fg1.size(); | 
					
						
							|  |  |  |   size_t size2 = fg2.size(); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // combine them
 | 
					
						
							|  |  |  |   fg1.combine(fg2); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(size1+size2 == fg1.size()); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, combine2) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // create an ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create a test graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg1 = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create another factor graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg2 = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // get sizes
 | 
					
						
							|  |  |  |   size_t size1 = fg1.size(); | 
					
						
							|  |  |  |   size_t size2 = fg2.size(); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // combine them
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg3 = GaussianFactorGraph::combine2(fg1, fg2); | 
					
						
							| 
									
										
										
										
											2009-11-05 04:59:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(size1+size2 == fg3.size()); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2009-10-22 13:02:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // print a vector of ints if needed for debugging
 | 
					
						
							|  |  |  | void print(vector<int> v) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   for (size_t k = 0; k < v.size(); k++) | 
					
						
							|  |  |  |     cout << v[k] << " "; | 
					
						
							|  |  |  |   cout << endl; | 
					
						
							| 
									
										
										
										
											2009-10-22 13:02:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-10-27 21:34:36 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST(GaussianFactorGraph, createSmoother) | 
					
						
							| 
									
										
										
										
											2009-10-27 21:34:36 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg1 = createSmoother(2).first; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   LONGS_EQUAL(3,fg1.size()); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg2 = createSmoother(3).first; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   LONGS_EQUAL(5,fg2.size()); | 
					
						
							| 
									
										
										
										
											2009-10-27 21:34:36 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-11 04:19:15 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | double error(const VectorValues& x) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // create an ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(ord); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   return fg.error(x); | 
					
						
							| 
									
										
										
										
											2009-12-12 12:44:34 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, multiplication ) | 
					
						
							| 
									
										
										
										
											2009-12-26 23:06:54 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   // create an ordering
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(2),L(1),X(1); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph A = createGaussianFactorGraph(ord); | 
					
						
							|  |  |  |   VectorValues x = createCorrectDelta(ord); | 
					
						
							| 
									
										
										
										
											2009-12-27 06:48:41 +08:00
										 |  |  |   Errors actual = A * x; | 
					
						
							|  |  |  |   Errors expected; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   expected += Vector2(-1.0,-1.0); | 
					
						
							|  |  |  |   expected += Vector2(2.0,-1.0); | 
					
						
							|  |  |  |   expected += Vector2(0.0, 1.0); | 
					
						
							|  |  |  |   expected += Vector2(-1.0, 1.5); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2009-12-26 23:06:54 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-10 05:34:20 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-05 22:14:49 +08:00
										 |  |  | // Extra test on elimination prompted by Michael's email to Frank 1/4/2010
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, elimination ) | 
					
						
							| 
									
										
										
										
											2010-01-05 22:14:49 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; | 
					
						
							| 
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 |  |  |   ord += X(1), X(2); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // Create Gaussian Factor Graph
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Matrix Ap = eye(1), An = eye(1) * -1; | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   Vector b = (Vector(1) << 0.0).finished(); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  |   SharedDiagonal sigma = noiseModel::Isotropic::Sigma(1,2.0); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   fg += ord[X(1)], An, ord[X(2)], Ap, b, sigma; | 
					
						
							|  |  |  |   fg += ord[X(1)], Ap, b, sigma; | 
					
						
							|  |  |  |   fg += ord[X(2)], Ap, b, sigma; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Eliminate
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet bayesNet = *GaussianSequentialSolver(fg).eliminate(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Check sigma
 | 
					
						
							|  |  |  |   EXPECT_DOUBLES_EQUAL(1.0,bayesNet[ord[X(2)]]->get_sigmas()(0),1e-5); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Check matrix
 | 
					
						
							|  |  |  |   Matrix R;Vector d; | 
					
						
							|  |  |  |   boost::tie(R,d) = matrix(bayesNet); | 
					
						
							| 
									
										
										
										
											2013-12-17 05:33:12 +08:00
										 |  |  |   Matrix expected = (Matrix(2, 2) << | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       0.707107,  -0.353553, | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |       0.0,   0.612372).finished(); | 
					
						
							| 
									
										
										
										
											2013-12-17 05:33:12 +08:00
										 |  |  |   Matrix expected2 = (Matrix(2, 2) << | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       0.707107,  -0.353553, | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |       0.0,   -0.612372).finished(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(equal_with_abs_tol(expected, R, 1e-6) || equal_with_abs_tol(expected2, R, 1e-6)); | 
					
						
							| 
									
										
										
										
											2010-01-05 22:14:49 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 00:16:32 +08:00
										 |  |  | // Tests ported from ConstrainedGaussianFactorGraph
 | 
					
						
							| 
									
										
										
										
											2009-11-10 12:36:07 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, constrained_simple ) | 
					
						
							| 
									
										
										
										
											2009-11-10 12:36:07 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // get a graph with a constraint in it
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createSimpleConstraintGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(hasConstraints(fg)); | 
					
						
							| 
									
										
										
										
											2011-11-11 03:44:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-10 12:36:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // eliminate and solve
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues actual = *GaussianSequentialSolver(fg).optimize(); | 
					
						
							| 
									
										
										
										
											2009-11-10 12:36:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // verify
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues expected = createSimpleConstraintValues(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2009-11-10 12:36:07 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, constrained_single ) | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // get a graph with a constraint in it
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createSingleConstraintGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(hasConstraints(fg)); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // eliminate and solve
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues actual = *GaussianSequentialSolver(fg).optimize(); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // verify
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues expected = createSingleConstraintValues(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, constrained_multi1 ) | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // get a graph with a constraint in it
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg = createMultiConstraintGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(hasConstraints(fg)); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // eliminate and solve
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues actual = *GaussianSequentialSolver(fg).optimize(); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // verify
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   VectorValues expected = createMultiConstraintValues(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2009-11-11 22:42:09 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2009-11-10 05:34:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 07:59:46 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-09-04 02:00:26 +08:00
										 |  |  | static SharedDiagonal model = noiseModel::Isotropic::Sigma(2,1); | 
					
						
							| 
									
										
										
										
											2010-01-09 03:07:46 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-13 09:29:19 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST(GaussianFactorGraph, replace) | 
					
						
							| 
									
										
										
										
											2010-02-13 09:29:19 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering ord; ord += X(1),X(2),X(3),X(4),X(5),X(6); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   SharedDiagonal noise(noiseModel::Isotropic::Sigma(3, 1.0)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph::sharedFactor f1(new JacobianFactor( | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       ord[X(1)], eye(3,3), ord[X(2)], eye(3,3), zero(3), noise)); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph::sharedFactor f2(new JacobianFactor( | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       ord[X(2)], eye(3,3), ord[X(3)], eye(3,3), zero(3), noise)); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph::sharedFactor f3(new JacobianFactor( | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       ord[X(3)], eye(3,3), ord[X(4)], eye(3,3), zero(3), noise)); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph::sharedFactor f4(new JacobianFactor( | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       ord[X(5)], eye(3,3), ord[X(6)], eye(3,3), zero(3), noise)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph actual; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   actual.push_back(f1); | 
					
						
							|  |  |  |   actual.push_back(f2); | 
					
						
							|  |  |  |   actual.push_back(f3); | 
					
						
							|  |  |  |   actual.replace(0, f4); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph expected; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   expected.push_back(f4); | 
					
						
							|  |  |  |   expected.push_back(f2); | 
					
						
							|  |  |  |   expected.push_back(f3); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2010-02-13 09:29:19 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-09-23 10:48:34 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST(GaussianFactorGraph, createSmoother2) | 
					
						
							| 
									
										
										
										
											2011-09-23 10:48:34 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   using namespace example; | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianFactorGraph fg2; | 
					
						
							|  |  |  |   Ordering ordering; | 
					
						
							| 
									
										
										
										
											2011-09-23 10:48:34 +08:00
										 |  |  |   boost::tie(fg2,ordering) = createSmoother(3); | 
					
						
							|  |  |  |   LONGS_EQUAL(5,fg2.size()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // eliminate
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 |  |  |   vector<Index> x3var; x3var.push_back(ordering[X(3)]); | 
					
						
							|  |  |  |   vector<Index> x1var; x1var.push_back(ordering[X(1)]); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet p_x3 = *GaussianSequentialSolver( | 
					
						
							| 
									
										
										
										
											2011-09-23 10:48:34 +08:00
										 |  |  |       *GaussianSequentialSolver(fg2).jointFactorGraph(x3var)).eliminate(); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   GaussianBayesNet p_x1 = *GaussianSequentialSolver( | 
					
						
							| 
									
										
										
										
											2011-09-23 10:48:34 +08:00
										 |  |  |       *GaussianSequentialSolver(fg2).jointFactorGraph(x1var)).eliminate(); | 
					
						
							|  |  |  |   CHECK(assert_equal(*p_x1.back(),*p_x3.front())); // should be the same because of symmetry
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | #endif
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-11-11 03:44:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST(GaussianFactorGraph, hasConstraints) | 
					
						
							| 
									
										
										
										
											2011-11-11 03:44:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   FactorGraph<GaussianFactor> fgc1 = createMultiConstraintGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(hasConstraints(fgc1)); | 
					
						
							| 
									
										
										
										
											2011-11-11 03:44:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   FactorGraph<GaussianFactor> fgc2 = createSimpleConstraintGraph() ; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(hasConstraints(fgc2)); | 
					
						
							| 
									
										
										
										
											2011-11-11 03:44:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianFactorGraph fg = createGaussianFactorGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   EXPECT(!hasConstraints(fg)); | 
					
						
							| 
									
										
										
										
											2011-11-11 03:44:03 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  | #include <gtsam/slam/ProjectionFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/RangeFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  | TEST( GaussianFactorGraph, conditional_sigma_failure) { | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  |   // This system derives from a failure case in DDF in which a Bayes Tree
 | 
					
						
							|  |  |  |   // has non-unit sigmas for conditionals in the Bayes Tree, which
 | 
					
						
							|  |  |  |   // should never happen by construction
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Reason for the failure: using Vector_() is dangerous as having a non-float gets set to zero, resulting in constraints
 | 
					
						
							|  |  |  |   gtsam::Key xC1 = 0, l32 = 1, l41 = 2; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // noisemodels at nonlinear level
 | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   gtsam::SharedNoiseModel priorModel = noiseModel::Diagonal::Sigmas((Vector(6) << 0.05, 0.05, 3.0, 0.2, 0.2, 0.2).finished()); | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  |   gtsam::SharedNoiseModel measModel = noiseModel::Unit::Create(2); | 
					
						
							|  |  |  |   gtsam::SharedNoiseModel elevationModel = noiseModel::Isotropic::Sigma(1, 3.0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   double fov = 60; // degrees
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   int imgW = 640; // pixels
 | 
					
						
							|  |  |  |   int imgH = 480; // pixels
 | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  |   gtsam::Cal3_S2::shared_ptr K(new gtsam::Cal3_S2(fov, imgW, imgH)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   typedef GenericProjectionFactor<Pose3, Point3> ProjectionFactor; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   double relElevation = 6; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values initValues; | 
					
						
							|  |  |  |   initValues.insert(xC1, | 
					
						
							|  |  |  |       Pose3(Rot3( | 
					
						
							|  |  |  |           -1.,           0.0,  1.2246468e-16, | 
					
						
							|  |  |  |           0.0,             1.,           0.0, | 
					
						
							|  |  |  |           -1.2246468e-16,           0.0,            -1.), | 
					
						
							|  |  |  |           Point3(0.511832102, 8.42819594, 5.76841725))); | 
					
						
							|  |  |  |   initValues.insert(l32,  Point3(0.364081507, 6.89766221, -0.231582751) ); | 
					
						
							|  |  |  |   initValues.insert(l41,  Point3(1.61051523, 6.7373052, -0.231582751)   ); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   NonlinearFactorGraph factors; | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   factors += PriorFactor<Pose3>(xC1, | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  |       Pose3(Rot3( | 
					
						
							|  |  |  |           -1.,           0.0,  1.2246468e-16, | 
					
						
							|  |  |  |           0.0,             1.,           0.0, | 
					
						
							|  |  |  |           -1.2246468e-16,           0.0,            -1), | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |           Point3(0.511832102, 8.42819594, 5.76841725)), priorModel); | 
					
						
							|  |  |  |   factors += ProjectionFactor(Point2(333.648615, 98.61535), measModel, xC1, l32, K); | 
					
						
							|  |  |  |   factors += ProjectionFactor(Point2(218.508, 83.8022039), measModel, xC1, l41, K); | 
					
						
							|  |  |  |   factors += RangeFactor<Pose3,Point3>(xC1, l32, relElevation, elevationModel); | 
					
						
							|  |  |  |   factors += RangeFactor<Pose3,Point3>(xC1, l41, relElevation, elevationModel); | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Check that sigmas are correct (i.e., unit)
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianFactorGraph lfg = *factors.linearize(initValues); | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianBayesTree actBT = *lfg.eliminateMultifrontal(); | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Check that all sigmas in an unconstrained bayes tree are set to one
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   BOOST_FOREACH(const GaussianBayesTree::sharedClique& clique, actBT.nodes() | br::map_values) { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |     GaussianConditional::shared_ptr conditional = clique->conditional(); | 
					
						
							| 
									
										
										
										
											2013-10-26 02:27:43 +08:00
										 |  |  |     //size_t dim = conditional->rows();
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |     //EXPECT(assert_equal(gtsam::ones(dim), conditional->get_model()->sigmas(), tol));
 | 
					
						
							|  |  |  |     EXPECT(!conditional->get_model()); | 
					
						
							| 
									
										
										
										
											2012-10-05 04:23:45 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr);} | 
					
						
							|  |  |  | /* ************************************************************************* */ |