testManifold.cpp 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158
  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 testManifold.cpp
  10. * @date September 18, 2014
  11. * @author Frank Dellaert
  12. * @author Paul Furgale
  13. * @brief unit tests for Manifold type machinery
  14. */
  15. #include <gtsam/base/Manifold.h>
  16. #include <gtsam/geometry/PinholeCamera.h>
  17. #include <gtsam/geometry/Pose2.h>
  18. #include <gtsam/geometry/Cal3_S2.h>
  19. #include <gtsam/geometry/Cal3Bundler.h>
  20. #include <gtsam/base/VectorSpace.h>
  21. #include <gtsam/base/testLie.h>
  22. #include <gtsam/base/Testable.h>
  23. #undef CHECK
  24. #include <CppUnitLite/TestHarness.h>
  25. #include <boost/assign/list_of.hpp>
  26. using boost::assign::list_of;
  27. using boost::assign::map_list_of;
  28. using namespace std;
  29. using namespace gtsam;
  30. // The DefaultChart of Camera below is laid out like Snavely's 9-dim vector
  31. typedef PinholeCamera<Cal3Bundler> Camera;
  32. //******************************************************************************
  33. TEST(Manifold, SomeManifoldsGTSAM) {
  34. //BOOST_CONCEPT_ASSERT((IsManifold<int>)); // integer is not a manifold
  35. BOOST_CONCEPT_ASSERT((IsManifold<Camera>));
  36. BOOST_CONCEPT_ASSERT((IsManifold<Cal3_S2>));
  37. BOOST_CONCEPT_ASSERT((IsManifold<Cal3Bundler>));
  38. BOOST_CONCEPT_ASSERT((IsManifold<Camera>));
  39. }
  40. //******************************************************************************
  41. TEST(Manifold, SomeLieGroupsGTSAM) {
  42. BOOST_CONCEPT_ASSERT((IsLieGroup<Rot2>));
  43. BOOST_CONCEPT_ASSERT((IsLieGroup<Pose2>));
  44. BOOST_CONCEPT_ASSERT((IsLieGroup<Rot3>));
  45. BOOST_CONCEPT_ASSERT((IsLieGroup<Pose3>));
  46. }
  47. //******************************************************************************
  48. TEST(Manifold, SomeVectorSpacesGTSAM) {
  49. BOOST_CONCEPT_ASSERT((IsVectorSpace<double>));
  50. BOOST_CONCEPT_ASSERT((IsVectorSpace<float>));
  51. BOOST_CONCEPT_ASSERT((IsVectorSpace<Point2>));
  52. BOOST_CONCEPT_ASSERT((IsVectorSpace<Matrix24>));
  53. }
  54. //******************************************************************************
  55. // dimension
  56. TEST(Manifold, _dimension) {
  57. //using namespace traits;
  58. EXPECT_LONGS_EQUAL(2, traits<Point2>::dimension);
  59. EXPECT_LONGS_EQUAL(8, traits<Matrix24>::dimension);
  60. EXPECT_LONGS_EQUAL(1, traits<double>::dimension);
  61. }
  62. //******************************************************************************
  63. TEST(Manifold, Identity) {
  64. EXPECT_DOUBLES_EQUAL(0.0, traits<double>::Identity(), 0.0);
  65. EXPECT(assert_equal(Matrix(Matrix24::Zero()), Matrix(traits<Matrix24>::Identity())));
  66. EXPECT(assert_equal(Pose3(), traits<Pose3>::Identity()));
  67. EXPECT(assert_equal(Point2(0,0), traits<Point2>::Identity()));
  68. }
  69. //******************************************************************************
  70. // charts
  71. TEST(Manifold, DefaultChart) {
  72. //DefaultChart<Point2> chart1;
  73. EXPECT(traits<Point2>::Local(Point2(0, 0), Point2(1, 0)) == Vector2(1, 0));
  74. EXPECT(traits<Point2>::Retract(Point2(0, 0), Vector2(1, 0)) == Point2(1, 0));
  75. Vector v2(2);
  76. v2 << 1, 0;
  77. //DefaultChart<Vector2> chart2;
  78. EXPECT(assert_equal(v2, traits<Vector2>::Local(Vector2(0, 0), Vector2(1, 0))));
  79. EXPECT(traits<Vector2>::Retract(Vector2(0, 0), v2) == Vector2(1, 0));
  80. {
  81. typedef Matrix2 ManifoldPoint;
  82. ManifoldPoint m;
  83. //DefaultChart<ManifoldPoint> chart;
  84. m << 1, 3,
  85. 2, 4;
  86. // m as per default is in column-major storage mode. So this yields a linear representation of (1, 2, 3, 4)!
  87. EXPECT(assert_equal(Vector(Vector4(1, 2, 3, 4)), Vector(traits<ManifoldPoint>::Local(ManifoldPoint::Zero(), m))));
  88. EXPECT(traits<ManifoldPoint>::Retract(m, Vector4(1, 2, 3, 4)) == 2 * m);
  89. }
  90. {
  91. typedef Eigen::Matrix<double, 1, 2> ManifoldPoint;
  92. ManifoldPoint m;
  93. //DefaultChart<ManifoldPoint> chart;
  94. m << 1, 2;
  95. EXPECT(assert_equal(Vector(Vector2(1, 2)), Vector(traits<ManifoldPoint>::Local(ManifoldPoint::Zero(), m))));
  96. EXPECT(traits<ManifoldPoint>::Retract(m, Vector2(1, 2)) == 2 * m);
  97. }
  98. {
  99. typedef Eigen::Matrix<double, 1, 1> ManifoldPoint;
  100. ManifoldPoint m;
  101. //DefaultChart<ManifoldPoint> chart;
  102. m << 1;
  103. EXPECT(assert_equal(Vector(ManifoldPoint::Ones()), Vector(traits<ManifoldPoint>::Local(ManifoldPoint::Zero(), m))));
  104. EXPECT(traits<ManifoldPoint>::Retract(m, ManifoldPoint::Ones()) == 2 * m);
  105. }
  106. //DefaultChart<double> chart3;
  107. Vector v1(1);
  108. v1 << 1;
  109. EXPECT(assert_equal(v1, traits<double>::Local(0, 1)));
  110. EXPECT_DOUBLES_EQUAL(traits<double>::Retract(0, v1), 1, 1e-9);
  111. // Dynamic does not work yet !
  112. Vector z = Z_2x1, v(2);
  113. v << 1, 0;
  114. //DefaultChart<Vector> chart4;
  115. // EXPECT(assert_equal(traits<Vector>::Local(z, v), v));
  116. // EXPECT(assert_equal(traits<Vector>::Retract(z, v), v));
  117. Vector v3(3);
  118. v3 << 1, 1, 1;
  119. Rot3 I = Rot3::identity();
  120. Rot3 R = I.retract(v3);
  121. //DefaultChart<Rot3> chart5;
  122. EXPECT(assert_equal(v3, traits<Rot3>::Local(I, R)));
  123. EXPECT(assert_equal(traits<Rot3>::Retract(I, v3), R));
  124. // Check zero vector
  125. //DefaultChart<Rot3> chart6;
  126. EXPECT(assert_equal((Vector) Z_3x1, traits<Rot3>::Local(R, R)));
  127. }
  128. //******************************************************************************
  129. int main() {
  130. TestResult tr;
  131. return TestRegistry::runAllTests(tr);
  132. }
  133. //******************************************************************************