timeLago.cpp 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182
  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 timeVirtual.cpp
  10. * @brief Time the overhead of using virtual destructors and methods
  11. * @author Richard Roberts
  12. * @date Dec 3, 2010
  13. */
  14. #include <gtsam/slam/dataset.h>
  15. #include <gtsam/slam/lago.h>
  16. #include <gtsam/geometry/Pose2.h>
  17. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  18. #include <gtsam/linear/Sampler.h>
  19. #include <gtsam/base/timing.h>
  20. #include <iostream>
  21. using namespace std;
  22. using namespace gtsam;
  23. int main(int argc, char *argv[]) {
  24. size_t trials = 1;
  25. // read graph
  26. Values::shared_ptr solution;
  27. NonlinearFactorGraph::shared_ptr g;
  28. string inputFile = findExampleDataFile("w10000");
  29. SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 0.05, 0.05, 5.0 * M_PI / 180.0).finished());
  30. boost::tie(g, solution) = load2D(inputFile, model);
  31. // add noise to create initial estimate
  32. Values initial;
  33. Values::ConstFiltered<Pose2> poses = solution->filter<Pose2>();
  34. SharedDiagonal noise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.5, 0.5, 15.0 * M_PI / 180.0).finished());
  35. Sampler sampler(noise);
  36. for(const Values::ConstFiltered<Pose2>::KeyValuePair& it: poses)
  37. initial.insert(it.key, it.value.retract(sampler.sample()));
  38. // Add prior on the pose having index (key) = 0
  39. noiseModel::Diagonal::shared_ptr priorModel = //
  40. noiseModel::Diagonal::Sigmas(Vector3(1e-6, 1e-6, 1e-8));
  41. g->addPrior(0, Pose2(), priorModel);
  42. // LAGO
  43. for (size_t i = 0; i < trials; i++) {
  44. {
  45. gttic_(lago);
  46. gttic_(init);
  47. Values lagoInitial = lago::initialize(*g);
  48. gttoc_(init);
  49. gttic_(refine);
  50. GaussNewtonOptimizer optimizer(*g, lagoInitial);
  51. Values result = optimizer.optimize();
  52. gttoc_(refine);
  53. }
  54. {
  55. gttic_(optimize);
  56. GaussNewtonOptimizer optimizer(*g, initial);
  57. Values result = optimizer.optimize();
  58. }
  59. tictoc_finishedIteration_();
  60. }
  61. tictoc_print_();
  62. return 0;
  63. }