LocalizationExample.cpp 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158
  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 LocalizationExample.cpp
  10. * @brief Simple robot localization example, with three "GPS-like" measurements
  11. * @author Frank Dellaert
  12. */
  13. /**
  14. * A simple 2D pose slam example with "GPS" measurements
  15. * - The robot moves forward 2 meter each iteration
  16. * - The robot initially faces along the X axis (horizontal, to the right in 2D)
  17. * - We have full odometry between pose
  18. * - We have "GPS-like" measurements implemented with a custom factor
  19. */
  20. // We will use Pose2 variables (x, y, theta) to represent the robot positions
  21. #include <gtsam/geometry/Pose2.h>
  22. // We will use simple integer Keys to refer to the robot poses.
  23. #include <gtsam/inference/Key.h>
  24. // As in OdometryExample.cpp, we use a BetweenFactor to model odometry measurements.
  25. #include <gtsam/slam/BetweenFactor.h>
  26. // We add all facors to a Nonlinear Factor Graph, as our factors are nonlinear.
  27. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  28. // The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
  29. // nonlinear functions around an initial linearization point, then solve the linear system
  30. // to update the linearization point. This happens repeatedly until the solver converges
  31. // to a consistent set of variable values. This requires us to specify an initial guess
  32. // for each variable, held in a Values container.
  33. #include <gtsam/nonlinear/Values.h>
  34. // Finally, once all of the factors have been added to our factor graph, we will want to
  35. // solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
  36. // GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
  37. // standard Levenberg-Marquardt solver
  38. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  39. // Once the optimized values have been calculated, we can also calculate the marginal covariance
  40. // of desired variables
  41. #include <gtsam/nonlinear/Marginals.h>
  42. using namespace std;
  43. using namespace gtsam;
  44. // Before we begin the example, we must create a custom unary factor to implement a
  45. // "GPS-like" functionality. Because standard GPS measurements provide information
  46. // only on the position, and not on the orientation, we cannot use a simple prior to
  47. // properly model this measurement.
  48. //
  49. // The factor will be a unary factor, affect only a single system variable. It will
  50. // also use a standard Gaussian noise model. Hence, we will derive our new factor from
  51. // the NoiseModelFactor1.
  52. #include <gtsam/nonlinear/NonlinearFactor.h>
  53. class UnaryFactor: public NoiseModelFactor1<Pose2> {
  54. // The factor will hold a measurement consisting of an (X,Y) location
  55. // We could this with a Point2 but here we just use two doubles
  56. double mx_, my_;
  57. public:
  58. /// shorthand for a smart pointer to a factor
  59. typedef boost::shared_ptr<UnaryFactor> shared_ptr;
  60. // The constructor requires the variable key, the (X, Y) measurement value, and the noise model
  61. UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
  62. NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}
  63. ~UnaryFactor() override {}
  64. // Using the NoiseModelFactor1 base class there are two functions that must be overridden.
  65. // The first is the 'evaluateError' function. This function implements the desired measurement
  66. // function, returning a vector of errors when evaluated at the provided variable value. It
  67. // must also calculate the Jacobians for this measurement function, if requested.
  68. Vector evaluateError(const Pose2& q, boost::optional<Matrix&> H = boost::none) const override {
  69. // The measurement function for a GPS-like measurement h(q) which predicts the measurement (m) is h(q) = q, q = [qx qy qtheta]
  70. // The error is then simply calculated as E(q) = h(q) - m:
  71. // error_x = q.x - mx
  72. // error_y = q.y - my
  73. // Node's orientation reflects in the Jacobian, in tangent space this is equal to the right-hand rule rotation matrix
  74. // H = [ cos(q.theta) -sin(q.theta) 0 ]
  75. // [ sin(q.theta) cos(q.theta) 0 ]
  76. const Rot2& R = q.rotation();
  77. if (H) (*H) = (gtsam::Matrix(2, 3) << R.c(), -R.s(), 0.0, R.s(), R.c(), 0.0).finished();
  78. return (Vector(2) << q.x() - mx_, q.y() - my_).finished();
  79. }
  80. // The second is a 'clone' function that allows the factor to be copied. Under most
  81. // circumstances, the following code that employs the default copy constructor should
  82. // work fine.
  83. gtsam::NonlinearFactor::shared_ptr clone() const override {
  84. return boost::static_pointer_cast<gtsam::NonlinearFactor>(
  85. gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this))); }
  86. // Additionally, we encourage you the use of unit testing your custom factors,
  87. // (as all GTSAM factors are), in which you would need an equals and print, to satisfy the
  88. // GTSAM_CONCEPT_TESTABLE_INST(T) defined in Testable.h, but these are not needed below.
  89. }; // UnaryFactor
  90. int main(int argc, char** argv) {
  91. // 1. Create a factor graph container and add factors to it
  92. NonlinearFactorGraph graph;
  93. // 2a. Add odometry factors
  94. // For simplicity, we will use the same noise model for each odometry factor
  95. auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  96. // Create odometry (Between) factors between consecutive poses
  97. graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise);
  98. graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2.0, 0.0, 0.0), odometryNoise);
  99. // 2b. Add "GPS-like" measurements
  100. // We will use our custom UnaryFactor for this.
  101. auto unaryNoise =
  102. noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y
  103. graph.emplace_shared<UnaryFactor>(1, 0.0, 0.0, unaryNoise);
  104. graph.emplace_shared<UnaryFactor>(2, 2.0, 0.0, unaryNoise);
  105. graph.emplace_shared<UnaryFactor>(3, 4.0, 0.0, unaryNoise);
  106. graph.print("\nFactor Graph:\n"); // print
  107. // 3. Create the data structure to hold the initialEstimate estimate to the solution
  108. // For illustrative purposes, these have been deliberately set to incorrect values
  109. Values initialEstimate;
  110. initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
  111. initialEstimate.insert(2, Pose2(2.3, 0.1, -0.2));
  112. initialEstimate.insert(3, Pose2(4.1, 0.1, 0.1));
  113. initialEstimate.print("\nInitial Estimate:\n"); // print
  114. // 4. Optimize using Levenberg-Marquardt optimization. The optimizer
  115. // accepts an optional set of configuration parameters, controlling
  116. // things like convergence criteria, the type of linear system solver
  117. // to use, and the amount of information displayed during optimization.
  118. // Here we will use the default set of parameters. See the
  119. // documentation for the full set of parameters.
  120. LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
  121. Values result = optimizer.optimize();
  122. result.print("Final Result:\n");
  123. // 5. Calculate and print marginal covariances for all variables
  124. Marginals marginals(graph, result);
  125. cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl;
  126. cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl;
  127. cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl;
  128. return 0;
  129. }