testLie.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178
  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. * -------------------------------1------------------------------------------- */
  8. /**
  9. * @file testLie.cpp
  10. * @date May, 2015
  11. * @author Frank Dellaert
  12. * @brief unit tests for Lie group type machinery
  13. */
  14. #include <gtsam/base/ProductLieGroup.h>
  15. #include <gtsam/geometry/Pose2.h>
  16. #include <gtsam/geometry/Point2.h>
  17. #include <gtsam/base/testLie.h>
  18. #include <CppUnitLite/TestHarness.h>
  19. using namespace std;
  20. using namespace gtsam;
  21. static const double tol = 1e-9;
  22. //******************************************************************************
  23. typedef ProductLieGroup<Point2, Pose2> Product;
  24. // Define any direct product group to be a model of the multiplicative Group concept
  25. namespace gtsam {
  26. template<> struct traits<Product> : internal::LieGroupTraits<Product> {
  27. static void Print(const Product& m, const string& s = "") {
  28. cout << s << "(" << m.first << "," << m.second.translation() << "/"
  29. << m.second.theta() << ")" << endl;
  30. }
  31. static bool Equals(const Product& m1, const Product& m2, double tol = 1e-8) {
  32. return traits<Point2>::Equals(m1.first, m2.first, tol) && m1.second.equals(m2.second, tol);
  33. }
  34. };
  35. }
  36. //******************************************************************************
  37. TEST(Lie, ProductLieGroup) {
  38. BOOST_CONCEPT_ASSERT((IsGroup<Product>));
  39. BOOST_CONCEPT_ASSERT((IsManifold<Product>));
  40. BOOST_CONCEPT_ASSERT((IsLieGroup<Product>));
  41. Product pair1;
  42. Vector5 d;
  43. d << 1, 2, 0.1, 0.2, 0.3;
  44. Product expected(Point2(1, 2), Pose2::Expmap(Vector3(0.1, 0.2, 0.3)));
  45. Product pair2 = pair1.expmap(d);
  46. EXPECT(assert_equal(expected, pair2, 1e-9));
  47. EXPECT(assert_equal(d, pair1.logmap(pair2), 1e-9));
  48. }
  49. /* ************************************************************************* */
  50. Product compose_proxy(const Product& A, const Product& B) {
  51. return A.compose(B);
  52. }
  53. TEST( testProduct, compose ) {
  54. Product state1(Point2(1, 2), Pose2(3, 4, 5)), state2 = state1;
  55. Matrix actH1, actH2;
  56. state1.compose(state2, actH1, actH2);
  57. Matrix numericH1 = numericalDerivative21(compose_proxy, state1, state2);
  58. Matrix numericH2 = numericalDerivative22(compose_proxy, state1, state2);
  59. EXPECT(assert_equal(numericH1, actH1, tol));
  60. EXPECT(assert_equal(numericH2, actH2, tol));
  61. }
  62. /* ************************************************************************* */
  63. Product between_proxy(const Product& A, const Product& B) {
  64. return A.between(B);
  65. }
  66. TEST( testProduct, between ) {
  67. Product state1(Point2(1, 2), Pose2(3, 4, 5)), state2 = state1;
  68. Matrix actH1, actH2;
  69. state1.between(state2, actH1, actH2);
  70. Matrix numericH1 = numericalDerivative21(between_proxy, state1, state2);
  71. Matrix numericH2 = numericalDerivative22(between_proxy, state1, state2);
  72. EXPECT(assert_equal(numericH1, actH1, tol));
  73. EXPECT(assert_equal(numericH2, actH2, tol));
  74. }
  75. /* ************************************************************************* */
  76. Product inverse_proxy(const Product& A) {
  77. return A.inverse();
  78. }
  79. TEST( testProduct, inverse ) {
  80. Product state1(Point2(1, 2), Pose2(3, 4, 5));
  81. Matrix actH1;
  82. state1.inverse(actH1);
  83. Matrix numericH1 = numericalDerivative11(inverse_proxy, state1);
  84. EXPECT(assert_equal(numericH1, actH1, tol));
  85. }
  86. /* ************************************************************************* */
  87. Product expmap_proxy(const Vector5& vec) {
  88. return Product::Expmap(vec);
  89. }
  90. TEST( testProduct, Expmap ) {
  91. Vector5 vec;
  92. vec << 1, 2, 0.1, 0.2, 0.3;
  93. Matrix actH;
  94. Product::Expmap(vec, actH);
  95. Matrix numericH = numericalDerivative11(expmap_proxy, vec);
  96. EXPECT(assert_equal(numericH, actH, tol));
  97. }
  98. /* ************************************************************************* */
  99. Vector5 logmap_proxy(const Product& p) {
  100. return Product::Logmap(p);
  101. }
  102. TEST( testProduct, Logmap ) {
  103. Product state(Point2(1, 2), Pose2(3, 4, 5));
  104. Matrix actH;
  105. Product::Logmap(state, actH);
  106. Matrix numericH = numericalDerivative11(logmap_proxy, state);
  107. EXPECT(assert_equal(numericH, actH, tol));
  108. }
  109. /* ************************************************************************* */
  110. Product interpolate_proxy(const Product& x, const Product& y, double t) {
  111. return interpolate<Product>(x, y, t);
  112. }
  113. TEST(Lie, Interpolate) {
  114. Product x(Point2(1, 2), Pose2(3, 4, 5));
  115. Product y(Point2(6, 7), Pose2(8, 9, 0));
  116. double t;
  117. Matrix actH1, numericH1, actH2, numericH2;
  118. t = 0.0;
  119. interpolate<Product>(x, y, t, actH1, actH2);
  120. numericH1 = numericalDerivative31<Product, Product, Product, double>(
  121. interpolate_proxy, x, y, t);
  122. EXPECT(assert_equal(numericH1, actH1, tol));
  123. numericH2 = numericalDerivative32<Product, Product, Product, double>(
  124. interpolate_proxy, x, y, t);
  125. EXPECT(assert_equal(numericH2, actH2, tol));
  126. t = 0.5;
  127. interpolate<Product>(x, y, t, actH1, actH2);
  128. numericH1 = numericalDerivative31<Product, Product, Product, double>(
  129. interpolate_proxy, x, y, t);
  130. EXPECT(assert_equal(numericH1, actH1, tol));
  131. numericH2 = numericalDerivative32<Product, Product, Product, double>(
  132. interpolate_proxy, x, y, t);
  133. EXPECT(assert_equal(numericH2, actH2, tol));
  134. t = 1.0;
  135. interpolate<Product>(x, y, t, actH1, actH2);
  136. numericH1 = numericalDerivative31<Product, Product, Product, double>(
  137. interpolate_proxy, x, y, t);
  138. EXPECT(assert_equal(numericH1, actH1, tol));
  139. numericH2 = numericalDerivative32<Product, Product, Product, double>(
  140. interpolate_proxy, x, y, t);
  141. EXPECT(assert_equal(numericH2, actH2, tol));
  142. }
  143. //******************************************************************************
  144. int main() {
  145. TestResult tr;
  146. return TestRegistry::runAllTests(tr);
  147. }
  148. //******************************************************************************