METISOrderingExample.cpp 2.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364
  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 METISOrdering.cpp
  10. * @brief Simple robot motion example, with prior and two odometry measurements,
  11. * using a METIS ordering
  12. * @author Frank Dellaert
  13. * @author Andrew Melim
  14. */
  15. /**
  16. * Example of a simple 2D localization example optimized using METIS ordering
  17. * - For more details on the full optimization pipeline, see OdometryExample.cpp
  18. */
  19. #include <gtsam/geometry/Pose2.h>
  20. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  21. #include <gtsam/nonlinear/Marginals.h>
  22. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  23. #include <gtsam/nonlinear/Values.h>
  24. #include <gtsam/slam/BetweenFactor.h>
  25. using namespace std;
  26. using namespace gtsam;
  27. int main(int argc, char** argv) {
  28. NonlinearFactorGraph graph;
  29. Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
  30. auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
  31. graph.addPrior(1, priorMean, priorNoise);
  32. Pose2 odometry(2.0, 0.0, 0.0);
  33. auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  34. graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, odometry, odometryNoise);
  35. graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, odometry, odometryNoise);
  36. graph.print("\nFactor Graph:\n"); // print
  37. Values initial;
  38. initial.insert(1, Pose2(0.5, 0.0, 0.2));
  39. initial.insert(2, Pose2(2.3, 0.1, -0.2));
  40. initial.insert(3, Pose2(4.1, 0.1, 0.1));
  41. initial.print("\nInitial Estimate:\n"); // print
  42. // optimize using Levenberg-Marquardt optimization
  43. LevenbergMarquardtParams params;
  44. // In order to specify the ordering type, we need to se the "orderingType". By
  45. // default this parameter is set to OrderingType::COLAMD
  46. params.orderingType = Ordering::METIS;
  47. LevenbergMarquardtOptimizer optimizer(graph, initial, params);
  48. Values result = optimizer.optimize();
  49. result.print("Final Result:\n");
  50. return 0;
  51. }