| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  |  * 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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @file    testNonlinearFactorGraph.cpp | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |  * @brief   Unit tests for Non-Linear Factor NonlinearFactorGraph | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  |  * @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-08-06 06:31:33 +08:00
										 |  |  | #include <gtsam/inference/FactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2013-09-17 11:13:32 +08:00
										 |  |  | #include <gtsam/symbolic/SymbolicFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.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
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, equals ) | 
					
						
							| 
									
										
										
										
											2009-09-09 12:43:04 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   NonlinearFactorGraph fg2 = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   CHECK( fg.equals(fg2) ); | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, error ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   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
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, keys ) | 
					
						
							| 
									
										
										
										
											2010-10-31 03:27:30 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2015-06-21 09:38:25 +08:00
										 |  |  |   KeySet actual = fg.keys(); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   LONGS_EQUAL(3, (long)actual.size()); | 
					
						
							| 
									
										
										
										
											2015-06-21 09:38:25 +08:00
										 |  |  |   KeySet::const_iterator it = actual.begin(); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   LONGS_EQUAL((long)L(1), (long)*(it++)); | 
					
						
							|  |  |  |   LONGS_EQUAL((long)X(1), (long)*(it++)); | 
					
						
							|  |  |  |   LONGS_EQUAL((long)X(2), (long)*(it++)); | 
					
						
							| 
									
										
										
										
											2010-10-31 03:27:30 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, GET_ORDERING) | 
					
						
							| 
									
										
										
										
											2009-12-09 23:25:50 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph nlfg = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2015-02-22 02:16:03 +08:00
										 |  |  |   Ordering actual = Ordering::Colamd(nlfg); | 
					
						
							| 
									
										
										
										
											2012-06-20 09:35:42 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Constrained ordering - put x2 at the end
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   FastMap<Key, int> constraints; | 
					
						
							|  |  |  |   constraints[X(2)] = 1; | 
					
						
							| 
									
										
										
										
											2015-02-22 02:16:03 +08:00
										 |  |  |   Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints); | 
					
						
							| 
									
										
										
										
											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
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, probPrime ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   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
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, linearize ) | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Values initial = createNoisyValues(); | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   GaussianFactorGraph linearFG = *fg.linearize(initial); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   GaussianFactorGraph expected = createGaussianFactorGraph(); | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   CHECK(assert_equal(expected,linearFG)); // Needs correct linearizations
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, clone ) | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   NonlinearFactorGraph actClone = fg.clone(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   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
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | TEST( NonlinearFactorGraph, rekey ) | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph init = createNonlinearFactorGraph(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   map<Key,Key> rekey_mapping; | 
					
						
							|  |  |  |   rekey_mapping.insert(make_pair(L(1), L(4))); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph actRekey = init.rekey(rekey_mapping); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // ensure deep clone
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   LONGS_EQUAL((long)init.size(), (long)actRekey.size()); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   for (size_t i=0; i<init.size(); ++i) | 
					
						
							|  |  |  |       EXPECT(init[i] != actRekey[i]); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   NonlinearFactorGraph expRekey; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // 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); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   expRekey += simulated2D::Measurement(z3, sigma0_2, X(1), L(4)); | 
					
						
							|  |  |  |   expRekey += simulated2D::Measurement(z4, sigma0_2, X(2), L(4)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expRekey, actRekey)); | 
					
						
							| 
									
										
										
										
											2012-05-25 00:05:01 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-09-17 11:13:32 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( NonlinearFactorGraph, symbolic ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   NonlinearFactorGraph graph = createNonlinearFactorGraph(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   SymbolicFactorGraph expected; | 
					
						
							|  |  |  |   expected.push_factor(X(1)); | 
					
						
							|  |  |  |   expected.push_factor(X(1), X(2)); | 
					
						
							|  |  |  |   expected.push_factor(X(1), L(1)); | 
					
						
							|  |  |  |   expected.push_factor(X(2), L(1)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   SymbolicFactorGraph actual = *graph.symbolic(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(NonlinearFactorGraph, UpdateCholesky) { | 
					
						
							|  |  |  |   NonlinearFactorGraph fg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  |   Values initial = createNoisyValues(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // solve conventionally
 | 
					
						
							|  |  |  |   GaussianFactorGraph linearFG = *fg.linearize(initial); | 
					
						
							|  |  |  |   auto delta = linearFG.optimizeDensely(); | 
					
						
							|  |  |  |   auto expected = initial.retract(delta); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // solve with new method
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, fg.updateCholesky(initial))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // solve with Ordering
 | 
					
						
							|  |  |  |   Ordering ordering; | 
					
						
							|  |  |  |   ordering += L(1), X(2), X(1); | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, fg.updateCholesky(initial, ordering))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // solve with new method, heavily damped
 | 
					
						
							|  |  |  |   auto dampen = [](const HessianFactor::shared_ptr& hessianFactor) { | 
					
						
							|  |  |  |     auto iterator = hessianFactor->begin(); | 
					
						
							|  |  |  |     for (; iterator != hessianFactor->end(); iterator++) { | 
					
						
							|  |  |  |       const auto index = std::distance(hessianFactor->begin(), iterator); | 
					
						
							|  |  |  |       auto block = hessianFactor->info().diagonalBlock(index); | 
					
						
							|  |  |  |       for (int j = 0; j < block.rows(); j++) { | 
					
						
							|  |  |  |         block(j, j) += 1e9; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  |   EXPECT(assert_equal(initial, fg.updateCholesky(initial, boost::none, dampen), 1e-6)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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
										 |  |  | /* ************************************************************************* */ |