testGaussianISAM2.cpp 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822
  1. /**
  2. * @file testGaussianISAM2.cpp
  3. * @brief Unit tests for GaussianISAM2
  4. * @author Michael Kaess
  5. */
  6. #include <gtsam/nonlinear/ISAM2.h>
  7. #include <tests/smallExample.h>
  8. #include <gtsam/slam/BetweenFactor.h>
  9. #include <gtsam/sam/BearingRangeFactor.h>
  10. #include <gtsam/geometry/Point2.h>
  11. #include <gtsam/geometry/Pose2.h>
  12. #include <gtsam/nonlinear/Values.h>
  13. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  14. #include <gtsam/nonlinear/Marginals.h>
  15. #include <gtsam/linear/GaussianBayesNet.h>
  16. #include <gtsam/linear/GaussianBayesTree.h>
  17. #include <gtsam/linear/GaussianFactorGraph.h>
  18. #include <gtsam/inference/Ordering.h>
  19. #include <gtsam/base/debug.h>
  20. #include <gtsam/base/TestableAssertions.h>
  21. #include <gtsam/base/treeTraversal-inst.h>
  22. #include <CppUnitLite/TestHarness.h>
  23. #include <boost/assign/list_of.hpp>
  24. #include <boost/range/adaptor/map.hpp>
  25. using namespace boost::assign;
  26. namespace br { using namespace boost::adaptors; using namespace boost::range; }
  27. using namespace std;
  28. using namespace gtsam;
  29. using boost::shared_ptr;
  30. static const SharedNoiseModel model;
  31. // SETDEBUG("ISAM2 update", true);
  32. // SETDEBUG("ISAM2 update verbose", true);
  33. // SETDEBUG("ISAM2 recalculate", true);
  34. // Set up parameters
  35. SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.1, 0.1, M_PI/100.0).finished());
  36. SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0, 0.1).finished());
  37. ISAM2 createSlamlikeISAM2(
  38. boost::optional<Values&> init_values = boost::none,
  39. boost::optional<NonlinearFactorGraph&> full_graph = boost::none,
  40. const ISAM2Params& params = ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0,
  41. 0, false, true,
  42. ISAM2Params::CHOLESKY, true,
  43. DefaultKeyFormatter, true),
  44. size_t maxPoses = 10) {
  45. // These variables will be reused and accumulate factors and values
  46. ISAM2 isam(params);
  47. Values fullinit;
  48. NonlinearFactorGraph fullgraph;
  49. // i keeps track of the time step
  50. size_t i = 0;
  51. // Add a prior at time 0 and update isam
  52. {
  53. NonlinearFactorGraph newfactors;
  54. newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
  55. fullgraph.push_back(newfactors);
  56. Values init;
  57. init.insert((0), Pose2(0.01, 0.01, 0.01));
  58. fullinit.insert((0), Pose2(0.01, 0.01, 0.01));
  59. isam.update(newfactors, init);
  60. }
  61. if(i > maxPoses)
  62. goto done;
  63. // Add odometry from time 0 to time 5
  64. for( ; i<5; ++i) {
  65. NonlinearFactorGraph newfactors;
  66. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  67. fullgraph.push_back(newfactors);
  68. Values init;
  69. init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  70. fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  71. isam.update(newfactors, init);
  72. if(i > maxPoses)
  73. goto done;
  74. }
  75. if(i > maxPoses)
  76. goto done;
  77. // Add odometry from time 5 to 6 and landmark measurement at time 5
  78. {
  79. NonlinearFactorGraph newfactors;
  80. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  81. newfactors += BearingRangeFactor<Pose2,Point2>(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
  82. newfactors += BearingRangeFactor<Pose2,Point2>(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
  83. fullgraph.push_back(newfactors);
  84. Values init;
  85. init.insert((i+1), Pose2(1.01, 0.01, 0.01));
  86. init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
  87. init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
  88. fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01));
  89. fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
  90. fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
  91. isam.update(newfactors, init);
  92. ++ i;
  93. }
  94. if(i > maxPoses)
  95. goto done;
  96. // Add odometry from time 6 to time 10
  97. for( ; i<10; ++i) {
  98. NonlinearFactorGraph newfactors;
  99. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  100. fullgraph.push_back(newfactors);
  101. Values init;
  102. init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  103. fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  104. isam.update(newfactors, init);
  105. if(i > maxPoses)
  106. goto done;
  107. }
  108. if(i > maxPoses)
  109. goto done;
  110. // Add odometry from time 10 to 11 and landmark measurement at time 10
  111. {
  112. NonlinearFactorGraph newfactors;
  113. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  114. newfactors += BearingRangeFactor<Pose2,Point2>(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
  115. newfactors += BearingRangeFactor<Pose2,Point2>(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
  116. fullgraph.push_back(newfactors);
  117. Values init;
  118. init.insert((i+1), Pose2(6.9, 0.1, 0.01));
  119. fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01));
  120. isam.update(newfactors, init);
  121. ++ i;
  122. }
  123. done:
  124. if (full_graph)
  125. *full_graph = fullgraph;
  126. if (init_values)
  127. *init_values = fullinit;
  128. return isam;
  129. }
  130. /* ************************************************************************* */
  131. //TEST(ISAM2, CheckRelinearization) {
  132. //
  133. // typedef GaussianISAM2<Values>::Impl Impl;
  134. //
  135. // // Create values where indices 1 and 3 are above the threshold of 0.1
  136. // VectorValues values;
  137. // values.reserve(4, 10);
  138. // values.push_back_preallocated(Vector2(0.09, 0.09));
  139. // values.push_back_preallocated(Vector3(0.11, 0.11, 0.09));
  140. // values.push_back_preallocated(Vector3(0.09, 0.09, 0.09));
  141. // values.push_back_preallocated(Vector2(0.11, 0.11));
  142. //
  143. // // Create a permutation
  144. // Permutation permutation(4);
  145. // permutation[0] = 2;
  146. // permutation[1] = 0;
  147. // permutation[2] = 1;
  148. // permutation[3] = 3;
  149. //
  150. // Permuted<VectorValues> permuted(permutation, values);
  151. //
  152. // // After permutation, the indices above the threshold are 2 and 2
  153. // KeySet expected;
  154. // expected.insert(2);
  155. // expected.insert(3);
  156. //
  157. // // Indices checked by CheckRelinearization
  158. // KeySet actual = Impl::CheckRelinearization(permuted, 0.1);
  159. //
  160. // EXPECT(assert_equal(expected, actual));
  161. //}
  162. /* ************************************************************************* */
  163. struct ConsistencyVisitor
  164. {
  165. bool consistent;
  166. const ISAM2& isam;
  167. ConsistencyVisitor(const ISAM2& isam) :
  168. consistent(true), isam(isam) {}
  169. int operator()(const ISAM2::sharedClique& node, int& parentData)
  170. {
  171. if(find(isam.roots().begin(), isam.roots().end(), node) == isam.roots().end())
  172. {
  173. if(node->parent_.expired())
  174. consistent = false;
  175. if(find(node->parent()->children.begin(), node->parent()->children.end(), node) == node->parent()->children.end())
  176. consistent = false;
  177. }
  178. for(Key j: node->conditional()->frontals())
  179. {
  180. if(isam.nodes().at(j).get() != node.get())
  181. consistent = false;
  182. }
  183. return 0;
  184. }
  185. };
  186. /* ************************************************************************* */
  187. bool isam_check(const NonlinearFactorGraph& fullgraph, const Values& fullinit, const ISAM2& isam, Test& test, TestResult& result) {
  188. TestResult& result_ = result;
  189. const string name_ = test.getName();
  190. Values actual = isam.calculateEstimate();
  191. Values expected = fullinit.retract(fullgraph.linearize(fullinit)->optimize());
  192. bool isamEqual = assert_equal(expected, actual);
  193. // Check information
  194. GaussianFactorGraph isamGraph(isam);
  195. isamGraph += isam.roots().front()->cachedFactor_;
  196. Matrix expectedHessian = fullgraph.linearize(isam.getLinearizationPoint())->augmentedHessian();
  197. Matrix actualHessian = isamGraph.augmentedHessian();
  198. expectedHessian.bottomRightCorner(1,1) = actualHessian.bottomRightCorner(1,1);
  199. bool isamTreeEqual = assert_equal(expectedHessian, actualHessian);
  200. // Check consistency
  201. ConsistencyVisitor visitor(isam);
  202. int data; // Unused
  203. treeTraversal::DepthFirstForest(isam, data, visitor);
  204. bool consistent = visitor.consistent;
  205. // The following two checks make sure that the cached gradients are maintained and used correctly
  206. // Check gradient at each node
  207. bool nodeGradientsOk = true;
  208. typedef ISAM2::sharedClique sharedClique;
  209. for(const sharedClique& clique: isam.nodes() | br::map_values) {
  210. // Compute expected gradient
  211. GaussianFactorGraph jfg;
  212. jfg += clique->conditional();
  213. VectorValues expectedGradient = jfg.gradientAtZero();
  214. // Compare with actual gradients
  215. DenseIndex variablePosition = 0;
  216. for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
  217. const DenseIndex dim = clique->conditional()->getDim(jit);
  218. Vector actual = clique->gradientContribution().segment(variablePosition, dim);
  219. bool gradOk = assert_equal(expectedGradient[*jit], actual);
  220. EXPECT(gradOk);
  221. nodeGradientsOk = nodeGradientsOk && gradOk;
  222. variablePosition += dim;
  223. }
  224. bool dimOk = clique->gradientContribution().rows() == variablePosition;
  225. EXPECT(dimOk);
  226. nodeGradientsOk = nodeGradientsOk && dimOk;
  227. }
  228. // Check gradient
  229. VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
  230. VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
  231. VectorValues actualGradient = isam.gradientAtZero();
  232. bool expectedGradOk = assert_equal(expectedGradient2, expectedGradient);
  233. EXPECT(expectedGradOk);
  234. bool totalGradOk = assert_equal(expectedGradient, actualGradient);
  235. EXPECT(totalGradOk);
  236. return nodeGradientsOk && expectedGradOk && totalGradOk && isamEqual && isamTreeEqual && consistent;
  237. }
  238. /* ************************************************************************* */
  239. TEST(ISAM2, simple)
  240. {
  241. for(size_t i = 0; i < 10; ++i) {
  242. // These variables will be reused and accumulate factors and values
  243. Values fullinit;
  244. NonlinearFactorGraph fullgraph;
  245. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false), i);
  246. // Compare solutions
  247. EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
  248. }
  249. }
  250. /* ************************************************************************* */
  251. TEST(ISAM2, slamlike_solution_gaussnewton)
  252. {
  253. // These variables will be reused and accumulate factors and values
  254. Values fullinit;
  255. NonlinearFactorGraph fullgraph;
  256. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
  257. // Compare solutions
  258. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  259. }
  260. /* ************************************************************************* */
  261. TEST(ISAM2, slamlike_solution_dogleg)
  262. {
  263. // These variables will be reused and accumulate factors and values
  264. Values fullinit;
  265. NonlinearFactorGraph fullgraph;
  266. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false));
  267. // Compare solutions
  268. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  269. }
  270. /* ************************************************************************* */
  271. TEST(ISAM2, slamlike_solution_gaussnewton_qr)
  272. {
  273. // These variables will be reused and accumulate factors and values
  274. Values fullinit;
  275. NonlinearFactorGraph fullgraph;
  276. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, false, ISAM2Params::QR));
  277. // Compare solutions
  278. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  279. }
  280. /* ************************************************************************* */
  281. TEST(ISAM2, slamlike_solution_dogleg_qr)
  282. {
  283. // These variables will be reused and accumulate factors and values
  284. Values fullinit;
  285. NonlinearFactorGraph fullgraph;
  286. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2DoglegParams(1.0), 0.0, 0, false, false, ISAM2Params::QR));
  287. // Compare solutions
  288. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  289. }
  290. /* ************************************************************************* */
  291. TEST(ISAM2, clone) {
  292. ISAM2 clone1;
  293. {
  294. ISAM2 isam = createSlamlikeISAM2();
  295. clone1 = isam;
  296. ISAM2 clone2(isam);
  297. // Modify original isam
  298. NonlinearFactorGraph factors;
  299. factors += BetweenFactor<Pose2>(0, 10,
  300. isam.calculateEstimate<Pose2>(0).between(isam.calculateEstimate<Pose2>(10)), noiseModel::Unit::Create(3));
  301. isam.update(factors);
  302. CHECK(assert_equal(createSlamlikeISAM2(), clone2));
  303. }
  304. // This is to (perhaps unsuccessfully) try to currupt unallocated memory referenced
  305. // if the references in the iSAM2 copy point to the old instance which deleted at
  306. // the end of the {...} section above.
  307. ISAM2 temp = createSlamlikeISAM2();
  308. CHECK(assert_equal(createSlamlikeISAM2(), clone1));
  309. CHECK(assert_equal(clone1, temp));
  310. // Check clone empty
  311. ISAM2 isam;
  312. clone1 = isam;
  313. CHECK(assert_equal(ISAM2(), clone1));
  314. }
  315. /* ************************************************************************* */
  316. TEST(ISAM2, removeFactors)
  317. {
  318. // This test builds a graph in the same way as the "slamlike" test above, but
  319. // then removes the 2nd-to-last landmark measurement
  320. // These variables will be reused and accumulate factors and values
  321. Values fullinit;
  322. NonlinearFactorGraph fullgraph;
  323. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
  324. // Remove the 2nd measurement on landmark 0 (Key 100)
  325. FactorIndices toRemove;
  326. toRemove.push_back(12);
  327. isam.update(NonlinearFactorGraph(), Values(), toRemove);
  328. // Remove the factor from the full system
  329. fullgraph.remove(12);
  330. // Compare solutions
  331. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  332. }
  333. /* ************************************************************************* */
  334. TEST(ISAM2, removeVariables)
  335. {
  336. // These variables will be reused and accumulate factors and values
  337. Values fullinit;
  338. NonlinearFactorGraph fullgraph;
  339. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
  340. // Remove the measurement on landmark 0 (Key 100)
  341. FactorIndices toRemove;
  342. toRemove.push_back(7);
  343. toRemove.push_back(14);
  344. isam.update(NonlinearFactorGraph(), Values(), toRemove);
  345. // Remove the factors and variable from the full system
  346. fullgraph.remove(7);
  347. fullgraph.remove(14);
  348. fullinit.erase(100);
  349. // Compare solutions
  350. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  351. }
  352. /* ************************************************************************* */
  353. TEST(ISAM2, swapFactors)
  354. {
  355. // This test builds a graph in the same way as the "slamlike" test above, but
  356. // then swaps the 2nd-to-last landmark measurement with a different one
  357. Values fullinit;
  358. NonlinearFactorGraph fullgraph;
  359. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph);
  360. // Remove the measurement on landmark 0 and replace with a different one
  361. {
  362. size_t swap_idx = isam.getFactorsUnsafe().size()-2;
  363. FactorIndices toRemove;
  364. toRemove.push_back(swap_idx);
  365. fullgraph.remove(swap_idx);
  366. NonlinearFactorGraph swapfactors;
  367. // swapfactors += BearingRange<Pose2,Point2>(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise; // original factor
  368. swapfactors += BearingRangeFactor<Pose2,Point2>(10, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 5.0, brNoise);
  369. fullgraph.push_back(swapfactors);
  370. isam.update(swapfactors, Values(), toRemove);
  371. }
  372. // Compare solutions
  373. EXPECT(assert_equal(fullgraph, NonlinearFactorGraph(isam.getFactorsUnsafe())));
  374. EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
  375. // Check gradient at each node
  376. typedef ISAM2::sharedClique sharedClique;
  377. for(const sharedClique& clique: isam.nodes() | br::map_values) {
  378. // Compute expected gradient
  379. GaussianFactorGraph jfg;
  380. jfg += clique->conditional();
  381. VectorValues expectedGradient = jfg.gradientAtZero();
  382. // Compare with actual gradients
  383. DenseIndex variablePosition = 0;
  384. for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
  385. const DenseIndex dim = clique->conditional()->getDim(jit);
  386. Vector actual = clique->gradientContribution().segment(variablePosition, dim);
  387. EXPECT(assert_equal(expectedGradient[*jit], actual));
  388. variablePosition += dim;
  389. }
  390. EXPECT_LONGS_EQUAL((long)clique->gradientContribution().rows(), (long)variablePosition);
  391. }
  392. // Check gradient
  393. VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
  394. VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
  395. VectorValues actualGradient = isam.gradientAtZero();
  396. EXPECT(assert_equal(expectedGradient2, expectedGradient));
  397. EXPECT(assert_equal(expectedGradient, actualGradient));
  398. }
  399. /* ************************************************************************* */
  400. TEST(ISAM2, constrained_ordering)
  401. {
  402. // These variables will be reused and accumulate factors and values
  403. ISAM2 isam(ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false));
  404. Values fullinit;
  405. NonlinearFactorGraph fullgraph;
  406. // We will constrain x3 and x4 to the end
  407. FastMap<Key, int> constrained;
  408. constrained.insert(make_pair((3), 1));
  409. constrained.insert(make_pair((4), 2));
  410. // i keeps track of the time step
  411. size_t i = 0;
  412. // Add a prior at time 0 and update isam
  413. {
  414. NonlinearFactorGraph newfactors;
  415. newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
  416. fullgraph.push_back(newfactors);
  417. Values init;
  418. init.insert((0), Pose2(0.01, 0.01, 0.01));
  419. fullinit.insert((0), Pose2(0.01, 0.01, 0.01));
  420. isam.update(newfactors, init);
  421. }
  422. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  423. // Add odometry from time 0 to time 5
  424. for( ; i<5; ++i) {
  425. NonlinearFactorGraph newfactors;
  426. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  427. fullgraph.push_back(newfactors);
  428. Values init;
  429. init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  430. fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  431. if(i >= 3)
  432. isam.update(newfactors, init, FactorIndices(), constrained);
  433. else
  434. isam.update(newfactors, init);
  435. }
  436. // Add odometry from time 5 to 6 and landmark measurement at time 5
  437. {
  438. NonlinearFactorGraph newfactors;
  439. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  440. newfactors += BearingRangeFactor<Pose2,Point2>(i, 100, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
  441. newfactors += BearingRangeFactor<Pose2,Point2>(i, 101, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
  442. fullgraph.push_back(newfactors);
  443. Values init;
  444. init.insert((i+1), Pose2(1.01, 0.01, 0.01));
  445. init.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
  446. init.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
  447. fullinit.insert((i+1), Pose2(1.01, 0.01, 0.01));
  448. fullinit.insert(100, Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
  449. fullinit.insert(101, Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
  450. isam.update(newfactors, init, FactorIndices(), constrained);
  451. ++ i;
  452. }
  453. // Add odometry from time 6 to time 10
  454. for( ; i<10; ++i) {
  455. NonlinearFactorGraph newfactors;
  456. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  457. fullgraph.push_back(newfactors);
  458. Values init;
  459. init.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  460. fullinit.insert((i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
  461. isam.update(newfactors, init, FactorIndices(), constrained);
  462. }
  463. // Add odometry from time 10 to 11 and landmark measurement at time 10
  464. {
  465. NonlinearFactorGraph newfactors;
  466. newfactors += BetweenFactor<Pose2>(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
  467. newfactors += BearingRangeFactor<Pose2,Point2>(i, 100, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
  468. newfactors += BearingRangeFactor<Pose2,Point2>(i, 101, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
  469. fullgraph.push_back(newfactors);
  470. Values init;
  471. init.insert((i+1), Pose2(6.9, 0.1, 0.01));
  472. fullinit.insert((i+1), Pose2(6.9, 0.1, 0.01));
  473. isam.update(newfactors, init, FactorIndices(), constrained);
  474. ++ i;
  475. }
  476. // Compare solutions
  477. EXPECT(isam_check(fullgraph, fullinit, isam, *this, result_));
  478. // Check gradient at each node
  479. typedef ISAM2::sharedClique sharedClique;
  480. for(const sharedClique& clique: isam.nodes() | br::map_values) {
  481. // Compute expected gradient
  482. GaussianFactorGraph jfg;
  483. jfg += clique->conditional();
  484. VectorValues expectedGradient = jfg.gradientAtZero();
  485. // Compare with actual gradients
  486. DenseIndex variablePosition = 0;
  487. for(GaussianConditional::const_iterator jit = clique->conditional()->begin(); jit != clique->conditional()->end(); ++jit) {
  488. const DenseIndex dim = clique->conditional()->getDim(jit);
  489. Vector actual = clique->gradientContribution().segment(variablePosition, dim);
  490. EXPECT(assert_equal(expectedGradient[*jit], actual));
  491. variablePosition += dim;
  492. }
  493. LONGS_EQUAL((long)clique->gradientContribution().rows(), (long)variablePosition);
  494. }
  495. // Check gradient
  496. VectorValues expectedGradient = GaussianFactorGraph(isam).gradientAtZero();
  497. VectorValues expectedGradient2 = GaussianFactorGraph(isam).gradient(VectorValues::Zero(expectedGradient));
  498. VectorValues actualGradient = isam.gradientAtZero();
  499. EXPECT(assert_equal(expectedGradient2, expectedGradient));
  500. EXPECT(assert_equal(expectedGradient, actualGradient));
  501. }
  502. /* ************************************************************************* */
  503. TEST(ISAM2, slamlike_solution_partial_relinearization_check)
  504. {
  505. // These variables will be reused and accumulate factors and values
  506. Values fullinit;
  507. NonlinearFactorGraph fullgraph;
  508. ISAM2Params params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false);
  509. params.enablePartialRelinearizationCheck = true;
  510. ISAM2 isam = createSlamlikeISAM2(fullinit, fullgraph, params);
  511. // Compare solutions
  512. CHECK(isam_check(fullgraph, fullinit, isam, *this, result_));
  513. }
  514. namespace {
  515. bool checkMarginalizeLeaves(ISAM2& isam, const FastList<Key>& leafKeys) {
  516. Matrix expectedAugmentedHessian, expected3AugmentedHessian;
  517. KeyVector toKeep;
  518. for(Key j: isam.getDelta() | br::map_keys)
  519. if(find(leafKeys.begin(), leafKeys.end(), j) == leafKeys.end())
  520. toKeep.push_back(j);
  521. // Calculate expected marginal from iSAM2 tree
  522. expectedAugmentedHessian = GaussianFactorGraph(isam).marginal(toKeep, EliminateQR)->augmentedHessian();
  523. // Calculate expected marginal from cached linear factors
  524. //assert(isam.params().cacheLinearizedFactors);
  525. //Matrix expected2AugmentedHessian = isam.linearFactors_.marginal(toKeep, EliminateQR)->augmentedHessian();
  526. // Calculate expected marginal from original nonlinear factors
  527. expected3AugmentedHessian = isam.getFactorsUnsafe().linearize(isam.getLinearizationPoint())
  528. ->marginal(toKeep, EliminateQR)->augmentedHessian();
  529. // Do marginalization
  530. isam.marginalizeLeaves(leafKeys);
  531. // Check
  532. GaussianFactorGraph actualMarginalGraph(isam);
  533. Matrix actualAugmentedHessian = actualMarginalGraph.augmentedHessian();
  534. //Matrix actual2AugmentedHessian = linearFactors_.augmentedHessian();
  535. Matrix actual3AugmentedHessian = isam.getFactorsUnsafe().linearize(
  536. isam.getLinearizationPoint())->augmentedHessian();
  537. assert(actualAugmentedHessian.allFinite());
  538. // Check full marginalization
  539. //cout << "treeEqual" << endl;
  540. bool treeEqual = assert_equal(expectedAugmentedHessian, actualAugmentedHessian, 1e-6);
  541. //actualAugmentedHessian.bottomRightCorner(1,1) = expected2AugmentedHessian.bottomRightCorner(1,1); bool linEqual = assert_equal(expected2AugmentedHessian, actualAugmentedHessian, 1e-6);
  542. //cout << "nonlinEqual" << endl;
  543. actualAugmentedHessian.bottomRightCorner(1,1) = expected3AugmentedHessian.bottomRightCorner(1,1); bool nonlinEqual = assert_equal(expected3AugmentedHessian, actualAugmentedHessian, 1e-6);
  544. //bool linCorrect = assert_equal(expected3AugmentedHessian, expected2AugmentedHessian, 1e-6);
  545. //actual2AugmentedHessian.bottomRightCorner(1,1) = expected3AugmentedHessian.bottomRightCorner(1,1); bool afterLinCorrect = assert_equal(expected3AugmentedHessian, actual2AugmentedHessian, 1e-6);
  546. //cout << "nonlinCorrect" << endl;
  547. bool afterNonlinCorrect = assert_equal(expected3AugmentedHessian, actual3AugmentedHessian, 1e-6);
  548. bool ok = treeEqual && /*linEqual &&*/ nonlinEqual && /*linCorrect &&*/ /*afterLinCorrect &&*/ afterNonlinCorrect;
  549. return ok;
  550. }
  551. }
  552. /* ************************************************************************* */
  553. TEST(ISAM2, marginalizeLeaves1) {
  554. ISAM2 isam;
  555. NonlinearFactorGraph factors;
  556. factors.addPrior(0, 0.0, model);
  557. factors += BetweenFactor<double>(0, 1, 0.0, model);
  558. factors += BetweenFactor<double>(1, 2, 0.0, model);
  559. factors += BetweenFactor<double>(0, 2, 0.0, model);
  560. Values values;
  561. values.insert(0, 0.0);
  562. values.insert(1, 0.0);
  563. values.insert(2, 0.0);
  564. FastMap<Key, int> constrainedKeys;
  565. constrainedKeys.insert(make_pair(0, 0));
  566. constrainedKeys.insert(make_pair(1, 1));
  567. constrainedKeys.insert(make_pair(2, 2));
  568. isam.update(factors, values, FactorIndices(), constrainedKeys);
  569. FastList<Key> leafKeys = list_of(0);
  570. EXPECT(checkMarginalizeLeaves(isam, leafKeys));
  571. }
  572. /* ************************************************************************* */
  573. TEST(ISAM2, marginalizeLeaves2) {
  574. ISAM2 isam;
  575. NonlinearFactorGraph factors;
  576. factors.addPrior(0, 0.0, model);
  577. factors += BetweenFactor<double>(0, 1, 0.0, model);
  578. factors += BetweenFactor<double>(1, 2, 0.0, model);
  579. factors += BetweenFactor<double>(0, 2, 0.0, model);
  580. factors += BetweenFactor<double>(2, 3, 0.0, model);
  581. Values values;
  582. values.insert(0, 0.0);
  583. values.insert(1, 0.0);
  584. values.insert(2, 0.0);
  585. values.insert(3, 0.0);
  586. FastMap<Key, int> constrainedKeys;
  587. constrainedKeys.insert(make_pair(0, 0));
  588. constrainedKeys.insert(make_pair(1, 1));
  589. constrainedKeys.insert(make_pair(2, 2));
  590. constrainedKeys.insert(make_pair(3, 3));
  591. isam.update(factors, values, FactorIndices(), constrainedKeys);
  592. FastList<Key> leafKeys = list_of(0);
  593. EXPECT(checkMarginalizeLeaves(isam, leafKeys));
  594. }
  595. /* ************************************************************************* */
  596. TEST(ISAM2, marginalizeLeaves3) {
  597. ISAM2 isam;
  598. NonlinearFactorGraph factors;
  599. factors.addPrior(0, 0.0, model);
  600. factors += BetweenFactor<double>(0, 1, 0.0, model);
  601. factors += BetweenFactor<double>(1, 2, 0.0, model);
  602. factors += BetweenFactor<double>(0, 2, 0.0, model);
  603. factors += BetweenFactor<double>(2, 3, 0.0, model);
  604. factors += BetweenFactor<double>(3, 4, 0.0, model);
  605. factors += BetweenFactor<double>(4, 5, 0.0, model);
  606. factors += BetweenFactor<double>(3, 5, 0.0, model);
  607. Values values;
  608. values.insert(0, 0.0);
  609. values.insert(1, 0.0);
  610. values.insert(2, 0.0);
  611. values.insert(3, 0.0);
  612. values.insert(4, 0.0);
  613. values.insert(5, 0.0);
  614. FastMap<Key, int> constrainedKeys;
  615. constrainedKeys.insert(make_pair(0, 0));
  616. constrainedKeys.insert(make_pair(1, 1));
  617. constrainedKeys.insert(make_pair(2, 2));
  618. constrainedKeys.insert(make_pair(3, 3));
  619. constrainedKeys.insert(make_pair(4, 4));
  620. constrainedKeys.insert(make_pair(5, 5));
  621. isam.update(factors, values, FactorIndices(), constrainedKeys);
  622. FastList<Key> leafKeys = list_of(0);
  623. EXPECT(checkMarginalizeLeaves(isam, leafKeys));
  624. }
  625. /* ************************************************************************* */
  626. TEST(ISAM2, marginalizeLeaves4) {
  627. ISAM2 isam;
  628. NonlinearFactorGraph factors;
  629. factors.addPrior(0, 0.0, model);
  630. factors += BetweenFactor<double>(0, 2, 0.0, model);
  631. factors += BetweenFactor<double>(1, 2, 0.0, model);
  632. Values values;
  633. values.insert(0, 0.0);
  634. values.insert(1, 0.0);
  635. values.insert(2, 0.0);
  636. FastMap<Key, int> constrainedKeys;
  637. constrainedKeys.insert(make_pair(0, 0));
  638. constrainedKeys.insert(make_pair(1, 1));
  639. constrainedKeys.insert(make_pair(2, 2));
  640. isam.update(factors, values, FactorIndices(), constrainedKeys);
  641. FastList<Key> leafKeys = list_of(1);
  642. EXPECT(checkMarginalizeLeaves(isam, leafKeys));
  643. }
  644. /* ************************************************************************* */
  645. TEST(ISAM2, marginalizeLeaves5)
  646. {
  647. // Create isam2
  648. ISAM2 isam = createSlamlikeISAM2();
  649. // Marginalize
  650. FastList<Key> marginalizeKeys = list_of(0);
  651. EXPECT(checkMarginalizeLeaves(isam, marginalizeKeys));
  652. }
  653. /* ************************************************************************* */
  654. TEST(ISAM2, marginalCovariance)
  655. {
  656. // Create isam2
  657. ISAM2 isam = createSlamlikeISAM2();
  658. // Check marginal
  659. Matrix expected = Marginals(isam.getFactorsUnsafe(), isam.getLinearizationPoint()).marginalCovariance(5);
  660. Matrix actual = isam.marginalCovariance(5);
  661. EXPECT(assert_equal(expected, actual));
  662. }
  663. /* ************************************************************************* */
  664. TEST(ISAM2, calculate_nnz)
  665. {
  666. ISAM2 isam = createSlamlikeISAM2();
  667. int expected = 241;
  668. int actual = isam.roots().front()->calculate_nnz();
  669. EXPECT_LONGS_EQUAL(expected, actual);
  670. }
  671. /* ************************************************************************* */
  672. int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
  673. /* ************************************************************************* */