timeShonanFactor.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  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 timeShonanFactor.cpp
  10. * @brief time ShonanFactor with BAL file
  11. * @author Frank Dellaert
  12. * @date 2019
  13. */
  14. #include <gtsam/base/timing.h>
  15. #include <gtsam/geometry/Pose3.h>
  16. #include <gtsam/linear/NoiseModel.h>
  17. #include <gtsam/linear/PCGSolver.h>
  18. #include <gtsam/linear/SubgraphPreconditioner.h>
  19. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  20. #include <gtsam/nonlinear/NonlinearEquality.h>
  21. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  22. #include <gtsam/nonlinear/Values.h>
  23. #include <gtsam/slam/PriorFactor.h>
  24. #include <gtsam/slam/dataset.h>
  25. #include <gtsam/sfm/ShonanFactor.h>
  26. #include <iostream>
  27. #include <random>
  28. #include <string>
  29. #include <vector>
  30. using namespace std;
  31. using namespace gtsam;
  32. static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2);
  33. int main(int argc, char* argv[]) {
  34. // primitive argument parsing:
  35. if (argc > 3) {
  36. throw runtime_error("Usage: timeShonanFactor [g2oFile]");
  37. }
  38. string g2oFile;
  39. try {
  40. if (argc > 1)
  41. g2oFile = argv[argc - 1];
  42. else
  43. g2oFile = findExampleDataFile("sphere_smallnoise.graph");
  44. } catch (const exception& e) {
  45. cerr << e.what() << '\n';
  46. exit(1);
  47. }
  48. // Read G2O file
  49. const auto measurements = parseMeasurements<Rot3>(g2oFile);
  50. const auto poses = parseVariables<Pose3>(g2oFile);
  51. // Build graph
  52. NonlinearFactorGraph graph;
  53. // graph.add(NonlinearEquality<SOn>(0, SOn::identity(4)));
  54. auto priorModel = noiseModel::Isotropic::Sigma(6, 10000);
  55. graph.add(PriorFactor<SOn>(0, SOn::identity(4), priorModel));
  56. auto G = boost::make_shared<Matrix>(SOn::VectorizedGenerators(4));
  57. for (const auto &m : measurements) {
  58. const auto &keys = m.keys();
  59. const Rot3 &Rij = m.measured();
  60. const auto &model = m.noiseModel();
  61. graph.emplace_shared<ShonanFactor3>(
  62. keys[0], keys[1], Rij, 4, model, G);
  63. }
  64. std::mt19937 rng(42);
  65. // Set parameters to be similar to ceres
  66. LevenbergMarquardtParams params;
  67. LevenbergMarquardtParams::SetCeresDefaults(&params);
  68. params.setLinearSolverType("MULTIFRONTAL_QR");
  69. // params.setVerbosityLM("SUMMARY");
  70. // params.linearSolverType = LevenbergMarquardtParams::Iterative;
  71. // auto pcg = boost::make_shared<PCGSolverParameters>();
  72. // pcg->preconditioner_ =
  73. // boost::make_shared<SubgraphPreconditionerParameters>();
  74. // boost::make_shared<BlockJacobiPreconditionerParameters>();
  75. // params.iterativeParams = pcg;
  76. // Optimize
  77. for (size_t i = 0; i < 100; i++) {
  78. gttic_(optimize);
  79. Values initial;
  80. initial.insert(0, SOn::identity(4));
  81. for (size_t j = 1; j < poses.size(); j++) {
  82. initial.insert(j, SOn::Random(rng, 4));
  83. }
  84. LevenbergMarquardtOptimizer lm(graph, initial, params);
  85. Values result = lm.optimize();
  86. cout << "cost = " << graph.error(result) << endl;
  87. }
  88. tictoc_finishedIteration_();
  89. tictoc_print_();
  90. return 0;
  91. }