testVisualISAM2.cpp 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124
  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 testVisualISAM2.cpp
  10. * @brief Test convergence of visualSLAM example.
  11. * @author Duy-Nguyen Ta
  12. * @author Frank Dellaert
  13. */
  14. #include <CppUnitLite/TestHarness.h>
  15. #include <examples/SFMdata.h>
  16. #include <gtsam/geometry/Point2.h>
  17. #include <gtsam/inference/Symbol.h>
  18. #include <gtsam/nonlinear/ISAM2.h>
  19. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  20. #include <gtsam/nonlinear/Values.h>
  21. #include <gtsam/slam/ProjectionFactor.h>
  22. #include <vector>
  23. using namespace std;
  24. using namespace gtsam;
  25. /* ************************************************************************* */
  26. TEST(testVisualISAM2, all)
  27. {
  28. Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
  29. auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
  30. // Create ground truth data
  31. vector<Point3> points = createPoints();
  32. vector<Pose3> poses = createPoses();
  33. // Set the parameters
  34. ISAM2Params parameters;
  35. parameters.relinearizeThreshold = 0.01;
  36. parameters.relinearizeSkip = 1;
  37. ISAM2 isam(parameters);
  38. // Create a Factor Graph and Values to hold the new data
  39. NonlinearFactorGraph graph;
  40. Values initialEstimate;
  41. // Loop over the poses, adding the observations to iSAM incrementally
  42. for (size_t i = 0; i < poses.size(); ++i)
  43. {
  44. // Add factors for each landmark observation
  45. for (size_t j = 0; j < points.size(); ++j)
  46. {
  47. PinholeCamera<Cal3_S2> camera(poses[i], *K);
  48. Point2 measurement = camera.project(points[j]);
  49. graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2>>(
  50. measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
  51. }
  52. // Add an initial guess for the current pose
  53. // Intentionally initialize the variables off from the ground truth
  54. static Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
  55. Point3(0.05, -0.10, 0.20));
  56. initialEstimate.insert(Symbol('x', i), poses[i] * kDeltaPose);
  57. // Treat first iteration as special case
  58. if (i == 0)
  59. {
  60. // Add a prior on pose x0, 30cm std on x,y,z and 0.1 rad on roll,pitch,yaw
  61. static auto kPosePrior = noiseModel::Diagonal::Sigmas(
  62. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
  63. .finished());
  64. graph.addPrior(Symbol('x', 0), poses[0], kPosePrior);
  65. // Add a prior on landmark l0
  66. static auto kPointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
  67. graph.addPrior(Symbol('l', 0), points[0], kPointPrior);
  68. // Add initial guesses to all observed landmarks
  69. // Intentionally initialize the variables off from the ground truth
  70. static Point3 kDeltaPoint(-0.25, 0.20, 0.15);
  71. for (size_t j = 0; j < points.size(); ++j)
  72. initialEstimate.insert<Point3>(Symbol('l', j), points[j] + kDeltaPoint);
  73. }
  74. else
  75. {
  76. // Update iSAM with the new factors
  77. isam.update(graph, initialEstimate);
  78. // Do an extra update to converge withing these 8 iterations
  79. isam.update();
  80. // Optimize
  81. Values currentEstimate = isam.calculateEstimate();
  82. // reset for next iteration
  83. graph.resize(0);
  84. initialEstimate.clear();
  85. }
  86. } // for loop
  87. auto result = isam.calculateEstimate();
  88. EXPECT_LONGS_EQUAL(16, result.size());
  89. for (size_t j = 0; j < points.size(); ++j)
  90. {
  91. Symbol key('l', j);
  92. EXPECT(assert_equal(points[j], result.at<Point3>(key), 0.01));
  93. }
  94. }
  95. /* ************************************************************************* */
  96. int main()
  97. {
  98. TestResult tr;
  99. return TestRegistry::runAllTests(tr);
  100. }
  101. /* ************************************************************************* */