SFMExample_bal.cpp 3.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192
  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.cpp
  10. * @brief Solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file
  11. * @author Frank Dellaert
  12. */
  13. // For an explanation of headers, see SFMExample.cpp
  14. #include <gtsam/inference/Symbol.h>
  15. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  16. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  17. #include <gtsam/slam/GeneralSFMFactor.h>
  18. #include <gtsam/slam/dataset.h> // for loading BAL datasets !
  19. #include <vector>
  20. using namespace std;
  21. using namespace gtsam;
  22. using symbol_shorthand::C;
  23. using symbol_shorthand::P;
  24. // We will be using a projection factor that ties a SFM_Camera to a 3D point.
  25. // An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler calibration
  26. // and has a total of 9 free parameters
  27. typedef GeneralSFMFactor<SfmCamera,Point3> MyFactor;
  28. /* ************************************************************************* */
  29. int main (int argc, char* argv[]) {
  30. // Find default file, but if an argument is given, try loading a file
  31. string filename = findExampleDataFile("dubrovnik-3-7-pre");
  32. if (argc>1) filename = string(argv[1]);
  33. // Load the SfM data from file
  34. SfmData mydata;
  35. readBAL(filename, mydata);
  36. cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
  37. // Create a factor graph
  38. NonlinearFactorGraph graph;
  39. // We share *one* noiseModel between all projection factors
  40. auto noise =
  41. noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  42. // Add measurements to the factor graph
  43. size_t j = 0;
  44. for(const SfmTrack& track: mydata.tracks) {
  45. for(const SfmMeasurement& m: track.measurements) {
  46. size_t i = m.first;
  47. Point2 uv = m.second;
  48. graph.emplace_shared<MyFactor>(uv, noise, C(i), P(j)); // note use of shorthand symbols C and P
  49. }
  50. j += 1;
  51. }
  52. // Add a prior on pose x1. This indirectly specifies where the origin is.
  53. // and a prior on the position of the first landmark to fix the scale
  54. graph.addPrior(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1));
  55. graph.addPrior(P(0), mydata.tracks[0].p, noiseModel::Isotropic::Sigma(3, 0.1));
  56. // Create initial estimate
  57. Values initial;
  58. size_t i = 0; j = 0;
  59. for(const SfmCamera& camera: mydata.cameras) initial.insert(C(i++), camera);
  60. for(const SfmTrack& track: mydata.tracks) initial.insert(P(j++), track.p);
  61. /* Optimize the graph and print results */
  62. Values result;
  63. try {
  64. LevenbergMarquardtParams params;
  65. params.setVerbosity("ERROR");
  66. LevenbergMarquardtOptimizer lm(graph, initial, params);
  67. result = lm.optimize();
  68. } catch (exception& e) {
  69. cout << e.what();
  70. }
  71. cout << "final error: " << graph.error(result) << endl;
  72. return 0;
  73. }
  74. /* ************************************************************************* */