timeCameraExpression.cpp 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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 timeCameraExpression.cpp
  10. * @brief time CalibratedCamera derivatives
  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/slam/ProjectionFactor.h>
  17. #include <gtsam/slam/GeneralSFMFactor.h>
  18. #include <gtsam/geometry/Pose3.h>
  19. #include <gtsam/geometry/Cal3_S2.h>
  20. #include "timeLinearize.h"
  21. using namespace std;
  22. using namespace gtsam;
  23. #define time timeSingleThreaded
  24. boost::shared_ptr<Cal3_S2> fixedK(new Cal3_S2());
  25. Point2 myProject(const Pose3& pose, const Point3& point,
  26. OptionalJacobian<2,6> H1, OptionalJacobian<2,3> H2) {
  27. PinholeCamera<Cal3_S2> camera(pose, *fixedK);
  28. return camera.project(point, H1, H2, boost::none);
  29. }
  30. int main() {
  31. // Create leaves
  32. Pose3_ x(1);
  33. Point3_ p(2);
  34. Cal3_S2_ K(3);
  35. // Some parameters needed
  36. Point2 z(-17, 30);
  37. SharedNoiseModel model = noiseModel::Unit::Create(2);
  38. // Create values
  39. Values values;
  40. values.insert(1, Pose3());
  41. values.insert(2, Point3(0, 0, 1));
  42. values.insert(3, Cal3_S2());
  43. // UNCALIBRATED
  44. // Dedicated factor
  45. // Oct 3, 2014, Macbook Air
  46. // 4.2 musecs/call
  47. NonlinearFactor::shared_ptr f1 =
  48. boost::make_shared<GeneralSFMFactor2<Cal3_S2> >(z, model, 1, 2, 3);
  49. time("GeneralSFMFactor2<Cal3_S2> : ", f1, values);
  50. // ExpressionFactor
  51. // Oct 3, 2014, Macbook Air
  52. // 20.3 musecs/call
  53. NonlinearFactor::shared_ptr f2 =
  54. boost::make_shared<ExpressionFactor<Point2> >(model, z,
  55. uncalibrate(K, project(transformTo(x, p))));
  56. time("Bin(Leaf,Un(Bin(Leaf,Leaf))): ", f2, values);
  57. // ExpressionFactor ternary
  58. // Oct 3, 2014, Macbook Air
  59. // 20.3 musecs/call
  60. NonlinearFactor::shared_ptr f3 =
  61. boost::make_shared<ExpressionFactor<Point2> >(model, z,
  62. project3(x, p, K));
  63. time("Ternary(Leaf,Leaf,Leaf) : ", f3, values);
  64. // CALIBRATED
  65. // Dedicated factor
  66. // Oct 3, 2014, Macbook Air
  67. // 3.4 musecs/call
  68. NonlinearFactor::shared_ptr g1 = boost::make_shared<
  69. GenericProjectionFactor<Pose3, Point3> >(z, model, 1, 2, fixedK);
  70. time("GenericProjectionFactor<P,P>: ", g1, values);
  71. // ExpressionFactor
  72. // Oct 3, 2014, Macbook Air
  73. // 16.0 musecs/call
  74. NonlinearFactor::shared_ptr g2 =
  75. boost::make_shared<ExpressionFactor<Point2> >(model, z,
  76. uncalibrate(Cal3_S2_(*fixedK), project(transformTo(x, p))));
  77. time("Bin(Cnst,Un(Bin(Leaf,Leaf))): ", g2, values);
  78. // ExpressionFactor, optimized
  79. // Oct 3, 2014, Macbook Air
  80. // 9.0 musecs/call
  81. typedef PinholeCamera<Cal3_S2> Camera;
  82. typedef Expression<Camera> Camera_;
  83. NonlinearFactor::shared_ptr g3 =
  84. boost::make_shared<ExpressionFactor<Point2> >(model, z,
  85. Point2_(myProject, x, p));
  86. time("Binary(Leaf,Leaf) : ", g3, values);
  87. return 0;
  88. }