ShonanAveragingCLI.cpp 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138
  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 ShonanAveragingCLI.cpp
  10. * @brief Run Shonan Rotation Averaging Algorithm on a file or example dataset
  11. * @author Frank Dellaert
  12. * @date August, 2020
  13. *
  14. * Example usage:
  15. *
  16. * Running without arguments will run on tiny 3D example pose3example-grid
  17. * ./ShonanAveragingCLI
  18. *
  19. * Read 2D dataset w10000 (in examples/data) and output to w10000-rotations.g2o
  20. * ./ShonanAveragingCLI -d 2 -n w10000 -o w10000-rotations.g2o
  21. *
  22. * Read 3D dataset sphere25000.txt and output to shonan.g2o (default)
  23. * ./ShonanAveragingCLI -i spere2500.txt
  24. *
  25. * If you prefer using a robust Huber loss, you can add the option "-h true",
  26. * for instance
  27. * ./ShonanAveragingCLI -i spere2500.txt -h true
  28. */
  29. #include <gtsam/base/timing.h>
  30. #include <gtsam/sfm/ShonanAveraging.h>
  31. #include <gtsam/slam/InitializePose.h>
  32. #include <gtsam/slam/dataset.h>
  33. #include <boost/program_options.hpp>
  34. using namespace std;
  35. using namespace gtsam;
  36. namespace po = boost::program_options;
  37. /* ************************************************************************* */
  38. int main(int argc, char* argv[]) {
  39. string datasetName;
  40. string inputFile;
  41. string outputFile;
  42. int d, seed, pMin;
  43. bool useHuberLoss;
  44. po::options_description desc(
  45. "Shonan Rotation Averaging CLI reads a *pose* graph, extracts the "
  46. "rotation constraints, and runs the Shonan algorithm.");
  47. desc.add_options()("help", "Print help message")(
  48. "named_dataset,n",
  49. po::value<string>(&datasetName)->default_value("pose3example-grid"),
  50. "Find and read frome example dataset file")(
  51. "input_file,i", po::value<string>(&inputFile)->default_value(""),
  52. "Read pose constraints graph from the specified file")(
  53. "output_file,o",
  54. po::value<string>(&outputFile)->default_value("shonan.g2o"),
  55. "Write solution to the specified file")(
  56. "dimension,d", po::value<int>(&d)->default_value(3),
  57. "Optimize over 2D or 3D rotations")(
  58. "useHuberLoss,h", po::value<bool>(&useHuberLoss)->default_value(false),
  59. "set True to use Huber loss")("pMin,p",
  60. po::value<int>(&pMin)->default_value(3),
  61. "set to use desired rank pMin")(
  62. "seed,s", po::value<int>(&seed)->default_value(42),
  63. "Random seed for initial estimate");
  64. po::variables_map vm;
  65. po::store(po::command_line_parser(argc, argv).options(desc).run(), vm);
  66. po::notify(vm);
  67. if (vm.count("help")) {
  68. cout << desc << "\n";
  69. return 1;
  70. }
  71. // Get input file
  72. if (inputFile.empty()) {
  73. if (datasetName.empty()) {
  74. cout << "You must either specify a named dataset or an input file\n"
  75. << desc << endl;
  76. return 1;
  77. }
  78. inputFile = findExampleDataFile(datasetName);
  79. }
  80. // Seed random number generator
  81. static std::mt19937 rng(seed);
  82. NonlinearFactorGraph::shared_ptr inputGraph;
  83. Values::shared_ptr posesInFile;
  84. Values poses;
  85. auto lmParams = LevenbergMarquardtParams::CeresDefaults();
  86. if (d == 2) {
  87. cout << "Running Shonan averaging for SO(2) on " << inputFile << endl;
  88. ShonanAveraging2::Parameters parameters(lmParams);
  89. parameters.setUseHuber(useHuberLoss);
  90. ShonanAveraging2 shonan(inputFile, parameters);
  91. auto initial = shonan.initializeRandomly(rng);
  92. auto result = shonan.run(initial, pMin);
  93. // Parse file again to set up translation problem, adding a prior
  94. boost::tie(inputGraph, posesInFile) = load2D(inputFile);
  95. auto priorModel = noiseModel::Unit::Create(3);
  96. inputGraph->addPrior(0, posesInFile->at<Pose2>(0), priorModel);
  97. cout << "recovering 2D translations" << endl;
  98. auto poseGraph = initialize::buildPoseGraph<Pose2>(*inputGraph);
  99. poses = initialize::computePoses<Pose2>(result.first, &poseGraph);
  100. } else if (d == 3) {
  101. cout << "Running Shonan averaging for SO(3) on " << inputFile << endl;
  102. ShonanAveraging3::Parameters parameters(lmParams);
  103. parameters.setUseHuber(useHuberLoss);
  104. ShonanAveraging3 shonan(inputFile, parameters);
  105. auto initial = shonan.initializeRandomly(rng);
  106. auto result = shonan.run(initial, pMin);
  107. // Parse file again to set up translation problem, adding a prior
  108. boost::tie(inputGraph, posesInFile) = load3D(inputFile);
  109. auto priorModel = noiseModel::Unit::Create(6);
  110. inputGraph->addPrior(0, posesInFile->at<Pose3>(0), priorModel);
  111. cout << "recovering 3D translations" << endl;
  112. auto poseGraph = initialize::buildPoseGraph<Pose3>(*inputGraph);
  113. poses = initialize::computePoses<Pose3>(result.first, &poseGraph);
  114. } else {
  115. cout << "Can only run SO(2) or SO(3) averaging\n" << desc << endl;
  116. return 1;
  117. }
  118. cout << "Writing result to " << outputFile << endl;
  119. writeG2o(*inputGraph, poses, outputFile);
  120. return 0;
  121. }
  122. /* ************************************************************************* */