/* ---------------------------------------------------------------------------- * 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 testExpression.cpp * @date September 18, 2014 * @author Frank Dellaert * @author Paul Furgale * @brief unit tests for Block Automatic Differentiation */ #include #include #include #include #include #include #include #include #undef CHECK #include #include using boost::assign::list_of; using boost::assign::map_list_of; using namespace std; using namespace gtsam; // The DefaultChart of Camera below is laid out like Snavely's 9-dim vector typedef PinholeCamera Camera; /* ************************************************************************* */ // is_manifold TEST(Manifold, _is_manifold) { using namespace traits; EXPECT(!is_manifold::value); EXPECT(is_manifold::value); EXPECT(is_manifold::value); EXPECT(is_manifold::value); EXPECT(is_manifold::value); EXPECT(is_manifold::value); } /* ************************************************************************* */ // dimension TEST(Manifold, _dimension) { using namespace traits; EXPECT_LONGS_EQUAL(2, dimension::value); EXPECT_LONGS_EQUAL(8, dimension::value); EXPECT_LONGS_EQUAL(1, dimension::value); EXPECT_LONGS_EQUAL(Eigen::Dynamic, dimension::value); EXPECT_LONGS_EQUAL(Eigen::Dynamic, dimension::value); } /* ************************************************************************* */ // charts TEST(Manifold, DefaultChart) { DefaultChart chart1; EXPECT(chart1.local(Point2(0, 0), Point2(1, 0)) == Vector2(1, 0)); EXPECT(chart1.retract(Point2(0, 0), Vector2(1, 0)) == Point2(1, 0)); Vector v2(2); v2 << 1, 0; DefaultChart chart2; EXPECT(assert_equal(v2, chart2.local(Vector2(0, 0), Vector2(1, 0)))); EXPECT(chart2.retract(Vector2(0, 0), v2) == Vector2(1, 0)); DefaultChart chart3; Vector v1(1); v1 << 1; EXPECT(assert_equal(v1, chart3.local(0, 1))); EXPECT_DOUBLES_EQUAL(chart3.retract(0, v1), 1, 1e-9); // Dynamic does not work yet ! Vector z = zero(2), v(2); v << 1, 0; DefaultChart chart4; EXPECT(assert_equal(chart4.local(z, v), v)); EXPECT(assert_equal(chart4.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, chart5.local(I, R))); EXPECT(assert_equal(chart5.retract(I, v3), R)); // Check zero vector DefaultChart chart6; EXPECT(assert_equal(zero(3), chart6.local(R, R))); } /* ************************************************************************* */ // zero TEST(Manifold, _zero) { EXPECT(assert_equal(Pose3(), traits::zero::value())); Cal3Bundler cal(0, 0, 0); EXPECT(assert_equal(cal, traits::zero::value())); EXPECT(assert_equal(Camera(Pose3(), cal), traits::zero::value())); EXPECT(assert_equal(Point2(), traits::zero::value())); EXPECT(assert_equal(Matrix(Matrix24::Zero()), Matrix(traits::zero::value()))); EXPECT_DOUBLES_EQUAL(0.0, traits::zero::value(), 0.0); } /* ************************************************************************* */ // identity TEST(Manifold, _identity) { EXPECT(assert_equal(Pose3(), traits::identity::value())); EXPECT(assert_equal(Cal3Bundler(), traits::identity::value())); EXPECT(assert_equal(Camera(), traits::identity::value())); EXPECT(assert_equal(Point2(), traits::identity::value())); EXPECT(assert_equal(Matrix(Matrix24::Zero()), Matrix(traits::identity::value()))); EXPECT_DOUBLES_EQUAL(0.0, traits::identity::value(), 0.0); } /* ************************************************************************* */ // charts TEST(Manifold, Canonical) { Canonical chart1; EXPECT(chart1.local(Point2(1, 0))==Vector2(1, 0)); EXPECT(chart1.retract(Vector2(1, 0))==Point2(1, 0)); Vector v2(2); v2 << 1, 0; Canonical chart2; EXPECT(assert_equal(v2, chart2.local(Vector2(1, 0)))); EXPECT(chart2.retract(v2)==Vector2(1, 0)); Canonical chart3; Eigen::Matrix v1; v1 << 1; EXPECT(chart3.local(1)==v1); EXPECT_DOUBLES_EQUAL(chart3.retract(v1), 1, 1e-9); Canonical chart4; Point3 point(1, 2, 3); Vector v3(3); v3 << 1, 2, 3; EXPECT(assert_equal(v3, chart4.local(point))); EXPECT(assert_equal(chart4.retract(v3), point)); Canonical chart5; Pose3 pose(Rot3::identity(), point); Vector v6(6); v6 << 0, 0, 0, 1, 2, 3; EXPECT(assert_equal(v6, chart5.local(pose))); EXPECT(assert_equal(chart5.retract(v6), pose)); Canonical chart6; Cal3Bundler cal0(0, 0, 0); Camera camera(Pose3(), cal0); Vector z9 = Vector9::Zero(); EXPECT(assert_equal(z9, chart6.local(camera))); EXPECT(assert_equal(chart6.retract(z9), camera)); Cal3Bundler cal; // Note !! Cal3Bundler() != zero::value() Camera camera2(pose, cal); Vector v9(9); v9 << 0, 0, 0, 1, 2, 3, 1, 0, 0; EXPECT(assert_equal(v9, chart6.local(camera2))); EXPECT(assert_equal(chart6.retract(v9), camera2)); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */