Pose2SLAMExample.cpp 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128
  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 Pose2SLAMExample.cpp
  10. * @brief A 2D Pose SLAM example
  11. * @date Oct 21, 2010
  12. * @author Yong Dian Jian
  13. */
  14. /**
  15. * A simple 2D pose slam example
  16. * - The robot moves in a 2 meter square
  17. * - The robot moves 2 meters each step, turning 90 degrees after each step
  18. * - The robot initially faces along the X axis (horizontal, to the right in 2D)
  19. * - We have full odometry between pose
  20. * - We have a loop closure constraint when the robot returns to the first position
  21. */
  22. // In planar SLAM example we use Pose2 variables (x, y, theta) to represent the robot poses
  23. #include <gtsam/geometry/Pose2.h>
  24. // We will use simple integer Keys to refer to the robot poses.
  25. #include <gtsam/inference/Key.h>
  26. // In GTSAM, measurement functions are represented as 'factors'. Several common factors
  27. // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
  28. // Here we will use Between factors for the relative motion described by odometry measurements.
  29. // We will also use a Between Factor to encode the loop closure constraint
  30. // Also, we will initialize the robot at the origin using a Prior factor.
  31. #include <gtsam/slam/BetweenFactor.h>
  32. // When the factors are created, we will add them to a Factor Graph. As the factors we are using
  33. // are nonlinear factors, we will need a Nonlinear Factor Graph.
  34. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  35. // Finally, once all of the factors have been added to our factor graph, we will want to
  36. // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
  37. // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
  38. // a Gauss-Newton solver
  39. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  40. // Once the optimized values have been calculated, we can also calculate the marginal covariance
  41. // of desired variables
  42. #include <gtsam/nonlinear/Marginals.h>
  43. // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
  44. // nonlinear functions around an initial linearization point, then solve the linear system
  45. // to update the linearization point. This happens repeatedly until the solver converges
  46. // to a consistent set of variable values. This requires us to specify an initial guess
  47. // for each variable, held in a Values container.
  48. #include <gtsam/nonlinear/Values.h>
  49. using namespace std;
  50. using namespace gtsam;
  51. int main(int argc, char** argv) {
  52. // 1. Create a factor graph container and add factors to it
  53. NonlinearFactorGraph graph;
  54. // 2a. Add a prior on the first pose, setting it to the origin
  55. // A prior factor consists of a mean and a noise model (covariance matrix)
  56. auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
  57. graph.addPrior(1, Pose2(0, 0, 0), priorNoise);
  58. // For simplicity, we will use the same noise model for odometry and loop closures
  59. auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  60. // 2b. Add odometry factors
  61. // Create odometry (Between) factors between consecutive poses
  62. graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2, 0, 0), model);
  63. graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2, 0, M_PI_2), model);
  64. graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2, 0, M_PI_2), model);
  65. graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2, 0, M_PI_2), model);
  66. // 2c. Add the loop closure constraint
  67. // This factor encodes the fact that we have returned to the same pose. In real systems,
  68. // these constraints may be identified in many ways, such as appearance-based techniques
  69. // with camera images. We will use another Between Factor to enforce this constraint:
  70. graph.emplace_shared<BetweenFactor<Pose2> >(5, 2, Pose2(2, 0, M_PI_2), model);
  71. graph.print("\nFactor Graph:\n"); // print
  72. // 3. Create the data structure to hold the initialEstimate estimate to the solution
  73. // For illustrative purposes, these have been deliberately set to incorrect values
  74. Values initialEstimate;
  75. initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
  76. initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2));
  77. initialEstimate.insert(3, Pose2(4.1, 0.1, M_PI_2));
  78. initialEstimate.insert(4, Pose2(4.0, 2.0, M_PI));
  79. initialEstimate.insert(5, Pose2(2.1, 2.1, -M_PI_2));
  80. initialEstimate.print("\nInitial Estimate:\n"); // print
  81. // 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer
  82. // The optimizer accepts an optional set of configuration parameters,
  83. // controlling things like convergence criteria, the type of linear
  84. // system solver to use, and the amount of information displayed during
  85. // optimization. We will set a few parameters as a demonstration.
  86. GaussNewtonParams parameters;
  87. // Stop iterating once the change in error between steps is less than this value
  88. parameters.relativeErrorTol = 1e-5;
  89. // Do not perform more than N iteration steps
  90. parameters.maxIterations = 100;
  91. // Create the optimizer ...
  92. GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters);
  93. // ... and optimize
  94. Values result = optimizer.optimize();
  95. result.print("Final Result:\n");
  96. // 5. Calculate and print marginal covariances for all variables
  97. cout.precision(3);
  98. Marginals marginals(graph, result);
  99. cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl;
  100. cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl;
  101. cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl;
  102. cout << "x4 covariance:\n" << marginals.marginalCovariance(4) << endl;
  103. cout << "x5 covariance:\n" << marginals.marginalCovariance(5) << endl;
  104. return 0;
  105. }