VisualISAM2Example.cpp 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145
  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 VisualISAM2Example.cpp
  10. * @brief A visualSLAM example for the structure-from-motion problem on a
  11. * simulated dataset This version uses iSAM2 to solve the problem incrementally
  12. * @author Duy-Nguyen Ta
  13. */
  14. /**
  15. * A structure-from-motion example with landmarks
  16. * - The landmarks form a 10 meter cube
  17. * - The robot rotates around the landmarks, always facing towards the cube
  18. */
  19. // For loading the data
  20. #include "SFMdata.h"
  21. // Camera observations of landmarks will be stored as Point2 (x, y).
  22. #include <gtsam/geometry/Point2.h>
  23. // Each variable in the system (poses and landmarks) must be identified with a
  24. // unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols
  25. // (X1, X2, L1). Here we will use Symbols
  26. #include <gtsam/inference/Symbol.h>
  27. // We want to use iSAM2 to solve the structure-from-motion problem
  28. // incrementally, so include iSAM2 here
  29. #include <gtsam/nonlinear/ISAM2.h>
  30. // iSAM2 requires as input a set of new factors to be added stored in a factor
  31. // graph, and initial guesses for any new variables used in the added factors
  32. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  33. #include <gtsam/nonlinear/Values.h>
  34. // In GTSAM, measurement functions are represented as 'factors'. Several common
  35. // factors have been provided with the library for solving robotics/SLAM/Bundle
  36. // Adjustment problems. Here we will use Projection factors to model the
  37. // camera's landmark observations. Also, we will initialize the robot at some
  38. // location using a Prior factor.
  39. #include <gtsam/slam/ProjectionFactor.h>
  40. #include <vector>
  41. using namespace std;
  42. using namespace gtsam;
  43. /* ************************************************************************* */
  44. int main(int argc, char* argv[]) {
  45. // Define the camera calibration parameters
  46. Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
  47. // Define the camera observation noise model, 1 pixel stddev
  48. auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
  49. // Create the set of ground-truth landmarks
  50. vector<Point3> points = createPoints();
  51. // Create the set of ground-truth poses
  52. vector<Pose3> poses = createPoses();
  53. // Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps
  54. // to maintain proper linearization and efficient variable ordering, iSAM2
  55. // performs partial relinearization/reordering at each step. A parameter
  56. // structure is available that allows the user to set various properties, such
  57. // as the relinearization threshold and type of linear solver. For this
  58. // example, we we set the relinearization threshold small so the iSAM2 result
  59. // will approach the batch result.
  60. ISAM2Params parameters;
  61. parameters.relinearizeThreshold = 0.01;
  62. parameters.relinearizeSkip = 1;
  63. ISAM2 isam(parameters);
  64. // Create a Factor Graph and Values to hold the new data
  65. NonlinearFactorGraph graph;
  66. Values initialEstimate;
  67. // Loop over the poses, adding the observations to iSAM incrementally
  68. for (size_t i = 0; i < poses.size(); ++i) {
  69. // Add factors for each landmark observation
  70. for (size_t j = 0; j < points.size(); ++j) {
  71. PinholeCamera<Cal3_S2> camera(poses[i], *K);
  72. Point2 measurement = camera.project(points[j]);
  73. graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(
  74. measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
  75. }
  76. // Add an initial guess for the current pose
  77. // Intentionally initialize the variables off from the ground truth
  78. static Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
  79. Point3(0.05, -0.10, 0.20));
  80. initialEstimate.insert(Symbol('x', i), poses[i] * kDeltaPose);
  81. // If this is the first iteration, add a prior on the first pose to set the
  82. // coordinate frame and a prior on the first landmark to set the scale Also,
  83. // as iSAM solves incrementally, we must wait until each is observed at
  84. // least twice before adding it to iSAM.
  85. if (i == 0) {
  86. // Add a prior on pose x0, 30cm std on x,y,z and 0.1 rad on roll,pitch,yaw
  87. static auto kPosePrior = noiseModel::Diagonal::Sigmas(
  88. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
  89. .finished());
  90. graph.addPrior(Symbol('x', 0), poses[0], kPosePrior);
  91. // Add a prior on landmark l0
  92. static auto kPointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
  93. graph.addPrior(Symbol('l', 0), points[0], kPointPrior);
  94. // Add initial guesses to all observed landmarks
  95. // Intentionally initialize the variables off from the ground truth
  96. static Point3 kDeltaPoint(-0.25, 0.20, 0.15);
  97. for (size_t j = 0; j < points.size(); ++j)
  98. initialEstimate.insert<Point3>(Symbol('l', j), points[j] + kDeltaPoint);
  99. } else {
  100. // Update iSAM with the new factors
  101. isam.update(graph, initialEstimate);
  102. // Each call to iSAM2 update(*) performs one iteration of the iterative
  103. // nonlinear solver. If accuracy is desired at the expense of time,
  104. // update(*) can be called additional times to perform multiple optimizer
  105. // iterations every step.
  106. isam.update();
  107. Values currentEstimate = isam.calculateEstimate();
  108. cout << "****************************************************" << endl;
  109. cout << "Frame " << i << ": " << endl;
  110. currentEstimate.print("Current estimate: ");
  111. // Clear the factor graph and values for the next iteration
  112. graph.resize(0);
  113. initialEstimate.clear();
  114. }
  115. }
  116. return 0;
  117. }
  118. /* ************************************************************************* */