Pose2SLAMExample_graphviz.cpp 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970
  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 Pose2SLAMExample_graphviz.cpp
  10. * @brief Save factor graph as graphviz dot file
  11. * @date Sept 6, 2013
  12. * @author Frank Dellaert
  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. #include <fstream>
  19. using namespace std;
  20. using namespace gtsam;
  21. int main(int argc, char** argv) {
  22. // 1. Create a factor graph container and add factors to it
  23. NonlinearFactorGraph graph;
  24. // 2a. Add a prior on the first pose, setting it to the origin
  25. auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
  26. graph.addPrior(1, Pose2(0, 0, 0), priorNoise);
  27. // For simplicity, we will use the same noise model for odometry and loop
  28. // closures
  29. auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  30. // 2b. Add odometry factors
  31. graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2, 0, 0), model);
  32. graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2, 0, M_PI_2), model);
  33. graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2, 0, M_PI_2), model);
  34. graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2, 0, M_PI_2), model);
  35. // 2c. Add the loop closure constraint
  36. graph.emplace_shared<BetweenFactor<Pose2> >(5, 2, Pose2(2, 0, M_PI_2), model);
  37. // 3. Create the data structure to hold the initial estimate to the solution
  38. // For illustrative purposes, these have been deliberately set to incorrect values
  39. Values initial;
  40. initial.insert(1, Pose2(0.5, 0.0, 0.2));
  41. initial.insert(2, Pose2(2.3, 0.1, -0.2));
  42. initial.insert(3, Pose2(4.1, 0.1, M_PI_2));
  43. initial.insert(4, Pose2(4.0, 2.0, M_PI));
  44. initial.insert(5, Pose2(2.1, 2.1, -M_PI_2));
  45. // Single Step Optimization using Levenberg-Marquardt
  46. Values result = LevenbergMarquardtOptimizer(graph, initial).optimize();
  47. // save factor graph as graphviz dot file
  48. // Render to PDF using "fdp Pose2SLAMExample.dot -Tpdf > graph.pdf"
  49. ofstream os("Pose2SLAMExample.dot");
  50. graph.saveGraph(os, result);
  51. // Also print out to console
  52. graph.saveGraph(cout, result);
  53. return 0;
  54. }