OdometryExample.cpp 4.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697
  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 OdometryExample.cpp
  10. * @brief Simple robot motion example, with prior and two odometry measurements
  11. * @author Frank Dellaert
  12. */
  13. /**
  14. * Example of a simple 2D localization example
  15. * - Robot poses are facing along the X axis (horizontal, to the right in 2D)
  16. * - The robot moves 2 meters each step
  17. * - We have full odometry between poses
  18. */
  19. // We will use Pose2 variables (x, y, theta) to represent the robot positions
  20. #include <gtsam/geometry/Pose2.h>
  21. // In GTSAM, measurement functions are represented as 'factors'. Several common factors
  22. // have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
  23. // Here we will use Between factors for the relative motion described by odometry measurements.
  24. // Also, we will initialize the robot at the origin using a Prior factor.
  25. #include <gtsam/slam/BetweenFactor.h>
  26. // When the factors are created, we will add them to a Factor Graph. As the factors we are using
  27. // are nonlinear factors, we will need a Nonlinear Factor Graph.
  28. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  29. // Finally, once all of the factors have been added to our factor graph, we will want to
  30. // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
  31. // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
  32. // Levenberg-Marquardt solver
  33. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  34. // Once the optimized values have been calculated, we can also calculate the marginal covariance
  35. // of desired variables
  36. #include <gtsam/nonlinear/Marginals.h>
  37. // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
  38. // nonlinear functions around an initial linearization point, then solve the linear system
  39. // to update the linearization point. This happens repeatedly until the solver converges
  40. // to a consistent set of variable values. This requires us to specify an initial guess
  41. // for each variable, held in a Values container.
  42. #include <gtsam/nonlinear/Values.h>
  43. using namespace std;
  44. using namespace gtsam;
  45. int main(int argc, char** argv) {
  46. // Create an empty nonlinear factor graph
  47. NonlinearFactorGraph graph;
  48. // Add a prior on the first pose, setting it to the origin
  49. // A prior factor consists of a mean and a noise model (covariance matrix)
  50. Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
  51. auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
  52. graph.addPrior(1, priorMean, priorNoise);
  53. // Add odometry factors
  54. Pose2 odometry(2.0, 0.0, 0.0);
  55. // For simplicity, we will use the same noise model for each odometry factor
  56. auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  57. // Create odometry (Between) factors between consecutive poses
  58. graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, odometry, odometryNoise);
  59. graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, odometry, odometryNoise);
  60. graph.print("\nFactor Graph:\n"); // print
  61. // Create the data structure to hold the initialEstimate estimate to the solution
  62. // For illustrative purposes, these have been deliberately set to incorrect values
  63. Values initial;
  64. initial.insert(1, Pose2(0.5, 0.0, 0.2));
  65. initial.insert(2, Pose2(2.3, 0.1, -0.2));
  66. initial.insert(3, Pose2(4.1, 0.1, 0.1));
  67. initial.print("\nInitial Estimate:\n"); // print
  68. // optimize using Levenberg-Marquardt optimization
  69. Values result = LevenbergMarquardtOptimizer(graph, initial).optimize();
  70. result.print("Final Result:\n");
  71. // Calculate and print marginal covariances for all variables
  72. cout.precision(2);
  73. Marginals marginals(graph, result);
  74. cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl;
  75. cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl;
  76. cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl;
  77. return 0;
  78. }