SFMExample_bal_COLAMD_METIS.cpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142
  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 SFMExample_bal_COLAMD_METIS.cpp
  10. * @brief This file is to compare the ordering performance for COLAMD vs METIS.
  11. * Example problem is to solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file.
  12. * @author Frank Dellaert, Zhaoyang Lv
  13. */
  14. // For an explanation of headers, see SFMExample.cpp
  15. #include <gtsam/inference/Symbol.h>
  16. #include <gtsam/inference/Ordering.h>
  17. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  18. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  19. #include <gtsam/slam/GeneralSFMFactor.h>
  20. #include <gtsam/slam/dataset.h> // for loading BAL datasets !
  21. #include <gtsam/base/timing.h>
  22. #include <vector>
  23. using namespace std;
  24. using namespace gtsam;
  25. using symbol_shorthand::C;
  26. using symbol_shorthand::P;
  27. // We will be using a projection factor that ties a SFM_Camera to a 3D point.
  28. // An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler
  29. // calibration and has a total of 9 free parameters
  30. typedef GeneralSFMFactor<SfmCamera, Point3> MyFactor;
  31. int main(int argc, char* argv[]) {
  32. // Find default file, but if an argument is given, try loading a file
  33. string filename = findExampleDataFile("dubrovnik-3-7-pre");
  34. if (argc > 1) filename = string(argv[1]);
  35. // Load the SfM data from file
  36. SfmData mydata;
  37. readBAL(filename, mydata);
  38. cout << boost::format("read %1% tracks on %2% cameras\n") %
  39. mydata.number_tracks() % mydata.number_cameras();
  40. // Create a factor graph
  41. NonlinearFactorGraph graph;
  42. // We share *one* noiseModel between all projection factors
  43. auto noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  44. // Add measurements to the factor graph
  45. size_t j = 0;
  46. for (const SfmTrack& track : mydata.tracks) {
  47. for (const SfmMeasurement& m : track.measurements) {
  48. size_t i = m.first;
  49. Point2 uv = m.second;
  50. graph.emplace_shared<MyFactor>(
  51. uv, noise, C(i), P(j)); // note use of shorthand symbols C and P
  52. }
  53. j += 1;
  54. }
  55. // Add a prior on pose x1. This indirectly specifies where the origin is.
  56. // and a prior on the position of the first landmark to fix the scale
  57. graph.addPrior(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1));
  58. graph.addPrior(P(0), mydata.tracks[0].p,
  59. noiseModel::Isotropic::Sigma(3, 0.1));
  60. // Create initial estimate
  61. Values initial;
  62. size_t i = 0;
  63. j = 0;
  64. for (const SfmCamera& camera : mydata.cameras) initial.insert(C(i++), camera);
  65. for (const SfmTrack& track : mydata.tracks) initial.insert(P(j++), track.p);
  66. /** --------------- COMPARISON -----------------------**/
  67. /** ----------------------------------------------------**/
  68. LevenbergMarquardtParams params_using_COLAMD, params_using_METIS;
  69. try {
  70. params_using_METIS.setVerbosity("ERROR");
  71. gttic_(METIS_ORDERING);
  72. params_using_METIS.ordering = Ordering::Create(Ordering::METIS, graph);
  73. gttoc_(METIS_ORDERING);
  74. params_using_COLAMD.setVerbosity("ERROR");
  75. gttic_(COLAMD_ORDERING);
  76. params_using_COLAMD.ordering = Ordering::Create(Ordering::COLAMD, graph);
  77. gttoc_(COLAMD_ORDERING);
  78. } catch (exception& e) {
  79. cout << e.what();
  80. }
  81. // expect they have different ordering results
  82. if (params_using_COLAMD.ordering == params_using_METIS.ordering) {
  83. cout << "COLAMD and METIS produce the same ordering. "
  84. << "Problem here!!!" << endl;
  85. }
  86. /* Optimize the graph with METIS and COLAMD and time the results */
  87. Values result_METIS, result_COLAMD;
  88. try {
  89. gttic_(OPTIMIZE_WITH_METIS);
  90. LevenbergMarquardtOptimizer lm_METIS(graph, initial, params_using_METIS);
  91. result_METIS = lm_METIS.optimize();
  92. gttoc_(OPTIMIZE_WITH_METIS);
  93. gttic_(OPTIMIZE_WITH_COLAMD);
  94. LevenbergMarquardtOptimizer lm_COLAMD(graph, initial, params_using_COLAMD);
  95. result_COLAMD = lm_COLAMD.optimize();
  96. gttoc_(OPTIMIZE_WITH_COLAMD);
  97. } catch (exception& e) {
  98. cout << e.what();
  99. }
  100. { // printing the result
  101. cout << "COLAMD final error: " << graph.error(result_COLAMD) << endl;
  102. cout << "METIS final error: " << graph.error(result_METIS) << endl;
  103. cout << endl << endl;
  104. cout << "Time comparison by solving " << filename << " results:" << endl;
  105. cout << boost::format("%1% point tracks and %2% cameras\n") %
  106. mydata.number_tracks() % mydata.number_cameras()
  107. << endl;
  108. tictoc_print_();
  109. }
  110. return 0;
  111. }