SFMExampleExpressions_bal.cpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113
  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 SFMExampleExpressions_bal.cpp
  10. * @brief A structure-from-motion example done with Expressions
  11. * @author Frank Dellaert
  12. * @date January 2015
  13. */
  14. /**
  15. * This is the Expression version of SFMExample
  16. * See detailed description of headers there, this focuses on explaining the AD part
  17. */
  18. // The two new headers that allow using our Automatic Differentiation Expression framework
  19. #include <gtsam/slam/expressions.h>
  20. #include <gtsam/nonlinear/ExpressionFactorGraph.h>
  21. // Header order is close to far
  22. #include <gtsam/inference/Symbol.h>
  23. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  24. #include <gtsam/slam/dataset.h> // for loading BAL datasets !
  25. #include <vector>
  26. using namespace std;
  27. using namespace gtsam;
  28. using namespace noiseModel;
  29. using symbol_shorthand::C;
  30. using symbol_shorthand::P;
  31. // An SfmCamera is defined in datase.h as a camera with unknown Cal3Bundler calibration
  32. // and has a total of 9 free parameters
  33. int main(int argc, char* argv[]) {
  34. // Find default file, but if an argument is given, try loading a file
  35. string filename = findExampleDataFile("dubrovnik-3-7-pre");
  36. if (argc > 1) filename = string(argv[1]);
  37. // Load the SfM data from file
  38. SfmData mydata;
  39. readBAL(filename, mydata);
  40. cout << boost::format("read %1% tracks on %2% cameras\n") %
  41. mydata.number_tracks() % mydata.number_cameras();
  42. // Create a factor graph
  43. ExpressionFactorGraph graph;
  44. // Here we don't use a PriorFactor but directly the ExpressionFactor class
  45. // First, we create an expression to the pose from the first camera
  46. Expression<SfmCamera> camera0_(C(0));
  47. // Then, to get its pose:
  48. Pose3_ pose0_(&SfmCamera::getPose, camera0_);
  49. // Finally, we say it should be equal to first guess
  50. graph.addExpressionFactor(pose0_, mydata.cameras[0].pose(),
  51. noiseModel::Isotropic::Sigma(6, 0.1));
  52. // similarly, we create a prior on the first point
  53. Point3_ point0_(P(0));
  54. graph.addExpressionFactor(point0_, mydata.tracks[0].p,
  55. noiseModel::Isotropic::Sigma(3, 0.1));
  56. // We share *one* noiseModel between all projection factors
  57. auto noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
  58. // Simulated measurements from each camera pose, adding them to the factor
  59. // graph
  60. size_t j = 0;
  61. for (const SfmTrack& track : mydata.tracks) {
  62. // Leaf expression for j^th point
  63. Point3_ point_('p', j);
  64. for (const SfmMeasurement& m : track.measurements) {
  65. size_t i = m.first;
  66. Point2 uv = m.second;
  67. // Leaf expression for i^th camera
  68. Expression<SfmCamera> camera_(C(i));
  69. // Below an expression for the prediction of the measurement:
  70. Point2_ predict_ = project2<SfmCamera>(camera_, point_);
  71. // Again, here we use an ExpressionFactor
  72. graph.addExpressionFactor(predict_, uv, noise);
  73. }
  74. j += 1;
  75. }
  76. // Create initial estimate
  77. Values initial;
  78. size_t i = 0;
  79. j = 0;
  80. for (const SfmCamera& camera : mydata.cameras) initial.insert(C(i++), camera);
  81. for (const SfmTrack& track : mydata.tracks) initial.insert(P(j++), track.p);
  82. /* Optimize the graph and print results */
  83. Values result;
  84. try {
  85. LevenbergMarquardtParams params;
  86. params.setVerbosity("ERROR");
  87. LevenbergMarquardtOptimizer lm(graph, initial, params);
  88. result = lm.optimize();
  89. } catch (exception& e) {
  90. cout << e.what();
  91. }
  92. cout << "final error: " << graph.error(result) << endl;
  93. return 0;
  94. }