timeRot2.cpp 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117
  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 timeRot2.cpp
  10. * @brief Time Rot2 geometry
  11. * @author Richard Roberts
  12. */
  13. #include <gtsam/geometry/Pose2.h>
  14. #include <gtsam/base/timing.h>
  15. #include <iostream>
  16. using namespace std;
  17. using namespace gtsam;
  18. /* ************************************************************************* */
  19. #define TEST(TITLE,STATEMENT) \
  20. gttic_(TITLE); \
  21. for(int i = 0; i < n; i++) \
  22. STATEMENT; \
  23. gttoc_(TITLE);
  24. /* ************************************************************************* */
  25. Rot2 Rot2betweenDefault(const Rot2& r1, const Rot2& r2) {
  26. return r1.inverse() * r2;
  27. }
  28. /* ************************************************************************* */
  29. Rot2 Rot2betweenOptimized(const Rot2& r1, const Rot2& r2) {
  30. // Same as compose but sign of sin for r1 is reversed
  31. return Rot2::fromCosSin(r1.c() * r2.c() + r1.s() * r2.s(), -r1.s() * r2.c() + r1.c() * r2.s());
  32. }
  33. /* ************************************************************************* */
  34. Vector Rot2BetweenFactorEvaluateErrorDefault(const Rot2& measured, const Rot2& p1, const Rot2& p2,
  35. boost::optional<Matrix&> H1, boost::optional<Matrix&> H2)
  36. {
  37. Rot2 hx = p1.between(p2, H1, H2); // h(x)
  38. // manifold equivalent of h(x)-z -> log(z,h(x))
  39. return measured.localCoordinates(hx);
  40. }
  41. /* ************************************************************************* */
  42. Vector Rot2BetweenFactorEvaluateErrorOptimizedBetween(const Rot2& measured, const Rot2& p1, const Rot2& p2,
  43. boost::optional<Matrix&> H1, boost::optional<Matrix&> H2)
  44. {
  45. Rot2 hx = Rot2betweenOptimized(p1, p2); // h(x)
  46. if (H1) *H1 = -I_1x1;
  47. if (H2) *H2 = I_1x1;
  48. // manifold equivalent of h(x)-z -> log(z,h(x))
  49. return Rot2::Logmap(Rot2betweenOptimized(measured, hx));
  50. }
  51. /* ************************************************************************* */
  52. Vector Rot2BetweenFactorEvaluateErrorOptimizedBetweenNoeye(const Rot2& measured, const Rot2& p1, const Rot2& p2,
  53. boost::optional<Matrix&> H1, boost::optional<Matrix&> H2)
  54. {
  55. // TODO: Implement
  56. Rot2 hx = Rot2betweenOptimized(p1, p2); // h(x)
  57. if (H1) *H1 = -I_1x1;
  58. if (H2) *H2 = I_1x1;
  59. // manifold equivalent of h(x)-z -> log(z,h(x))
  60. return Rot2::Logmap(Rot2betweenOptimized(measured, hx));
  61. }
  62. /* ************************************************************************* */
  63. typedef Eigen::Matrix<double,1,1> Matrix1;
  64. Vector Rot2BetweenFactorEvaluateErrorOptimizedBetweenFixed(const Rot2& measured, const Rot2& p1, const Rot2& p2,
  65. boost::optional<Matrix1&> H1, boost::optional<Matrix1&> H2)
  66. {
  67. // TODO: Implement
  68. Rot2 hx = Rot2betweenOptimized(p1, p2); // h(x)
  69. if (H1) *H1 = -Matrix1::Identity();
  70. if (H2) *H2 = Matrix1::Identity();
  71. // manifold equivalent of h(x)-z -> log(z,h(x))
  72. return Rot2::Logmap(Rot2betweenOptimized(measured, hx));
  73. }
  74. /* ************************************************************************* */
  75. int main()
  76. {
  77. int n = 50000000;
  78. cout << "NOTE: Times are reported for " << n << " calls" << endl;
  79. Vector1 v; v << 0.1;
  80. Rot2 R = Rot2(0.4), R2(0.5), R3(0.6);
  81. TEST(Rot2_Expmap, Rot2::Expmap(v));
  82. TEST(Rot2_Retract, R.retract(v));
  83. TEST(Rot2_Logmap, Rot2::Logmap(R2));
  84. TEST(Rot2_between, R.between(R2));
  85. TEST(betweenDefault, Rot2betweenDefault(R, R2));
  86. TEST(betweenOptimized, Rot2betweenOptimized(R, R2));
  87. TEST(Rot2_localCoordinates, R.localCoordinates(R2));
  88. Matrix H1, H2;
  89. Matrix1 H1f, H2f;
  90. TEST(Rot2BetweenFactorEvaluateErrorDefault, Rot2BetweenFactorEvaluateErrorDefault(R3, R, R2, H1, H2));
  91. TEST(Rot2BetweenFactorEvaluateErrorOptimizedBetween, Rot2BetweenFactorEvaluateErrorOptimizedBetween(R3, R, R2, H1, H2));
  92. TEST(Rot2BetweenFactorEvaluateErrorOptimizedBetweenNoeye, Rot2BetweenFactorEvaluateErrorOptimizedBetweenNoeye(R3, R, R2, H1, H2));
  93. TEST(Rot2BetweenFactorEvaluateErrorOptimizedBetweenFixed, Rot2BetweenFactorEvaluateErrorOptimizedBetweenFixed(R3, R, R2, H1f, H2f));
  94. // Print timings
  95. tictoc_print_();
  96. return 0;
  97. }