timeSFMBALsmart.cpp 1.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455
  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 timeSFMBALsmart.cpp
  10. * @brief time SFM with BAL file, SmartProjectionFactor
  11. * @author Frank Dellaert
  12. * @date Feb 26, 2016
  13. */
  14. #include "timeSFMBAL.h"
  15. #include <gtsam/slam/SmartProjectionFactor.h>
  16. #include <gtsam/geometry/Cal3Bundler.h>
  17. #include <gtsam/geometry/PinholeCamera.h>
  18. #include <gtsam/geometry/Point3.h>
  19. using namespace std;
  20. using namespace gtsam;
  21. typedef PinholeCamera<Cal3Bundler> Camera;
  22. typedef SmartProjectionFactor<Camera> SfmFactor;
  23. int main(int argc, char* argv[]) {
  24. // parse options and read BAL file
  25. SfmData db = preamble(argc, argv);
  26. // Add smart factors to graph
  27. NonlinearFactorGraph graph;
  28. for (size_t j = 0; j < db.number_tracks(); j++) {
  29. auto smartFactor = boost::make_shared<SfmFactor>(gNoiseModel);
  30. for (const SfmMeasurement& m : db.tracks[j].measurements) {
  31. size_t i = m.first;
  32. Point2 z = m.second;
  33. smartFactor->add(z, C(i));
  34. }
  35. graph.push_back(smartFactor);
  36. }
  37. Values initial;
  38. size_t i = 0;
  39. gUseSchur = false;
  40. for (const SfmCamera& camera : db.cameras)
  41. initial.insert(C(i++), camera);
  42. return optimize(db, graph, initial);
  43. }