testNonlinearFactorGraph.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file testNonlinearFactorGraph.cpp
  10. * @brief Unit tests for Non-Linear Factor NonlinearFactorGraph
  11. * @brief testNonlinearFactorGraph
  12. * @author Carlos Nieto
  13. * @author Christian Potthast
  14. */
  15. #include <gtsam/base/Testable.h>
  16. #include <gtsam/base/Matrix.h>
  17. #include <tests/smallExample.h>
  18. #include <gtsam/inference/FactorGraph.h>
  19. #include <gtsam/inference/Symbol.h>
  20. #include <gtsam/symbolic/SymbolicFactorGraph.h>
  21. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  22. #include <gtsam/geometry/Pose2.h>
  23. #include <gtsam/geometry/Pose3.h>
  24. #include <gtsam/sam/RangeFactor.h>
  25. #include <gtsam/slam/BetweenFactor.h>
  26. #include <CppUnitLite/TestHarness.h>
  27. #include <boost/assign/std/list.hpp>
  28. #include <boost/assign/std/set.hpp>
  29. using namespace boost::assign;
  30. /*STL/C++*/
  31. #include <iostream>
  32. using namespace std;
  33. using namespace gtsam;
  34. using namespace example;
  35. using symbol_shorthand::X;
  36. using symbol_shorthand::L;
  37. /* ************************************************************************* */
  38. TEST( NonlinearFactorGraph, equals )
  39. {
  40. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  41. NonlinearFactorGraph fg2 = createNonlinearFactorGraph();
  42. CHECK( fg.equals(fg2) );
  43. }
  44. /* ************************************************************************* */
  45. TEST( NonlinearFactorGraph, error )
  46. {
  47. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  48. Values c1 = createValues();
  49. double actual1 = fg.error(c1);
  50. DOUBLES_EQUAL( 0.0, actual1, 1e-9 );
  51. Values c2 = createNoisyValues();
  52. double actual2 = fg.error(c2);
  53. DOUBLES_EQUAL( 5.625, actual2, 1e-9 );
  54. }
  55. /* ************************************************************************* */
  56. TEST( NonlinearFactorGraph, keys )
  57. {
  58. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  59. KeySet actual = fg.keys();
  60. LONGS_EQUAL(3, (long)actual.size());
  61. KeySet::const_iterator it = actual.begin();
  62. LONGS_EQUAL((long)L(1), (long)*(it++));
  63. LONGS_EQUAL((long)X(1), (long)*(it++));
  64. LONGS_EQUAL((long)X(2), (long)*(it++));
  65. }
  66. /* ************************************************************************* */
  67. TEST( NonlinearFactorGraph, GET_ORDERING)
  68. {
  69. Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2
  70. NonlinearFactorGraph nlfg = createNonlinearFactorGraph();
  71. Ordering actual = Ordering::Colamd(nlfg);
  72. EXPECT(assert_equal(expected,actual));
  73. // Constrained ordering - put x2 at the end
  74. Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2);
  75. FastMap<Key, int> constraints;
  76. constraints[X(2)] = 1;
  77. Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints);
  78. EXPECT(assert_equal(expectedConstrained, actualConstrained));
  79. }
  80. /* ************************************************************************* */
  81. TEST( NonlinearFactorGraph, probPrime )
  82. {
  83. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  84. Values cfg = createValues();
  85. // evaluate the probability of the factor graph
  86. double actual = fg.probPrime(cfg);
  87. double expected = 1.0;
  88. DOUBLES_EQUAL(expected,actual,0);
  89. }
  90. /* ************************************************************************* */
  91. TEST( NonlinearFactorGraph, linearize )
  92. {
  93. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  94. Values initial = createNoisyValues();
  95. GaussianFactorGraph linearFG = *fg.linearize(initial);
  96. GaussianFactorGraph expected = createGaussianFactorGraph();
  97. CHECK(assert_equal(expected,linearFG)); // Needs correct linearizations
  98. }
  99. /* ************************************************************************* */
  100. TEST( NonlinearFactorGraph, clone )
  101. {
  102. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  103. NonlinearFactorGraph actClone = fg.clone();
  104. EXPECT(assert_equal(fg, actClone));
  105. for (size_t i=0; i<fg.size(); ++i)
  106. EXPECT(fg[i] != actClone[i]);
  107. }
  108. /* ************************************************************************* */
  109. TEST( NonlinearFactorGraph, rekey )
  110. {
  111. NonlinearFactorGraph init = createNonlinearFactorGraph();
  112. map<Key,Key> rekey_mapping;
  113. rekey_mapping.insert(make_pair(L(1), L(4)));
  114. NonlinearFactorGraph actRekey = init.rekey(rekey_mapping);
  115. // ensure deep clone
  116. LONGS_EQUAL((long)init.size(), (long)actRekey.size());
  117. for (size_t i=0; i<init.size(); ++i)
  118. EXPECT(init[i] != actRekey[i]);
  119. NonlinearFactorGraph expRekey;
  120. // original measurements
  121. expRekey.push_back(init[0]);
  122. expRekey.push_back(init[1]);
  123. // updated measurements
  124. Point2 z3(0, -1), z4(-1.5, -1.);
  125. SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2);
  126. expRekey += simulated2D::Measurement(z3, sigma0_2, X(1), L(4));
  127. expRekey += simulated2D::Measurement(z4, sigma0_2, X(2), L(4));
  128. EXPECT(assert_equal(expRekey, actRekey));
  129. }
  130. /* ************************************************************************* */
  131. TEST( NonlinearFactorGraph, symbolic )
  132. {
  133. NonlinearFactorGraph graph = createNonlinearFactorGraph();
  134. SymbolicFactorGraph expected;
  135. expected.push_factor(X(1));
  136. expected.push_factor(X(1), X(2));
  137. expected.push_factor(X(1), L(1));
  138. expected.push_factor(X(2), L(1));
  139. SymbolicFactorGraph actual = *graph.symbolic();
  140. EXPECT(assert_equal(expected, actual));
  141. }
  142. /* ************************************************************************* */
  143. TEST(NonlinearFactorGraph, UpdateCholesky) {
  144. NonlinearFactorGraph fg = createNonlinearFactorGraph();
  145. Values initial = createNoisyValues();
  146. // solve conventionally
  147. GaussianFactorGraph linearFG = *fg.linearize(initial);
  148. auto delta = linearFG.optimizeDensely();
  149. auto expected = initial.retract(delta);
  150. // solve with new method
  151. EXPECT(assert_equal(expected, fg.updateCholesky(initial)));
  152. // solve with Ordering
  153. Ordering ordering;
  154. ordering += L(1), X(2), X(1);
  155. EXPECT(assert_equal(expected, fg.updateCholesky(initial, ordering)));
  156. // solve with new method, heavily damped
  157. auto dampen = [](const HessianFactor::shared_ptr& hessianFactor) {
  158. auto iterator = hessianFactor->begin();
  159. for (; iterator != hessianFactor->end(); iterator++) {
  160. const auto index = std::distance(hessianFactor->begin(), iterator);
  161. auto block = hessianFactor->info().diagonalBlock(index);
  162. for (int j = 0; j < block.rows(); j++) {
  163. block(j, j) += 1e9;
  164. }
  165. }
  166. };
  167. EXPECT(assert_equal(initial, fg.updateCholesky(initial, dampen), 1e-6));
  168. }
  169. /* ************************************************************************* */
  170. // Example from issue #452 which threw an ILS error. The reason was a very
  171. // weak prior on heading, which was tightened, and the ILS disappeared.
  172. TEST(testNonlinearFactorGraph, eliminate) {
  173. // Linearization point
  174. Pose2 T11(0, 0, 0);
  175. Pose2 T12(1, 0, 0);
  176. Pose2 T21(0, 1, 0);
  177. Pose2 T22(1, 1, 0);
  178. // Factor graph
  179. auto graph = NonlinearFactorGraph();
  180. // Priors
  181. auto prior = noiseModel::Isotropic::Sigma(3, 1);
  182. graph.addPrior(11, T11, prior);
  183. graph.addPrior(21, T21, prior);
  184. // Odometry
  185. auto model = noiseModel::Diagonal::Sigmas(Vector3(0.01, 0.01, 0.3));
  186. graph.add(BetweenFactor<Pose2>(11, 12, T11.between(T12), model));
  187. graph.add(BetweenFactor<Pose2>(21, 22, T21.between(T22), model));
  188. // Range factor
  189. auto model_rho = noiseModel::Isotropic::Sigma(1, 0.01);
  190. graph.add(RangeFactor<Pose2>(12, 22, 1.0, model_rho));
  191. Values values;
  192. values.insert(11, T11.retract(Vector3(0.1,0.2,0.3)));
  193. values.insert(12, T12);
  194. values.insert(21, T21);
  195. values.insert(22, T22);
  196. auto linearized = graph.linearize(values);
  197. // Eliminate
  198. Ordering ordering;
  199. ordering += 11, 21, 12, 22;
  200. auto bn = linearized->eliminateSequential(ordering);
  201. EXPECT_LONGS_EQUAL(4, bn->size());
  202. }
  203. /* ************************************************************************* */
  204. TEST(testNonlinearFactorGraph, addPrior) {
  205. Key k(0);
  206. // Factor graph.
  207. auto graph = NonlinearFactorGraph();
  208. // Add a prior factor for key k.
  209. auto model_double = noiseModel::Isotropic::Sigma(1, 1);
  210. graph.addPrior<double>(k, 10, model_double);
  211. // Assert the graph has 0 error with the correct values.
  212. Values values;
  213. values.insert(k, 10.0);
  214. EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-16);
  215. // Assert the graph has some error with incorrect values.
  216. values.clear();
  217. values.insert(k, 11.0);
  218. EXPECT(0 != graph.error(values));
  219. // Clear the factor graph and values.
  220. values.clear();
  221. graph.erase(graph.begin(), graph.end());
  222. // Add a Pose3 prior to the factor graph. Use a gaussian noise model by
  223. // providing the covariance matrix.
  224. Eigen::DiagonalMatrix<double, 6, 6> covariance_pose3;
  225. covariance_pose3.setIdentity();
  226. Pose3 pose{Rot3(), Point3(0, 0, 0)};
  227. graph.addPrior(k, pose, covariance_pose3);
  228. // Assert the graph has 0 error with the correct values.
  229. values.insert(k, pose);
  230. EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-16);
  231. // Assert the graph has some error with incorrect values.
  232. values.clear();
  233. Pose3 pose_incorrect{Rot3::RzRyRx(-M_PI, M_PI, -M_PI / 8), Point3(1, 2, 3)};
  234. values.insert(k, pose_incorrect);
  235. EXPECT(0 != graph.error(values));
  236. }
  237. TEST(NonlinearFactorGraph, printErrors)
  238. {
  239. const NonlinearFactorGraph fg = createNonlinearFactorGraph();
  240. const Values c = createValues();
  241. // Test that it builds with default parameters.
  242. // We cannot check the output since (at present) output is fixed to std::cout.
  243. fg.printErrors(c);
  244. // Second round: using callback filter to check that we actually visit all factors:
  245. std::vector<bool> visited;
  246. visited.assign(fg.size(), false);
  247. const auto testFilter =
  248. [&](const gtsam::Factor *f, double error, size_t index) {
  249. EXPECT(f!=nullptr);
  250. EXPECT(error>=.0);
  251. visited.at(index)=true;
  252. return false; // do not print
  253. };
  254. fg.printErrors(c,"Test graph: ", gtsam::DefaultKeyFormatter,testFilter);
  255. for (bool visit : visited) EXPECT(visit==true);
  256. }
  257. /* ************************************************************************* */
  258. int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
  259. /* ************************************************************************* */