testGaussianBayesTreeB.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335
  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 testGaussianISAM.cpp
  10. * @brief Unit tests for GaussianISAM
  11. * @author Michael Kaess
  12. */
  13. #include <tests/smallExample.h>
  14. #include <gtsam/inference/Symbol.h>
  15. #include <gtsam/linear/GaussianBayesTree.h>
  16. #include <gtsam/linear/GaussianBayesNet.h>
  17. #include <gtsam/linear/GaussianConditional.h>
  18. #include <gtsam/linear/GaussianDensity.h>
  19. #include <gtsam/linear/HessianFactor.h>
  20. #include <gtsam/geometry/Rot2.h>
  21. #include <CppUnitLite/TestHarness.h>
  22. #include <boost/assign/std/list.hpp> // for operator +=
  23. using namespace boost::assign;
  24. using namespace std;
  25. using namespace gtsam;
  26. using namespace example;
  27. using symbol_shorthand::X;
  28. using symbol_shorthand::L;
  29. /* ************************************************************************* */
  30. // Some numbers that should be consistent among all smoother tests
  31. static double sigmax1 = 0.786153, /*sigmax2 = 1.0/1.47292,*/ sigmax3 = 0.671512, sigmax4 =
  32. 0.669534 /*, sigmax5 = sigmax3, sigmax6 = sigmax2*/, sigmax7 = sigmax1;
  33. static const double tol = 1e-4;
  34. /* ************************************************************************* *
  35. Bayes tree for smoother with "natural" ordering:
  36. C1 x6 x7
  37. C2 x5 : x6
  38. C3 x4 : x5
  39. C4 x3 : x4
  40. C5 x2 : x3
  41. C6 x1 : x2
  42. **************************************************************************** */
  43. TEST( GaussianBayesTree, linear_smoother_shortcuts )
  44. {
  45. // Create smoother with 7 nodes
  46. GaussianFactorGraph smoother = createSmoother(7);
  47. GaussianBayesTree bayesTree = *smoother.eliminateMultifrontal();
  48. // Create the Bayes tree
  49. LONGS_EQUAL(6, (long)bayesTree.size());
  50. // Check the conditional P(Root|Root)
  51. GaussianBayesNet empty;
  52. GaussianBayesTree::sharedClique R = bayesTree.roots().front();
  53. GaussianBayesNet actual1 = R->shortcut(R);
  54. EXPECT(assert_equal(empty,actual1,tol));
  55. // Check the conditional P(C2|Root)
  56. GaussianBayesTree::sharedClique C2 = bayesTree[X(5)];
  57. GaussianBayesNet actual2 = C2->shortcut(R);
  58. EXPECT(assert_equal(empty,actual2,tol));
  59. // Check the conditional P(C3|Root)
  60. double sigma3 = 0.61808;
  61. Matrix A56 = (Matrix(2,2) << -0.382022,0.,0.,-0.382022).finished();
  62. GaussianBayesNet expected3;
  63. expected3 += GaussianConditional(X(5), Z_2x1, I_2x2/sigma3, X(6), A56/sigma3);
  64. GaussianBayesTree::sharedClique C3 = bayesTree[X(4)];
  65. GaussianBayesNet actual3 = C3->shortcut(R);
  66. EXPECT(assert_equal(expected3,actual3,tol));
  67. // Check the conditional P(C4|Root)
  68. double sigma4 = 0.661968;
  69. Matrix A46 = (Matrix(2,2) << -0.146067,0.,0.,-0.146067).finished();
  70. GaussianBayesNet expected4;
  71. expected4 += GaussianConditional(X(4), Z_2x1, I_2x2/sigma4, X(6), A46/sigma4);
  72. GaussianBayesTree::sharedClique C4 = bayesTree[X(3)];
  73. GaussianBayesNet actual4 = C4->shortcut(R);
  74. EXPECT(assert_equal(expected4,actual4,tol));
  75. }
  76. /* ************************************************************************* *
  77. Bayes tree for smoother with "nested dissection" ordering:
  78. Node[x1] P(x1 | x2)
  79. Node[x3] P(x3 | x2 x4)
  80. Node[x5] P(x5 | x4 x6)
  81. Node[x7] P(x7 | x6)
  82. Node[x2] P(x2 | x4)
  83. Node[x6] P(x6 | x4)
  84. Node[x4] P(x4)
  85. becomes
  86. C1 x5 x6 x4
  87. C2 x3 x2 : x4
  88. C3 x1 : x2
  89. C4 x7 : x6
  90. ************************************************************************* */
  91. TEST( GaussianBayesTree, balanced_smoother_marginals )
  92. {
  93. // Create smoother with 7 nodes
  94. GaussianFactorGraph smoother = createSmoother(7);
  95. // Create the Bayes tree
  96. Ordering ordering;
  97. ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4);
  98. GaussianBayesTree bayesTree = *smoother.eliminateMultifrontal(ordering);
  99. VectorValues actualSolution = bayesTree.optimize();
  100. VectorValues expectedSolution = VectorValues::Zero(actualSolution);
  101. EXPECT(assert_equal(expectedSolution,actualSolution,tol));
  102. LONGS_EQUAL(4, (long)bayesTree.size());
  103. double tol=1e-5;
  104. // Check marginal on x1
  105. JacobianFactor expected1 = GaussianDensity::FromMeanAndStddev(X(1), Z_2x1, sigmax1);
  106. JacobianFactor actual1 = *bayesTree.marginalFactor(X(1));
  107. Matrix expectedCovarianceX1 = I_2x2 * (sigmax1 * sigmax1);
  108. Matrix actualCovarianceX1;
  109. GaussianFactor::shared_ptr m = bayesTree.marginalFactor(X(1), EliminateCholesky);
  110. actualCovarianceX1 = bayesTree.marginalFactor(X(1), EliminateCholesky)->information().inverse();
  111. EXPECT(assert_equal(expectedCovarianceX1, actualCovarianceX1, tol));
  112. EXPECT(assert_equal(expected1,actual1,tol));
  113. // Check marginal on x2
  114. double sigx2 = 0.68712938; // FIXME: this should be corrected analytically
  115. JacobianFactor expected2 = GaussianDensity::FromMeanAndStddev(X(2), Z_2x1, sigx2);
  116. JacobianFactor actual2 = *bayesTree.marginalFactor(X(2));
  117. EXPECT(assert_equal(expected2,actual2,tol));
  118. // Check marginal on x3
  119. JacobianFactor expected3 = GaussianDensity::FromMeanAndStddev(X(3), Z_2x1, sigmax3);
  120. JacobianFactor actual3 = *bayesTree.marginalFactor(X(3));
  121. EXPECT(assert_equal(expected3,actual3,tol));
  122. // Check marginal on x4
  123. JacobianFactor expected4 = GaussianDensity::FromMeanAndStddev(X(4), Z_2x1, sigmax4);
  124. JacobianFactor actual4 = *bayesTree.marginalFactor(X(4));
  125. EXPECT(assert_equal(expected4,actual4,tol));
  126. // Check marginal on x7 (should be equal to x1)
  127. JacobianFactor expected7 = GaussianDensity::FromMeanAndStddev(X(7), Z_2x1, sigmax7);
  128. JacobianFactor actual7 = *bayesTree.marginalFactor(X(7));
  129. EXPECT(assert_equal(expected7,actual7,tol));
  130. }
  131. /* ************************************************************************* */
  132. TEST( GaussianBayesTree, balanced_smoother_shortcuts )
  133. {
  134. // Create smoother with 7 nodes
  135. GaussianFactorGraph smoother = createSmoother(7);
  136. // Create the Bayes tree
  137. Ordering ordering;
  138. ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4);
  139. GaussianBayesTree bayesTree = *smoother.eliminateMultifrontal(ordering);
  140. // Check the conditional P(Root|Root)
  141. GaussianBayesNet empty;
  142. GaussianBayesTree::sharedClique R = bayesTree.roots().front();
  143. GaussianBayesNet actual1 = R->shortcut(R);
  144. EXPECT(assert_equal(empty,actual1,tol));
  145. // Check the conditional P(C2|Root)
  146. GaussianBayesTree::sharedClique C2 = bayesTree[X(3)];
  147. GaussianBayesNet actual2 = C2->shortcut(R);
  148. EXPECT(assert_equal(empty,actual2,tol));
  149. // Check the conditional P(C3|Root), which should be equal to P(x2|x4)
  150. /** TODO: Note for multifrontal conditional:
  151. * p_x2_x4 is now an element conditional of the multifrontal conditional bayesTree[ordering[X(2)]]->conditional()
  152. * We don't know yet how to take it out.
  153. */
  154. // GaussianConditional::shared_ptr p_x2_x4 = bayesTree[ordering[X(2)]]->conditional();
  155. // p_x2_x4->print("Conditional p_x2_x4: ");
  156. // GaussianBayesNet expected3(p_x2_x4);
  157. // GaussianISAM::sharedClique C3 = isamTree[ordering[X(1)]];
  158. // GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R);
  159. // EXPECT(assert_equal(expected3,actual3,tol));
  160. }
  161. ///* ************************************************************************* */
  162. //TEST( BayesTree, balanced_smoother_clique_marginals )
  163. //{
  164. // // Create smoother with 7 nodes
  165. // Ordering ordering;
  166. // ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4);
  167. // GaussianFactorGraph smoother = createSmoother(7, ordering).first;
  168. //
  169. // // Create the Bayes tree
  170. // GaussianBayesNet chordalBayesNet = *GaussianSequentialSolver(smoother).eliminate();
  171. // GaussianISAM bayesTree(chordalBayesNet);
  172. //
  173. // // Check the clique marginal P(C3)
  174. // double sigmax2_alt = 1/1.45533; // THIS NEEDS TO BE CHECKED!
  175. // GaussianBayesNet expected = simpleGaussian(ordering[X(2)],Z_2x1,sigmax2_alt);
  176. // push_front(expected,ordering[X(1)], Z_2x1, eye(2)*sqrt(2), ordering[X(2)], -eye(2)*sqrt(2)/2, ones(2));
  177. // GaussianISAM::sharedClique R = bayesTree.root(), C3 = bayesTree[ordering[X(1)]];
  178. // GaussianFactorGraph marginal = C3->marginal(R);
  179. // GaussianVariableIndex varIndex(marginal);
  180. // Permutation toFront(Permutation::PullToFront(C3->keys(), varIndex.size()));
  181. // Permutation toFrontInverse(*toFront.inverse());
  182. // varIndex.permute(toFront);
  183. // for(const GaussianFactor::shared_ptr& factor: marginal) {
  184. // factor->permuteWithInverse(toFrontInverse); }
  185. // GaussianBayesNet actual = *inference::EliminateUntil(marginal, C3->keys().size(), varIndex);
  186. // actual.permuteWithInverse(toFront);
  187. // EXPECT(assert_equal(expected,actual,tol));
  188. //}
  189. /* ************************************************************************* */
  190. TEST( GaussianBayesTree, balanced_smoother_joint )
  191. {
  192. // Create smoother with 7 nodes
  193. Ordering ordering;
  194. ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4);
  195. GaussianFactorGraph smoother = createSmoother(7);
  196. // Create the Bayes tree, expected to look like:
  197. // x5 x6 x4
  198. // x3 x2 : x4
  199. // x1 : x2
  200. // x7 : x6
  201. GaussianBayesTree bayesTree = *smoother.eliminateMultifrontal(ordering);
  202. // Conditional density elements reused by both tests
  203. const Matrix I = I_2x2, A = -0.00429185*I;
  204. // Check the joint density P(x1,x7) factored as P(x1|x7)P(x7)
  205. GaussianBayesNet expected1 = list_of
  206. // Why does the sign get flipped on the prior?
  207. (GaussianConditional(X(1), Z_2x1, I/sigmax7, X(7), A/sigmax7))
  208. (GaussianConditional(X(7), Z_2x1, -1*I/sigmax7));
  209. GaussianBayesNet actual1 = *bayesTree.jointBayesNet(X(1),X(7));
  210. EXPECT(assert_equal(expected1, actual1, tol));
  211. // // Check the joint density P(x7,x1) factored as P(x7|x1)P(x1)
  212. // GaussianBayesNet expected2;
  213. // GaussianConditional::shared_ptr
  214. // parent2(new GaussianConditional(X(1), Z_2x1, -1*I/sigmax1, ones(2)));
  215. // expected2.push_front(parent2);
  216. // push_front(expected2,X(7), Z_2x1, I/sigmax1, X(1), A/sigmax1, sigma);
  217. // GaussianBayesNet actual2 = *bayesTree.jointBayesNet(X(7),X(1));
  218. // EXPECT(assert_equal(expected2,actual2,tol));
  219. // Check the joint density P(x1,x4), i.e. with a root variable
  220. double sig14 = 0.784465;
  221. Matrix A14 = -0.0769231*I;
  222. GaussianBayesNet expected3 = list_of
  223. (GaussianConditional(X(1), Z_2x1, I/sig14, X(4), A14/sig14))
  224. (GaussianConditional(X(4), Z_2x1, I/sigmax4));
  225. GaussianBayesNet actual3 = *bayesTree.jointBayesNet(X(1),X(4));
  226. EXPECT(assert_equal(expected3,actual3,tol));
  227. // // Check the joint density P(x4,x1), i.e. with a root variable, factored the other way
  228. // GaussianBayesNet expected4;
  229. // GaussianConditional::shared_ptr
  230. // parent4(new GaussianConditional(X(1), Z_2x1, -1.0*I/sigmax1, ones(2)));
  231. // expected4.push_front(parent4);
  232. // double sig41 = 0.668096;
  233. // Matrix A41 = -0.055794*I;
  234. // push_front(expected4,X(4), Z_2x1, I/sig41, X(1), A41/sig41, sigma);
  235. // GaussianBayesNet actual4 = *bayesTree.jointBayesNet(X(4),X(1));
  236. // EXPECT(assert_equal(expected4,actual4,tol));
  237. }
  238. /* ************************************************************************* */
  239. TEST(GaussianBayesTree, shortcut_overlapping_separator)
  240. {
  241. // Test computing shortcuts when the separator overlaps. This previously
  242. // would have highlighted a problem where information was duplicated.
  243. // Create factor graph:
  244. // f(1,2,5)
  245. // f(3,4,5)
  246. // f(5,6)
  247. // f(6,7)
  248. GaussianFactorGraph fg;
  249. noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1);
  250. fg.add(1, (Matrix(1, 1) << 1.0).finished(), 3, (Matrix(1, 1) << 2.0).finished(), 5, (Matrix(1, 1) << 3.0).finished(), (Vector(1) << 4.0).finished(), model);
  251. fg.add(1, (Matrix(1, 1) << 5.0).finished(), (Vector(1) << 6.0).finished(), model);
  252. fg.add(2, (Matrix(1, 1) << 7.0).finished(), 4, (Matrix(1, 1) << 8.0).finished(), 5, (Matrix(1, 1) << 9.0).finished(), (Vector(1) << 10.0).finished(), model);
  253. fg.add(2, (Matrix(1, 1) << 11.0).finished(), (Vector(1) << 12.0).finished(), model);
  254. fg.add(5, (Matrix(1, 1) << 13.0).finished(), 6, (Matrix(1, 1) << 14.0).finished(), (Vector(1) << 15.0).finished(), model);
  255. fg.add(6, (Matrix(1, 1) << 17.0).finished(), 7, (Matrix(1, 1) << 18.0).finished(), (Vector(1) << 19.0).finished(), model);
  256. fg.add(7, (Matrix(1, 1) << 20.0).finished(), (Vector(1) << 21.0).finished(), model);
  257. // Eliminate into BayesTree
  258. // c(6,7)
  259. // c(5|6)
  260. // c(1,2|5)
  261. // c(3,4|5)
  262. Ordering ordering(fg.keys());
  263. GaussianBayesTree bt = *fg.eliminateMultifrontal(ordering); // eliminate in increasing key order, fg.keys() is sorted.
  264. GaussianFactorGraph joint = *bt.joint(1,2, EliminateQR);
  265. Matrix expectedJointJ = (Matrix(2,3) <<
  266. 5, 0, 6,
  267. 0, -11, -12
  268. ).finished();
  269. Matrix actualJointJ = joint.augmentedJacobian();
  270. // PR 315: sign of rows in joint are immaterial
  271. if (signbit(expectedJointJ(0, 2)) != signbit(actualJointJ(0, 2)))
  272. expectedJointJ.row(0) = -expectedJointJ.row(0);
  273. if (signbit(expectedJointJ(1, 2)) != signbit(actualJointJ(1, 2)))
  274. expectedJointJ.row(1) = -expectedJointJ.row(1);
  275. EXPECT(assert_equal(expectedJointJ, actualJointJ));
  276. }
  277. /* ************************************************************************* */
  278. int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
  279. /* ************************************************************************* */