| 
									
										
										
										
											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
										 |  |  | /** 
 | 
					
						
							|  |  |  |  * @file    testNonlinearFactorGraph.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for Non-Linear Factor Graph | 
					
						
							|  |  |  |  * @brief   testNonlinearFactorGraph | 
					
						
							|  |  |  |  * @author  Carlos Nieto | 
					
						
							|  |  |  |  * @author  Christian Potthast | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /*STL/C++*/ | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | #include <boost/assign/std/list.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-10-31 03:27:30 +08:00
										 |  |  | #include <boost/assign/std/set.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | using namespace boost::assign; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-20 10:11:28 +08:00
										 |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Matrix.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-10 04:15:44 +08:00
										 |  |  | #include <tests/smallExample.h>
 | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  | #include <gtsam/inference/FactorGraphOrdered.h>
 | 
					
						
							| 
									
										
										
										
											2011-12-21 07:25:43 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:05:38 +08:00
										 |  |  | #include <gtsam/nonlinear/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											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
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											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
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  | TEST( Graph, equals ) | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   Graph fg2 = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   CHECK( fg.equals(fg2) ); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  | TEST( Graph, error ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   Values c1 = createValues(); | 
					
						
							|  |  |  |   double actual1 = fg.error(c1); | 
					
						
							|  |  |  |   DOUBLES_EQUAL( 0.0, actual1, 1e-9 ); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values c2 = createNoisyValues(); | 
					
						
							|  |  |  |   double actual2 = fg.error(c2); | 
					
						
							|  |  |  |   DOUBLES_EQUAL( 5.625, actual2, 1e-9 ); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-31 03:27:30 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Graph, keys ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   FastSet<Key> actual = fg.keys(); | 
					
						
							|  |  |  |   LONGS_EQUAL(3, actual.size()); | 
					
						
							|  |  |  |   FastSet<Key>::const_iterator it = actual.begin(); | 
					
						
							|  |  |  |   LONGS_EQUAL(L(1), *(it++)); | 
					
						
							|  |  |  |   LONGS_EQUAL(X(1), *(it++)); | 
					
						
							|  |  |  |   LONGS_EQUAL(X(2), *(it++)); | 
					
						
							| 
									
										
										
										
											2010-10-31 03:27:30 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  | TEST( Graph, GET_ORDERING) | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  | //  OrderingOrdered expected; expected += "x1","l1","x2"; // For starting with x1,x2,l1
 | 
					
						
							|  |  |  |   OrderingOrdered expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2
 | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  |   Graph nlfg = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  |   SymbolicFactorGraphOrdered::shared_ptr symbolic; | 
					
						
							|  |  |  |   OrderingOrdered::shared_ptr ordering; | 
					
						
							| 
									
										
										
										
											2012-01-31 05:23:02 +08:00
										 |  |  |   boost::tie(symbolic, ordering) = nlfg.symbolic(createNoisyValues()); | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  |   OrderingOrdered actual = *nlfg.orderingCOLAMD(createNoisyValues()); | 
					
						
							| 
									
										
										
										
											2012-06-20 09:35:42 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Constrained ordering - put x2 at the end
 | 
					
						
							|  |  |  |   std::map<Key, int> constraints; | 
					
						
							|  |  |  |   constraints[X(2)] = 1; | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  |   OrderingOrdered actualConstrained = *nlfg.orderingCOLAMDConstrained(createNoisyValues(), constraints); | 
					
						
							|  |  |  |   OrderingOrdered expectedConstrained; expectedConstrained += L(1), X(1), X(2); | 
					
						
							| 
									
										
										
										
											2012-06-20 09:35:42 +08:00
										 |  |  |   EXPECT(assert_equal(expectedConstrained, actualConstrained)); | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  | TEST( Graph, probPrime ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   Values cfg = createValues(); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // evaluate the probability of the factor graph
 | 
					
						
							|  |  |  |   double actual = fg.probPrime(cfg); | 
					
						
							|  |  |  |   double expected = 1.0; | 
					
						
							|  |  |  |   DOUBLES_EQUAL(expected,actual,0); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 |  |  | TEST( Graph, linearize ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   Values initial = createNoisyValues(); | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  |   boost::shared_ptr<FactorGraphOrdered<GaussianFactorOrdered> > linearized = fg.linearize(initial, *initial.orderingArbitrary()); | 
					
						
							|  |  |  |   FactorGraphOrdered<GaussianFactorOrdered> expected = createGaussianFactorGraph(*initial.orderingArbitrary()); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   CHECK(assert_equal(expected,*linearized)); // Needs correct linearizations
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Graph, clone ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   Graph actClone = fg.clone(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(fg, actClone)); | 
					
						
							|  |  |  |   for (size_t i=0; i<fg.size(); ++i) | 
					
						
							|  |  |  |     EXPECT(fg[i] != actClone[i]); | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( Graph, rekey ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Graph init = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   map<Key,Key> rekey_mapping; | 
					
						
							|  |  |  |   rekey_mapping.insert(make_pair(L(1), L(4))); | 
					
						
							|  |  |  |   Graph actRekey = init.rekey(rekey_mapping); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // ensure deep clone
 | 
					
						
							|  |  |  |   LONGS_EQUAL(init.size(), actRekey.size()); | 
					
						
							|  |  |  |   for (size_t i=0; i<init.size(); ++i) | 
					
						
							|  |  |  |       EXPECT(init[i] != actRekey[i]); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Graph expRekey; | 
					
						
							|  |  |  |   // original measurements
 | 
					
						
							|  |  |  |   expRekey.push_back(init[0]); | 
					
						
							|  |  |  |   expRekey.push_back(init[1]); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // updated measurements
 | 
					
						
							|  |  |  |   Point2 z3(0, -1),  z4(-1.5, -1.); | 
					
						
							|  |  |  |   SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); | 
					
						
							|  |  |  |   expRekey.add(simulated2D::Measurement(z3, sigma0_2, X(1), L(4))); | 
					
						
							|  |  |  |   expRekey.add(simulated2D::Measurement(z4, sigma0_2, X(2), L(4))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expRekey, actRekey)); | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2012-06-20 09:35:42 +08:00
										 |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /* ************************************************************************* */ |