/* ---------------------------------------------------------------------------- * 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 * -------------------------------------------------------------------------- */ /** * @file testNonlinearFactorGraph.cpp * @brief Unit tests for Non-Linear Factor NonlinearFactorGraph * @brief testNonlinearFactorGraph * @author Carlos Nieto * @author Christian Potthast */ #include #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace boost::assign; /*STL/C++*/ #include using namespace std; using namespace gtsam; using namespace example; using symbol_shorthand::X; using symbol_shorthand::L; /* ************************************************************************* */ TEST( NonlinearFactorGraph, equals ) { NonlinearFactorGraph fg = createNonlinearFactorGraph(); NonlinearFactorGraph fg2 = createNonlinearFactorGraph(); CHECK( fg.equals(fg2) ); } /* ************************************************************************* */ TEST( NonlinearFactorGraph, error ) { NonlinearFactorGraph 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 ); } /* ************************************************************************* */ TEST( NonlinearFactorGraph, keys ) { NonlinearFactorGraph fg = createNonlinearFactorGraph(); KeySet actual = fg.keys(); LONGS_EQUAL(3, (long)actual.size()); KeySet::const_iterator it = actual.begin(); LONGS_EQUAL((long)L(1), (long)*(it++)); LONGS_EQUAL((long)X(1), (long)*(it++)); LONGS_EQUAL((long)X(2), (long)*(it++)); } /* ************************************************************************* */ TEST( NonlinearFactorGraph, GET_ORDERING) { Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2 NonlinearFactorGraph nlfg = createNonlinearFactorGraph(); Ordering actual = Ordering::Colamd(nlfg); EXPECT(assert_equal(expected,actual)); // Constrained ordering - put x2 at the end Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2); FastMap constraints; constraints[X(2)] = 1; Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints); EXPECT(assert_equal(expectedConstrained, actualConstrained)); } /* ************************************************************************* */ TEST( NonlinearFactorGraph, probPrime ) { NonlinearFactorGraph fg = createNonlinearFactorGraph(); Values cfg = createValues(); // evaluate the probability of the factor graph double actual = fg.probPrime(cfg); double expected = 1.0; DOUBLES_EQUAL(expected,actual,0); } /* ************************************************************************* */ TEST( NonlinearFactorGraph, linearize ) { NonlinearFactorGraph fg = createNonlinearFactorGraph(); Values initial = createNoisyValues(); GaussianFactorGraph linearFG = *fg.linearize(initial); GaussianFactorGraph expected = createGaussianFactorGraph(); CHECK(assert_equal(expected,linearFG)); // Needs correct linearizations } /* ************************************************************************* */ TEST( NonlinearFactorGraph, clone ) { NonlinearFactorGraph fg = createNonlinearFactorGraph(); NonlinearFactorGraph actClone = fg.clone(); EXPECT(assert_equal(fg, actClone)); for (size_t i=0; i rekey_mapping; rekey_mapping.insert(make_pair(L(1), L(4))); NonlinearFactorGraph actRekey = init.rekey(rekey_mapping); // ensure deep clone LONGS_EQUAL((long)init.size(), (long)actRekey.size()); for (size_t i=0; ibegin(); 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, dampen), 1e-6)); } /* ************************************************************************* */ // Example from issue #452 which threw an ILS error. The reason was a very // weak prior on heading, which was tightened, and the ILS disappeared. TEST(testNonlinearFactorGraph, eliminate) { // Linearization point Pose2 T11(0, 0, 0); Pose2 T12(1, 0, 0); Pose2 T21(0, 1, 0); Pose2 T22(1, 1, 0); // Factor graph auto graph = NonlinearFactorGraph(); // Priors auto prior = noiseModel::Isotropic::Sigma(3, 1); graph.add(PriorFactor(11, T11, prior)); graph.add(PriorFactor(21, T21, prior)); // Odometry auto model = noiseModel::Diagonal::Sigmas(Vector3(0.01, 0.01, 0.3)); graph.add(BetweenFactor(11, 12, T11.between(T12), model)); graph.add(BetweenFactor(21, 22, T21.between(T22), model)); // Range factor auto model_rho = noiseModel::Isotropic::Sigma(1, 0.01); graph.add(RangeFactor(12, 22, 1.0, model_rho)); Values values; values.insert(11, T11.retract(Vector3(0.1,0.2,0.3))); values.insert(12, T12); values.insert(21, T21); values.insert(22, T22); auto linearized = graph.linearize(values); // Eliminate Ordering ordering; ordering += 11, 21, 12, 22; auto bn = linearized->eliminateSequential(ordering); EXPECT_LONGS_EQUAL(4, bn->size()); } /* ************************************************************************* */ TEST(NonlinearFactorGraph, printErrors) { const NonlinearFactorGraph fg = createNonlinearFactorGraph(); const Values c = createValues(); // Test that it builds with default parameters. // We cannot check the output since (at present) output is fixed to std::cout. fg.printErrors(c); // Second round: using callback filter to check that we actually visit all factors: std::vector visited; visited.assign(fg.size(), false); const auto testFilter = [&](const gtsam::Factor *f, double error, size_t index) { EXPECT(f!=nullptr); EXPECT(error>=.0); visited.at(index)=true; return false; // do not print }; fg.printErrors(c,"Test graph: ", gtsam::DefaultKeyFormatter,testFilter); for (bool visit : visited) EXPECT(visit==true); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */