testGeneralSFMFactorB.cpp 2.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  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 testGeneralSFMFactorB.cpp
  10. * @author Frank Dellaert
  11. * @brief test general SFM class, with nonlinear optimization and BAL files
  12. */
  13. #include <gtsam/slam/dataset.h>
  14. #include <gtsam/slam/GeneralSFMFactor.h>
  15. #include <gtsam/geometry/Point3.h>
  16. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  17. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  18. #include <gtsam/nonlinear/NonlinearOptimizer.h>
  19. #include <gtsam/nonlinear/Values.h>
  20. #include <gtsam/inference/Symbol.h>
  21. #include <gtsam/linear/NoiseModel.h>
  22. #include <CppUnitLite/Failure.h>
  23. #include <CppUnitLite/Test.h>
  24. #include <CppUnitLite/TestRegistry.h>
  25. #include <CppUnitLite/TestResult.h>
  26. #include <stddef.h>
  27. #include <stdexcept>
  28. #include <string>
  29. using namespace std;
  30. using namespace gtsam;
  31. typedef GeneralSFMFactor<PinholeCamera<Cal3Bundler>, Point3> sfmFactor;
  32. using symbol_shorthand::P;
  33. /* ************************************************************************* */
  34. TEST(PinholeCamera, BAL) {
  35. string filename = findExampleDataFile("dubrovnik-3-7-pre");
  36. SfmData db;
  37. bool success = readBAL(filename, db);
  38. if (!success) throw runtime_error("Could not access file!");
  39. SharedNoiseModel unit2 = noiseModel::Unit::Create(2);
  40. NonlinearFactorGraph graph;
  41. for (size_t j = 0; j < db.number_tracks(); j++) {
  42. for (const SfmMeasurement& m: db.tracks[j].measurements)
  43. graph.emplace_shared<sfmFactor>(m.second, unit2, m.first, P(j));
  44. }
  45. Values initial = initialCamerasAndPointsEstimate(db);
  46. LevenbergMarquardtOptimizer lm(graph, initial);
  47. Values actual = lm.optimize();
  48. double actualError = graph.error(actual);
  49. EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5);
  50. }
  51. /* ************************************************************************* */
  52. int main() {
  53. TestResult tr;
  54. return TestRegistry::runAllTests(tr);
  55. }
  56. /* ************************************************************************* */