testGraph.cpp 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232
  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 testGraph.cpp
  10. * @date Jan 12, 2010
  11. * @author nikai
  12. * @brief unit test for graph-inl.h
  13. */
  14. #include <gtsam/slam/BetweenFactor.h>
  15. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  16. #include <gtsam/linear/GaussianFactorGraph.h>
  17. #include <gtsam/linear/JacobianFactor.h>
  18. #include <gtsam/inference/graph.h>
  19. #include <gtsam/inference/Symbol.h>
  20. #include <gtsam/geometry/Pose2.h>
  21. #include <CppUnitLite/TestHarness.h>
  22. #include <boost/shared_ptr.hpp>
  23. #include <boost/assign/std/list.hpp> // for operator +=
  24. using namespace boost::assign;
  25. #include <iostream>
  26. using namespace std;
  27. using namespace gtsam;
  28. /* ************************************************************************* */
  29. // x1 -> x2
  30. // -> x3 -> x4
  31. // -> x5
  32. TEST ( Ordering, predecessorMap2Keys ) {
  33. PredecessorMap<Key> p_map;
  34. p_map.insert(1,1);
  35. p_map.insert(2,1);
  36. p_map.insert(3,1);
  37. p_map.insert(4,3);
  38. p_map.insert(5,1);
  39. list<Key> expected;
  40. expected += 4,5,3,2,1;
  41. list<Key> actual = predecessorMap2Keys<Key>(p_map);
  42. LONGS_EQUAL((long)expected.size(), (long)actual.size());
  43. list<Key>::const_iterator it1 = expected.begin();
  44. list<Key>::const_iterator it2 = actual.begin();
  45. for(; it1!=expected.end(); it1++, it2++)
  46. CHECK(*it1 == *it2)
  47. }
  48. /* ************************************************************************* */
  49. TEST( Graph, predecessorMap2Graph )
  50. {
  51. typedef SGraph<string>::Vertex SVertex;
  52. SGraph<Key> graph;
  53. SVertex root;
  54. map<Key, SVertex> key2vertex;
  55. PredecessorMap<Key> p_map;
  56. p_map.insert(1, 2);
  57. p_map.insert(2, 2);
  58. p_map.insert(3, 2);
  59. boost::tie(graph, root, key2vertex) = predecessorMap2Graph<SGraph<Key>, SVertex, Key>(p_map);
  60. LONGS_EQUAL(3, (long)boost::num_vertices(graph));
  61. CHECK(root == key2vertex[2]);
  62. }
  63. /* ************************************************************************* */
  64. TEST( Graph, composePoses )
  65. {
  66. NonlinearFactorGraph graph;
  67. SharedNoiseModel cov = noiseModel::Unit::Create(3);
  68. Pose2 p1(1.0, 2.0, 0.3), p2(4.0, 5.0, 0.6), p3(7.0, 8.0, 0.9), p4(2.0, 2.0, 2.9);
  69. Pose2 p12=p1.between(p2), p23=p2.between(p3), p43=p4.between(p3);
  70. graph += BetweenFactor<Pose2>(1,2, p12, cov);
  71. graph += BetweenFactor<Pose2>(2,3, p23, cov);
  72. graph += BetweenFactor<Pose2>(4,3, p43, cov);
  73. PredecessorMap<Key> tree;
  74. tree.insert(1,2);
  75. tree.insert(2,2);
  76. tree.insert(3,2);
  77. tree.insert(4,3);
  78. Pose2 rootPose = p2;
  79. boost::shared_ptr<Values> actual = composePoses<NonlinearFactorGraph, BetweenFactor<Pose2>, Pose2, Key> (graph, tree, rootPose);
  80. Values expected;
  81. expected.insert(1, p1);
  82. expected.insert(2, p2);
  83. expected.insert(3, p3);
  84. expected.insert(4, p4);
  85. LONGS_EQUAL(4, (long)actual->size());
  86. CHECK(assert_equal(expected, *actual));
  87. }
  88. /* ************************************************************************* */
  89. TEST( GaussianFactorGraph, findMinimumSpanningTree )
  90. {
  91. GaussianFactorGraph g;
  92. Matrix I = I_2x2;
  93. Vector2 b(0, 0);
  94. const SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector2(0.5, 0.5));
  95. using namespace symbol_shorthand;
  96. g += JacobianFactor(X(1), I, X(2), I, b, model);
  97. g += JacobianFactor(X(1), I, X(3), I, b, model);
  98. g += JacobianFactor(X(1), I, X(4), I, b, model);
  99. g += JacobianFactor(X(2), I, X(3), I, b, model);
  100. g += JacobianFactor(X(2), I, X(4), I, b, model);
  101. g += JacobianFactor(X(3), I, X(4), I, b, model);
  102. PredecessorMap<Key> tree = findMinimumSpanningTree<GaussianFactorGraph, Key, JacobianFactor>(g);
  103. EXPECT_LONGS_EQUAL(X(1),tree[X(1)]);
  104. EXPECT_LONGS_EQUAL(X(1),tree[X(2)]);
  105. EXPECT_LONGS_EQUAL(X(1),tree[X(3)]);
  106. EXPECT_LONGS_EQUAL(X(1),tree[X(4)]);
  107. // we add a disconnected component - does not work yet
  108. // g += JacobianFactor(X(5), I, X(6), I, b, model);
  109. //
  110. // PredecessorMap<Key> forest = findMinimumSpanningTree<GaussianFactorGraph, Key, JacobianFactor>(g);
  111. // EXPECT_LONGS_EQUAL(X(1),forest[X(1)]);
  112. // EXPECT_LONGS_EQUAL(X(1),forest[X(2)]);
  113. // EXPECT_LONGS_EQUAL(X(1),forest[X(3)]);
  114. // EXPECT_LONGS_EQUAL(X(1),forest[X(4)]);
  115. // EXPECT_LONGS_EQUAL(X(5),forest[X(5)]);
  116. // EXPECT_LONGS_EQUAL(X(5),forest[X(6)]);
  117. }
  118. ///* ************************************************************************* */
  119. // SL-FIX TEST( GaussianFactorGraph, split )
  120. //{
  121. // GaussianFactorGraph g;
  122. // Matrix I = eye(2);
  123. // Vector b = Vector_(0, 0, 0);
  124. // g += X(1), I, X(2), I, b, model;
  125. // g += X(1), I, X(3), I, b, model;
  126. // g += X(1), I, X(4), I, b, model;
  127. // g += X(2), I, X(3), I, b, model;
  128. // g += X(2), I, X(4), I, b, model;
  129. //
  130. // PredecessorMap<string> tree;
  131. // tree[X(1)] = X(1);
  132. // tree[X(2)] = X(1);
  133. // tree[X(3)] = X(1);
  134. // tree[X(4)] = X(1);
  135. //
  136. // GaussianFactorGraph Ab1, Ab2;
  137. // g.split<string, GaussianFactor>(tree, Ab1, Ab2);
  138. // LONGS_EQUAL(3, Ab1.size());
  139. // LONGS_EQUAL(2, Ab2.size());
  140. //}
  141. ///* ************************************************************************* */
  142. // SL-FIX TEST( FactorGraph, splitMinimumSpanningTree )
  143. //{
  144. // SymbolicFactorGraph G;
  145. // G.push_factor("x1", "x2");
  146. // G.push_factor("x1", "x3");
  147. // G.push_factor("x1", "x4");
  148. // G.push_factor("x2", "x3");
  149. // G.push_factor("x2", "x4");
  150. // G.push_factor("x3", "x4");
  151. //
  152. // SymbolicFactorGraph T, C;
  153. // boost::tie(T, C) = G.splitMinimumSpanningTree();
  154. //
  155. // SymbolicFactorGraph expectedT, expectedC;
  156. // expectedT.push_factor("x1", "x2");
  157. // expectedT.push_factor("x1", "x3");
  158. // expectedT.push_factor("x1", "x4");
  159. // expectedC.push_factor("x2", "x3");
  160. // expectedC.push_factor("x2", "x4");
  161. // expectedC.push_factor("x3", "x4");
  162. // CHECK(assert_equal(expectedT,T));
  163. // CHECK(assert_equal(expectedC,C));
  164. //}
  165. ///* ************************************************************************* */
  166. ///**
  167. // * x1 - x2 - x3 - x4 - x5
  168. // * | | / |
  169. // * l1 l2 l3
  170. // */
  171. // SL-FIX TEST( FactorGraph, removeSingletons )
  172. //{
  173. // SymbolicFactorGraph G;
  174. // G.push_factor("x1", "x2");
  175. // G.push_factor("x2", "x3");
  176. // G.push_factor("x3", "x4");
  177. // G.push_factor("x4", "x5");
  178. // G.push_factor("x2", "l1");
  179. // G.push_factor("x3", "l2");
  180. // G.push_factor("x4", "l2");
  181. // G.push_factor("x4", "l3");
  182. //
  183. // SymbolicFactorGraph singletonGraph;
  184. // set<Symbol> singletons;
  185. // boost::tie(singletonGraph, singletons) = G.removeSingletons();
  186. //
  187. // set<Symbol> singletons_excepted; singletons_excepted += "x1", "x2", "x5", "l1", "l3";
  188. // CHECK(singletons_excepted == singletons);
  189. //
  190. // SymbolicFactorGraph singletonGraph_excepted;
  191. // singletonGraph_excepted.push_factor("x2", "l1");
  192. // singletonGraph_excepted.push_factor("x4", "l3");
  193. // singletonGraph_excepted.push_factor("x1", "x2");
  194. // singletonGraph_excepted.push_factor("x4", "x5");
  195. // singletonGraph_excepted.push_factor("x2", "x3");
  196. // CHECK(singletonGraph_excepted.equals(singletonGraph));
  197. //}
  198. /* ************************************************************************* */
  199. int main() {
  200. TestResult tr;
  201. return TestRegistry::runAllTests(tr);
  202. }
  203. /* ************************************************************************* */