PlanarSLAMExample.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  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 PlanarSLAMExample.cpp
  10. * @brief Simple robotics example using odometry measurements and bearing-range (laser) measurements
  11. * @author Alex Cunningham
  12. */
  13. /**
  14. * A simple 2D planar slam example with landmarks
  15. * - The robot and landmarks are on a 2 meter grid
  16. * - Robot poses are facing along the X axis (horizontal, to the right in 2D)
  17. * - The robot moves 2 meters each step
  18. * - We have full odometry between poses
  19. * - We have bearing and range information for measurements
  20. * - Landmarks are 2 meters away from the robot trajectory
  21. */
  22. // As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent
  23. // the robot positions and Point2 variables (x, y) to represent the landmark coordinates.
  24. #include <gtsam/geometry/Pose2.h>
  25. #include <gtsam/geometry/Point2.h>
  26. // Each variable in the system (poses and landmarks) must be identified with a unique key.
  27. // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
  28. // Here we will use Symbols
  29. #include <gtsam/inference/Symbol.h>
  30. // In GTSAM, measurement functions are represented as 'factors'. Several common factors
  31. // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
  32. // Here we will use a RangeBearing factor for the range-bearing measurements to identified
  33. // landmarks, and Between factors for the relative motion described by odometry measurements.
  34. // Also, we will initialize the robot at the origin using a Prior factor.
  35. #include <gtsam/slam/BetweenFactor.h>
  36. #include <gtsam/sam/BearingRangeFactor.h>
  37. // When the factors are created, we will add them to a Factor Graph. As the factors we are using
  38. // are nonlinear factors, we will need a Nonlinear Factor Graph.
  39. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  40. // Finally, once all of the factors have been added to our factor graph, we will want to
  41. // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
  42. // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
  43. // common Levenberg-Marquardt solver
  44. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  45. // Once the optimized values have been calculated, we can also calculate the marginal covariance
  46. // of desired variables
  47. #include <gtsam/nonlinear/Marginals.h>
  48. // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
  49. // nonlinear functions around an initial linearization point, then solve the linear system
  50. // to update the linearization point. This happens repeatedly until the solver converges
  51. // to a consistent set of variable values. This requires us to specify an initial guess
  52. // for each variable, held in a Values container.
  53. #include <gtsam/nonlinear/Values.h>
  54. using namespace std;
  55. using namespace gtsam;
  56. int main(int argc, char** argv) {
  57. // Create a factor graph
  58. NonlinearFactorGraph graph;
  59. // Create the keys we need for this simple example
  60. static Symbol x1('x', 1), x2('x', 2), x3('x', 3);
  61. static Symbol l1('l', 1), l2('l', 2);
  62. // Add a prior on pose x1 at the origin. A prior factor consists of a mean and
  63. // a noise model (covariance matrix)
  64. Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
  65. auto priorNoise = noiseModel::Diagonal::Sigmas(
  66. Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
  67. graph.addPrior(x1, prior, priorNoise); // add directly to graph
  68. // Add two odometry factors
  69. Pose2 odometry(2.0, 0.0, 0.0);
  70. // create a measurement for both factors (the same in this case)
  71. auto odometryNoise = noiseModel::Diagonal::Sigmas(
  72. Vector3(0.2, 0.2, 0.1)); // 20cm std on x,y, 0.1 rad on theta
  73. graph.emplace_shared<BetweenFactor<Pose2> >(x1, x2, odometry, odometryNoise);
  74. graph.emplace_shared<BetweenFactor<Pose2> >(x2, x3, odometry, odometryNoise);
  75. // Add Range-Bearing measurements to two different landmarks
  76. // create a noise model for the landmark measurements
  77. auto measurementNoise = noiseModel::Diagonal::Sigmas(
  78. Vector2(0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range
  79. // create the measurement values - indices are (pose id, landmark id)
  80. Rot2 bearing11 = Rot2::fromDegrees(45), bearing21 = Rot2::fromDegrees(90),
  81. bearing32 = Rot2::fromDegrees(90);
  82. double range11 = std::sqrt(4.0 + 4.0), range21 = 2.0, range32 = 2.0;
  83. // Add Bearing-Range factors
  84. graph.emplace_shared<BearingRangeFactor<Pose2, Point2> >(x1, l1, bearing11, range11, measurementNoise);
  85. graph.emplace_shared<BearingRangeFactor<Pose2, Point2> >(x2, l1, bearing21, range21, measurementNoise);
  86. graph.emplace_shared<BearingRangeFactor<Pose2, Point2> >(x3, l2, bearing32, range32, measurementNoise);
  87. // Print
  88. graph.print("Factor Graph:\n");
  89. // Create (deliberately inaccurate) initial estimate
  90. Values initialEstimate;
  91. initialEstimate.insert(x1, Pose2(0.5, 0.0, 0.2));
  92. initialEstimate.insert(x2, Pose2(2.3, 0.1, -0.2));
  93. initialEstimate.insert(x3, Pose2(4.1, 0.1, 0.1));
  94. initialEstimate.insert(l1, Point2(1.8, 2.1));
  95. initialEstimate.insert(l2, Point2(4.1, 1.8));
  96. // Print
  97. initialEstimate.print("Initial Estimate:\n");
  98. // Optimize using Levenberg-Marquardt optimization. The optimizer
  99. // accepts an optional set of configuration parameters, controlling
  100. // things like convergence criteria, the type of linear system solver
  101. // to use, and the amount of information displayed during optimization.
  102. // Here we will use the default set of parameters. See the
  103. // documentation for the full set of parameters.
  104. LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
  105. Values result = optimizer.optimize();
  106. result.print("Final Result:\n");
  107. // Calculate and print marginal covariances for all variables
  108. Marginals marginals(graph, result);
  109. print(marginals.marginalCovariance(x1), "x1 covariance");
  110. print(marginals.marginalCovariance(x2), "x2 covariance");
  111. print(marginals.marginalCovariance(x3), "x3 covariance");
  112. print(marginals.marginalCovariance(l1), "l1 covariance");
  113. print(marginals.marginalCovariance(l2), "l2 covariance");
  114. return 0;
  115. }