Pose2SLAMwSPCG.cpp 3.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980
  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 Pose2SLAMwSPCG.cpp
  10. * @brief A 2D Pose SLAM example using the SimpleSPCGSolver.
  11. * @author Yong-Dian Jian
  12. * @date June 2, 2012
  13. */
  14. // For an explanation of headers below, please see Pose2SLAMExample.cpp
  15. #include <gtsam/slam/BetweenFactor.h>
  16. #include <gtsam/geometry/Pose2.h>
  17. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  18. // In contrast to that example, however, we will use a PCG solver here
  19. #include <gtsam/linear/SubgraphSolver.h>
  20. using namespace std;
  21. using namespace gtsam;
  22. int main(int argc, char** argv) {
  23. // 1. Create a factor graph container and add factors to it
  24. NonlinearFactorGraph graph;
  25. // 2a. Add a prior on the first pose, setting it to the origin
  26. Pose2 prior(0.0, 0.0, 0.0); // prior at origin
  27. auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
  28. graph.addPrior(1, prior, priorNoise);
  29. // 2b. Add odometry factors
  30. auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  31. graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
  32. graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
  33. graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
  34. graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
  35. // 2c. Add the loop closure constraint
  36. auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  37. graph.emplace_shared<BetweenFactor<Pose2> >(5, 1, Pose2(0.0, 0.0, 0.0),
  38. model);
  39. graph.print("\nFactor Graph:\n"); // print
  40. // 3. Create the data structure to hold the initialEstimate estimate to the
  41. // solution
  42. Values initialEstimate;
  43. initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
  44. initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1));
  45. initialEstimate.insert(3, Pose2(2.1, 1.9, 2.8));
  46. initialEstimate.insert(4, Pose2(-.3, 2.5, 4.2));
  47. initialEstimate.insert(5, Pose2(0.1, -0.7, 5.8));
  48. initialEstimate.print("\nInitial Estimate:\n"); // print
  49. // 4. Single Step Optimization using Levenberg-Marquardt
  50. LevenbergMarquardtParams parameters;
  51. parameters.verbosity = NonlinearOptimizerParams::ERROR;
  52. parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA;
  53. // LM is still the outer optimization loop, but by specifying "Iterative"
  54. // below We indicate that an iterative linear solver should be used. In
  55. // addition, the *type* of the iterativeParams decides on the type of
  56. // iterative solver, in this case the SPCG (subgraph PCG)
  57. parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
  58. parameters.iterativeParams = boost::make_shared<SubgraphSolverParameters>();
  59. LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
  60. Values result = optimizer.optimize();
  61. result.print("Final Result:\n");
  62. cout << "subgraph solver final error = " << graph.error(result) << endl;
  63. return 0;
  64. }