/* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) * See LICENSE for the license information * -------------------------------1------------------------------------------- */ /** * @file testManifold.cpp * @date September 18, 2014 * @author Frank Dellaert * @author Paul Furgale * @brief unit tests for Manifold type machinery */ #include #include #include #include #include #include #include #include #undef CHECK #include using namespace std; using namespace gtsam; // The DefaultChart of Camera below is laid out like Snavely's 9-dim vector typedef PinholeCamera Camera; //****************************************************************************** TEST(Manifold, SomeManifoldsGTSAM) { //GTSAM_CONCEPT_ASSERT(IsManifold); // integer is not a manifold GTSAM_CONCEPT_ASSERT1(IsManifold); GTSAM_CONCEPT_ASSERT2(IsManifold); GTSAM_CONCEPT_ASSERT3(IsManifold); GTSAM_CONCEPT_ASSERT4(IsManifold); } //****************************************************************************** TEST(Manifold, SomeLieGroupsGTSAM) { GTSAM_CONCEPT_ASSERT1(IsLieGroup); GTSAM_CONCEPT_ASSERT2(IsLieGroup); GTSAM_CONCEPT_ASSERT3(IsLieGroup); GTSAM_CONCEPT_ASSERT4(IsLieGroup); } //****************************************************************************** TEST(Manifold, SomeVectorSpacesGTSAM) { GTSAM_CONCEPT_ASSERT1(IsVectorSpace); GTSAM_CONCEPT_ASSERT2(IsVectorSpace); GTSAM_CONCEPT_ASSERT3(IsVectorSpace); GTSAM_CONCEPT_ASSERT4(IsVectorSpace); } //****************************************************************************** // dimension TEST(Manifold, _dimension) { //using namespace traits; EXPECT_LONGS_EQUAL(2, traits::dimension); EXPECT_LONGS_EQUAL(8, traits::dimension); EXPECT_LONGS_EQUAL(1, traits::dimension); } //****************************************************************************** TEST(Manifold, Identity) { EXPECT_DOUBLES_EQUAL(0.0, traits::Identity(), 0.0); EXPECT(assert_equal(Matrix(Matrix24::Zero()), Matrix(traits::Identity()))); EXPECT(assert_equal(Pose3(), traits::Identity())); EXPECT(assert_equal(Point2(0,0), traits::Identity())); } //****************************************************************************** // charts TEST(Manifold, DefaultChart) { //DefaultChart chart1; EXPECT(traits::Local(Point2(0, 0), Point2(1, 0)) == Vector2(1, 0)); EXPECT(traits::Retract(Point2(0, 0), Vector2(1, 0)) == Point2(1, 0)); Vector v2(2); v2 << 1, 0; //DefaultChart chart2; EXPECT(assert_equal(v2, traits::Local(Vector2(0, 0), Vector2(1, 0)))); EXPECT(traits::Retract(Vector2(0, 0), v2) == Vector2(1, 0)); { typedef Matrix2 ManifoldPoint; ManifoldPoint m; //DefaultChart chart; m << 1, 3, 2, 4; // m as per default is in column-major storage mode. So this yields a linear representation of (1, 2, 3, 4)! EXPECT(assert_equal(Vector(Vector4(1, 2, 3, 4)), Vector(traits::Local(ManifoldPoint::Zero(), m)))); EXPECT(traits::Retract(m, Vector4(1, 2, 3, 4)) == 2 * m); } { typedef Eigen::Matrix ManifoldPoint; ManifoldPoint m; //DefaultChart chart; m << 1, 2; EXPECT(assert_equal(Vector(Vector2(1, 2)), Vector(traits::Local(ManifoldPoint::Zero(), m)))); EXPECT(traits::Retract(m, Vector2(1, 2)) == 2 * m); } { typedef Eigen::Matrix ManifoldPoint; ManifoldPoint m; //DefaultChart chart; m << 1; EXPECT(assert_equal(Vector(ManifoldPoint::Ones()), Vector(traits::Local(ManifoldPoint::Zero(), m)))); EXPECT(traits::Retract(m, ManifoldPoint::Ones()) == 2 * m); } //DefaultChart chart3; Vector v1(1); v1 << 1; EXPECT(assert_equal(v1, traits::Local(0, 1))); EXPECT_DOUBLES_EQUAL(traits::Retract(0, v1), 1, 1e-9); // Dynamic does not work yet ! Vector z = Z_2x1, v(2); v << 1, 0; //DefaultChart chart4; // EXPECT(assert_equal(traits::Local(z, v), v)); // EXPECT(assert_equal(traits::Retract(z, v), v)); Vector v3(3); v3 << 1, 1, 1; Rot3 I = Rot3::Identity(); Rot3 R = I.retract(v3); //DefaultChart chart5; EXPECT(assert_equal(v3, traits::Local(I, R))); EXPECT(assert_equal(traits::Retract(I, v3), R)); // Check zero vector //DefaultChart chart6; EXPECT(assert_equal((Vector) Z_3x1, traits::Local(R, R))); } //****************************************************************************** int main() { TestResult tr; return TestRegistry::runAllTests(tr); } //******************************************************************************