timeSFMExpressions.cpp 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182
  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 timeSFMExpressions.cpp
  10. * @brief time CalibratedCamera derivatives, realistic scenario
  11. * @author Frank Dellaert
  12. * @date October 3, 2014
  13. */
  14. #include <gtsam/slam/expressions.h>
  15. #include <gtsam/nonlinear/ExpressionFactor.h>
  16. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  17. #include <gtsam/linear/GaussianFactorGraph.h>
  18. #include <time.h>
  19. #include <iostream>
  20. #include <iomanip> // std::setprecision
  21. using namespace std;
  22. using namespace gtsam;
  23. //#define TERNARY
  24. int main() {
  25. // number of cameras, and points
  26. static const size_t M=100, N = 10000, n = M*N;
  27. // Create leaves
  28. Cal3_S2_ K('K', 0);
  29. std::vector<Expression<Pose3> > x = createUnknowns<Pose3>(M, 'x');
  30. std::vector<Expression<Point3> > p = createUnknowns<Point3>(N, 'p');
  31. // Some parameters needed
  32. Point2 z(-17, 30);
  33. SharedNoiseModel model = noiseModel::Unit::Create(2);
  34. // Create values
  35. Values values;
  36. values.insert(Symbol('K', 0), Cal3_S2());
  37. for (size_t i = 0; i < M; i++)
  38. values.insert(Symbol('x', i), Pose3());
  39. for (size_t j = 0; j < N; j++)
  40. values.insert(Symbol('p', j), Point3(0, 0, 1));
  41. long timeLog = clock();
  42. NonlinearFactorGraph graph;
  43. for (size_t i = 0; i < M; i++) {
  44. for (size_t j = 0; j < N; j++) {
  45. NonlinearFactor::shared_ptr f = boost::make_shared<
  46. ExpressionFactor<Point2> >
  47. #ifdef TERNARY
  48. (model, z, project3(x[i], p[j], K));
  49. #else
  50. (model, z, uncalibrate(K, project(transformTo(x[i], p[j]))));
  51. #endif
  52. graph.push_back(f);
  53. }
  54. }
  55. long timeLog2 = clock();
  56. cout << setprecision(3);
  57. double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
  58. cout << seconds << " seconds to build" << endl;
  59. timeLog = clock();
  60. GaussianFactorGraph::shared_ptr gfg = graph.linearize(values);
  61. timeLog2 = clock();
  62. seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
  63. cout << seconds << " seconds to linearize" << endl;
  64. cout << ((double) seconds * 1000000 / n) << " musecs/call" << endl;
  65. return 0;
  66. }