testMarginals.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263
  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 testMarginals.cpp
  10. * @brief
  11. * @author Richard Roberts
  12. * @date May 14, 2012
  13. */
  14. #include <CppUnitLite/TestHarness.h>
  15. // for all nonlinear keys
  16. #include <gtsam/inference/Symbol.h>
  17. // for points and poses
  18. #include <gtsam/geometry/Point2.h>
  19. #include <gtsam/geometry/Pose2.h>
  20. // for modeling measurement uncertainty - all models included here
  21. #include <gtsam/linear/NoiseModel.h>
  22. // add in headers for specific factors
  23. #include <gtsam/slam/BetweenFactor.h>
  24. #include <gtsam/sam/BearingRangeFactor.h>
  25. #include <gtsam/nonlinear/Marginals.h>
  26. using namespace std;
  27. using namespace gtsam;
  28. TEST(Marginals, planarSLAMmarginals) {
  29. // Taken from PlanarSLAMSelfContained_advanced
  30. // create keys for variables
  31. Symbol x1('x',1), x2('x',2), x3('x',3);
  32. Symbol l1('l',1), l2('l',2);
  33. // create graph container and add factors to it
  34. NonlinearFactorGraph graph;
  35. /* add prior */
  36. // gaussian for prior
  37. SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
  38. Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
  39. graph.addPrior(x1, priorMean, priorNoise); // add the factor to the graph
  40. /* add odometry */
  41. // general noisemodel for odometry
  42. SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  43. Pose2 odometry(2.0, 0.0, 0.0); // create a measurement for both factors (the same in this case)
  44. // create between factors to represent odometry
  45. graph += BetweenFactor<Pose2>(x1, x2, odometry, odometryNoise);
  46. graph += BetweenFactor<Pose2>(x2, x3, odometry, odometryNoise);
  47. /* add measurements */
  48. // general noisemodel for measurements
  49. SharedDiagonal measurementNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.2));
  50. // create the measurement values - indices are (pose id, landmark id)
  51. Rot2 bearing11 = Rot2::fromDegrees(45),
  52. bearing21 = Rot2::fromDegrees(90),
  53. bearing32 = Rot2::fromDegrees(90);
  54. double range11 = sqrt(4.0+4.0),
  55. range21 = 2.0,
  56. range32 = 2.0;
  57. // create bearing/range factors
  58. graph += BearingRangeFactor<Pose2, Point2>(x1, l1, bearing11, range11, measurementNoise);
  59. graph += BearingRangeFactor<Pose2, Point2>(x2, l1, bearing21, range21, measurementNoise);
  60. graph += BearingRangeFactor<Pose2, Point2>(x3, l2, bearing32, range32, measurementNoise);
  61. // linearization point for marginals
  62. Values soln;
  63. soln.insert(x1, Pose2(0.0, 0.0, 0.0));
  64. soln.insert(x2, Pose2(2.0, 0.0, 0.0));
  65. soln.insert(x3, Pose2(4.0, 0.0, 0.0));
  66. soln.insert(l1, Point2(2.0, 2.0));
  67. soln.insert(l2, Point2(4.0, 2.0));
  68. VectorValues soln_lin;
  69. soln_lin.insert(x1, Vector3(0.0, 0.0, 0.0));
  70. soln_lin.insert(x2, Vector3(2.0, 0.0, 0.0));
  71. soln_lin.insert(x3, Vector3(4.0, 0.0, 0.0));
  72. soln_lin.insert(l1, Vector2(2.0, 2.0));
  73. soln_lin.insert(l2, Vector2(4.0, 2.0));
  74. Matrix expectedx1(3,3);
  75. expectedx1 <<
  76. 0.09, -7.1942452e-18, -1.27897692e-17,
  77. -7.1942452e-18, 0.09, 1.27897692e-17,
  78. -1.27897692e-17, 1.27897692e-17, 0.01;
  79. Matrix expectedx2(3,3);
  80. expectedx2 <<
  81. 0.120967742, -0.00129032258, 0.00451612903,
  82. -0.00129032258, 0.158387097, 0.0206451613,
  83. 0.00451612903, 0.0206451613, 0.0177419355;
  84. Matrix expectedx3(3,3);
  85. expectedx3 <<
  86. 0.160967742, 0.00774193548, 0.00451612903,
  87. 0.00774193548, 0.351935484, 0.0561290323,
  88. 0.00451612903, 0.0561290323, 0.0277419355;
  89. Matrix expectedl1(2,2);
  90. expectedl1 <<
  91. 0.168709677, -0.0477419355,
  92. -0.0477419355, 0.163548387;
  93. Matrix expectedl2(2,2);
  94. expectedl2 <<
  95. 0.293870968, -0.104516129,
  96. -0.104516129, 0.391935484;
  97. auto testMarginals = [&] (Marginals marginals) {
  98. EXPECT(assert_equal(expectedx1, marginals.marginalCovariance(x1), 1e-8));
  99. EXPECT(assert_equal(expectedx2, marginals.marginalCovariance(x2), 1e-8));
  100. EXPECT(assert_equal(expectedx3, marginals.marginalCovariance(x3), 1e-8));
  101. EXPECT(assert_equal(expectedl1, marginals.marginalCovariance(l1), 1e-8));
  102. EXPECT(assert_equal(expectedl2, marginals.marginalCovariance(l2), 1e-8));
  103. };
  104. auto testJointMarginals = [&] (Marginals marginals) {
  105. // Check joint marginals for 3 variables
  106. Matrix expected_l2x1x3(8,8);
  107. expected_l2x1x3 <<
  108. 0.293871159514111, -0.104516127560770, 0.090000180000270, -0.000000000000000, -0.020000000000000, 0.151935669757191, -0.104516127560770, -0.050967744878460,
  109. -0.104516127560770, 0.391935664055174, 0.000000000000000, 0.090000180000270, 0.040000000000000, 0.007741936219615, 0.351935664055174, 0.056129031890193,
  110. 0.090000180000270, 0.000000000000000, 0.090000180000270, -0.000000000000000, 0.000000000000000, 0.090000180000270, 0.000000000000000, 0.000000000000000,
  111. -0.000000000000000, 0.090000180000270, -0.000000000000000, 0.090000180000270, 0.000000000000000, -0.000000000000000, 0.090000180000270, 0.000000000000000,
  112. -0.020000000000000, 0.040000000000000, 0.000000000000000, 0.000000000000000, 0.010000000000000, 0.000000000000000, 0.040000000000000, 0.010000000000000,
  113. 0.151935669757191, 0.007741936219615, 0.090000180000270, -0.000000000000000, 0.000000000000000, 0.160967924878730, 0.007741936219615, 0.004516127560770,
  114. -0.104516127560770, 0.351935664055174, 0.000000000000000, 0.090000180000270, 0.040000000000000, 0.007741936219615, 0.351935664055174, 0.056129031890193,
  115. -0.050967744878460, 0.056129031890193, 0.000000000000000, 0.000000000000000, 0.010000000000000, 0.004516127560770, 0.056129031890193, 0.027741936219615;
  116. KeyVector variables {x1, l2, x3};
  117. JointMarginal joint_l2x1x3 = marginals.jointMarginalCovariance(variables);
  118. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(0,0,2,2)), Matrix(joint_l2x1x3(l2,l2)), 1e-6));
  119. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(2,0,3,2)), Matrix(joint_l2x1x3(x1,l2)), 1e-6));
  120. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(5,0,3,2)), Matrix(joint_l2x1x3(x3,l2)), 1e-6));
  121. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(0,2,2,3)), Matrix(joint_l2x1x3(l2,x1)), 1e-6));
  122. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(2,2,3,3)), Matrix(joint_l2x1x3(x1,x1)), 1e-6));
  123. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(5,2,3,3)), Matrix(joint_l2x1x3(x3,x1)), 1e-6));
  124. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(0,5,2,3)), Matrix(joint_l2x1x3(l2,x3)), 1e-6));
  125. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(2,5,3,3)), Matrix(joint_l2x1x3(x1,x3)), 1e-6));
  126. EXPECT(assert_equal(Matrix(expected_l2x1x3.block(5,5,3,3)), Matrix(joint_l2x1x3(x3,x3)), 1e-6));
  127. // Check joint marginals for 2 variables (different code path than >2 variable case above)
  128. Matrix expected_l2x1(5,5);
  129. expected_l2x1 <<
  130. 0.293871159514111, -0.104516127560770, 0.090000180000270, -0.000000000000000, -0.020000000000000,
  131. -0.104516127560770, 0.391935664055174, 0.000000000000000, 0.090000180000270, 0.040000000000000,
  132. 0.090000180000270, 0.000000000000000, 0.090000180000270, -0.000000000000000, 0.000000000000000,
  133. -0.000000000000000, 0.090000180000270, -0.000000000000000, 0.090000180000270, 0.000000000000000,
  134. -0.020000000000000, 0.040000000000000, 0.000000000000000, 0.000000000000000, 0.010000000000000;
  135. variables.resize(2);
  136. variables[0] = l2;
  137. variables[1] = x1;
  138. JointMarginal joint_l2x1 = marginals.jointMarginalCovariance(variables);
  139. EXPECT(assert_equal(Matrix(expected_l2x1.block(0,0,2,2)), Matrix(joint_l2x1(l2,l2)), 1e-6));
  140. EXPECT(assert_equal(Matrix(expected_l2x1.block(2,0,3,2)), Matrix(joint_l2x1(x1,l2)), 1e-6));
  141. EXPECT(assert_equal(Matrix(expected_l2x1.block(0,2,2,3)), Matrix(joint_l2x1(l2,x1)), 1e-6));
  142. EXPECT(assert_equal(Matrix(expected_l2x1.block(2,2,3,3)), Matrix(joint_l2x1(x1,x1)), 1e-6));
  143. // Check joint marginal for 1 variable (different code path than >1 variable cases above)
  144. variables.resize(1);
  145. variables[0] = x1;
  146. JointMarginal joint_x1 = marginals.jointMarginalCovariance(variables);
  147. EXPECT(assert_equal(expectedx1, Matrix(joint_l2x1(x1,x1)), 1e-6));
  148. };
  149. Marginals marginals;
  150. marginals = Marginals(graph, soln, Marginals::CHOLESKY);
  151. testMarginals(marginals);
  152. marginals = Marginals(graph, soln, Marginals::QR);
  153. testMarginals(marginals);
  154. testJointMarginals(marginals);
  155. GaussianFactorGraph gfg = *graph.linearize(soln);
  156. marginals = Marginals(gfg, soln_lin, Marginals::CHOLESKY);
  157. testMarginals(marginals);
  158. marginals = Marginals(gfg, soln_lin, Marginals::QR);
  159. testMarginals(marginals);
  160. testJointMarginals(marginals);
  161. }
  162. /* ************************************************************************* */
  163. TEST(Marginals, order) {
  164. NonlinearFactorGraph fg;
  165. fg.addPrior(0, Pose2(), noiseModel::Unit::Create(3));
  166. fg += BetweenFactor<Pose2>(0, 1, Pose2(1,0,0), noiseModel::Unit::Create(3));
  167. fg += BetweenFactor<Pose2>(1, 2, Pose2(1,0,0), noiseModel::Unit::Create(3));
  168. fg += BetweenFactor<Pose2>(2, 3, Pose2(1,0,0), noiseModel::Unit::Create(3));
  169. Values vals;
  170. vals.insert(0, Pose2());
  171. vals.insert(1, Pose2(1,0,0));
  172. vals.insert(2, Pose2(2,0,0));
  173. vals.insert(3, Pose2(3,0,0));
  174. vals.insert(100, Point2(0,1));
  175. vals.insert(101, Point2(1,1));
  176. fg += BearingRangeFactor<Pose2,Point2>(0, 100,
  177. vals.at<Pose2>(0).bearing(vals.at<Point2>(100)),
  178. vals.at<Pose2>(0).range(vals.at<Point2>(100)), noiseModel::Unit::Create(2));
  179. fg += BearingRangeFactor<Pose2,Point2>(0, 101,
  180. vals.at<Pose2>(0).bearing(vals.at<Point2>(101)),
  181. vals.at<Pose2>(0).range(vals.at<Point2>(101)), noiseModel::Unit::Create(2));
  182. fg += BearingRangeFactor<Pose2,Point2>(1, 100,
  183. vals.at<Pose2>(1).bearing(vals.at<Point2>(100)),
  184. vals.at<Pose2>(1).range(vals.at<Point2>(100)), noiseModel::Unit::Create(2));
  185. fg += BearingRangeFactor<Pose2,Point2>(1, 101,
  186. vals.at<Pose2>(1).bearing(vals.at<Point2>(101)),
  187. vals.at<Pose2>(1).range(vals.at<Point2>(101)), noiseModel::Unit::Create(2));
  188. fg += BearingRangeFactor<Pose2,Point2>(2, 100,
  189. vals.at<Pose2>(2).bearing(vals.at<Point2>(100)),
  190. vals.at<Pose2>(2).range(vals.at<Point2>(100)), noiseModel::Unit::Create(2));
  191. fg += BearingRangeFactor<Pose2,Point2>(2, 101,
  192. vals.at<Pose2>(2).bearing(vals.at<Point2>(101)),
  193. vals.at<Pose2>(2).range(vals.at<Point2>(101)), noiseModel::Unit::Create(2));
  194. fg += BearingRangeFactor<Pose2,Point2>(3, 100,
  195. vals.at<Pose2>(3).bearing(vals.at<Point2>(100)),
  196. vals.at<Pose2>(3).range(vals.at<Point2>(100)), noiseModel::Unit::Create(2));
  197. fg += BearingRangeFactor<Pose2,Point2>(3, 101,
  198. vals.at<Pose2>(3).bearing(vals.at<Point2>(101)),
  199. vals.at<Pose2>(3).range(vals.at<Point2>(101)), noiseModel::Unit::Create(2));
  200. auto testMarginals = [&] (Marginals marginals, KeySet set) {
  201. KeyVector keys(set.begin(), set.end());
  202. JointMarginal joint = marginals.jointMarginalCovariance(keys);
  203. LONGS_EQUAL(3, (long)joint(0,0).rows());
  204. LONGS_EQUAL(3, (long)joint(1,1).rows());
  205. LONGS_EQUAL(3, (long)joint(2,2).rows());
  206. LONGS_EQUAL(3, (long)joint(3,3).rows());
  207. LONGS_EQUAL(2, (long)joint(100,100).rows());
  208. LONGS_EQUAL(2, (long)joint(101,101).rows());
  209. };
  210. Marginals marginals(fg, vals);
  211. KeySet set = fg.keys();
  212. testMarginals(marginals, set);
  213. GaussianFactorGraph gfg = *fg.linearize(vals);
  214. marginals = Marginals(gfg, vals);
  215. set = gfg.keys();
  216. testMarginals(marginals, set);
  217. }
  218. /* ************************************************************************* */
  219. int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
  220. /* ************************************************************************* */