VisualISAMExample.cpp 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138
  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 VisualISAMExample.cpp
  10. * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset
  11. * This version uses iSAM to solve the problem incrementally
  12. * @author Duy-Nguyen Ta
  13. * @author Frank Dellaert
  14. */
  15. /**
  16. * A structure-from-motion example with landmarks
  17. * - The landmarks form a 10 meter cube
  18. * - The robot rotates around the landmarks, always facing towards the cube
  19. */
  20. // For loading the data
  21. #include "SFMdata.h"
  22. // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
  23. #include <gtsam/geometry/Point2.h>
  24. // Each variable in the system (poses and landmarks) must be identified with a unique key.
  25. // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
  26. // Here we will use Symbols
  27. #include <gtsam/inference/Symbol.h>
  28. // In GTSAM, measurement functions are represented as 'factors'. Several common factors
  29. // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
  30. // Here we will use Projection factors to model the camera's landmark observations.
  31. // Also, we will initialize the robot at some location using a Prior factor.
  32. #include <gtsam/slam/ProjectionFactor.h>
  33. // We want to use iSAM to solve the structure-from-motion problem incrementally, so
  34. // include iSAM here
  35. #include <gtsam/nonlinear/NonlinearISAM.h>
  36. // iSAM requires as input a set set of new factors to be added stored in a factor graph,
  37. // and initial guesses for any new variables used in the added factors
  38. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  39. #include <gtsam/nonlinear/Values.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
  48. auto noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  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 a NonlinearISAM object which will relinearize and reorder the variables
  54. // every "relinearizeInterval" updates
  55. int relinearizeInterval = 3;
  56. NonlinearISAM isam(relinearizeInterval);
  57. // Create a Factor Graph and Values to hold the new data
  58. NonlinearFactorGraph graph;
  59. Values initialEstimate;
  60. // Loop over the different poses, adding the observations to iSAM incrementally
  61. for (size_t i = 0; i < poses.size(); ++i) {
  62. // Add factors for each landmark observation
  63. for (size_t j = 0; j < points.size(); ++j) {
  64. // Create ground truth measurement
  65. PinholeCamera<Cal3_S2> camera(poses[i], *K);
  66. Point2 measurement = camera.project(points[j]);
  67. // Add measurement
  68. graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(measurement, noise,
  69. Symbol('x', i), Symbol('l', j), K);
  70. }
  71. // Intentionally initialize the variables off from the ground truth
  72. Pose3 noise(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
  73. Pose3 initial_xi = poses[i].compose(noise);
  74. // Add an initial guess for the current pose
  75. initialEstimate.insert(Symbol('x', i), initial_xi);
  76. // If this is the first iteration, add a prior on the first pose to set the coordinate frame
  77. // and a prior on the first landmark to set the scale
  78. // Also, as iSAM solves incrementally, we must wait until each is observed at least twice before
  79. // adding it to iSAM.
  80. if (i == 0) {
  81. // Add a prior on pose x0, with 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
  82. auto poseNoise = noiseModel::Diagonal::Sigmas(
  83. (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
  84. graph.addPrior(Symbol('x', 0), poses[0], poseNoise);
  85. // Add a prior on landmark l0
  86. auto pointNoise =
  87. noiseModel::Isotropic::Sigma(3, 0.1);
  88. graph.addPrior(Symbol('l', 0), points[0], pointNoise);
  89. // Add initial guesses to all observed landmarks
  90. Point3 noise(-0.25, 0.20, 0.15);
  91. for (size_t j = 0; j < points.size(); ++j) {
  92. // Intentionally initialize the variables off from the ground truth
  93. Point3 initial_lj = points[j] + noise;
  94. initialEstimate.insert(Symbol('l', j), initial_lj);
  95. }
  96. } else {
  97. // Update iSAM with the new factors
  98. isam.update(graph, initialEstimate);
  99. Values currentEstimate = isam.estimate();
  100. cout << "****************************************************" << endl;
  101. cout << "Frame " << i << ": " << endl;
  102. currentEstimate.print("Current estimate: ");
  103. // Clear the factor graph and values for the next iteration
  104. graph.resize(0);
  105. initialEstimate.clear();
  106. }
  107. }
  108. return 0;
  109. }
  110. /* ************************************************************************* */