/* ---------------------------------------------------------------------------- * 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; /* ************************************************************************* */ template Point2 uncalibrate(const CAL& K, const Point2& p, boost::optional Dcal, boost::optional Dp) { return K.uncalibrate(p, Dcal, Dp); } static const Rot3 someR = Rot3::RzRyRx(1, 2, 3); /* ************************************************************************* */ // Constant TEST(Expression, constant) { Expression R(someR); Values values; JacobianMap actualMap; Rot3 actual = R.value(values, actualMap); EXPECT(assert_equal(someR, actual)); JacobianMap expected; EXPECT(actualMap == expected); EXPECT_LONGS_EQUAL(0, R.traceSize()) } /* ************************************************************************* */ // Leaf TEST(Expression, Leaf) { Expression R(100); Values values; values.insert(100, someR); JacobianMap expected; Matrix H = eye(3); expected.insert(make_pair(100, H.block(0, 0, 3, 3))); JacobianMap actualMap2; actualMap2.insert(make_pair(100, H.block(0, 0, 3, 3))); Rot3 actual2 = R.reverse(values, actualMap2); EXPECT(assert_equal(someR, actual2)); EXPECT(actualMap2 == expected); } /* ************************************************************************* */ // Many Leaves TEST(Expression, Leaves) { Values values; Point3 somePoint(1, 2, 3); values.insert(Symbol('p', 10), somePoint); std::vector > points = createUnknowns(10, 'p', 1); EXPECT(assert_equal(somePoint,points.back().value(values))); } /* ************************************************************************* */ //TEST(Expression, NullaryMethod) { // Expression p(67); // Expression norm(p, &Point3::norm); // Values values; // values.insert(67,Point3(3,4,5)); // Augmented a = norm.augmented(values); // EXPECT(a.value() == sqrt(50)); // JacobianMap expected; // expected[67] = (Matrix(1,3) << 3/sqrt(50),4/sqrt(50),5/sqrt(50)); // EXPECT(assert_equal(expected.at(67),a.jacobians().at(67))); //} /* ************************************************************************* */ // Binary(Leaf,Leaf) namespace binary { // Create leaves Expression x(1); Expression p(2); Expression p_cam(x, &Pose3::transform_to, p); } /* ************************************************************************* */ // keys TEST(Expression, BinaryKeys) { set expected = list_of(1)(2); EXPECT(expected == binary::p_cam.keys()); } /* ************************************************************************* */ // dimensions TEST(Expression, BinaryDimensions) { map actual, expected = map_list_of(1, 6)(2, 3); binary::p_cam.dims(actual); EXPECT(actual==expected); } /* ************************************************************************* */ // dimensions TEST(Expression, BinaryTraceSize) { typedef BinaryExpression Binary; size_t expectedTraceSize = sizeof(Binary::Record); EXPECT_LONGS_EQUAL(expectedTraceSize, binary::p_cam.traceSize()); } /* ************************************************************************* */ // Binary(Leaf,Unary(Binary(Leaf,Leaf))) namespace tree { using namespace binary; // Create leaves Expression K(3); // Create expression tree Expression projection(PinholeCamera::project_to_camera, p_cam); Expression uv_hat(uncalibrate, K, projection); } /* ************************************************************************* */ // keys TEST(Expression, TreeKeys) { set expected = list_of(1)(2)(3); EXPECT(expected == tree::uv_hat.keys()); } /* ************************************************************************* */ // dimensions TEST(Expression, TreeDimensions) { map actual, expected = map_list_of(1, 6)(2, 3)(3, 5); tree::uv_hat.dims(actual); EXPECT(actual==expected); } /* ************************************************************************* */ // TraceSize TEST(Expression, TreeTraceSize) { typedef UnaryExpression Unary; typedef BinaryExpression Binary1; typedef BinaryExpression Binary2; size_t expectedTraceSize = sizeof(Unary::Record) + sizeof(Binary1::Record) + sizeof(Binary2::Record); EXPECT_LONGS_EQUAL(expectedTraceSize, tree::uv_hat.traceSize()); } /* ************************************************************************* */ TEST(Expression, compose1) { // Create expression Expression R1(1), R2(2); Expression R3 = R1 * R2; // Check keys set expected = list_of(1)(2); EXPECT(expected == R3.keys()); } /* ************************************************************************* */ // Test compose with arguments referring to the same rotation TEST(Expression, compose2) { // Create expression Expression R1(1), R2(1); Expression R3 = R1 * R2; // Check keys set expected = list_of(1); EXPECT(expected == R3.keys()); } /* ************************************************************************* */ // Test compose with one arguments referring to constant rotation TEST(Expression, compose3) { // Create expression Expression R1(Rot3::identity()), R2(3); Expression R3 = R1 * R2; // Check keys set expected = list_of(3); EXPECT(expected == R3.keys()); } /* ************************************************************************* */ // Test with ternary function Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3, boost::optional H1, boost::optional H2, boost::optional H3) { // return dummy derivatives (not correct, but that's ok for testing here) if (H1) *H1 = eye(3); if (H2) *H2 = eye(3); if (H3) *H3 = eye(3); return R1 * (R2 * R3); } TEST(Expression, ternary) { // Create expression Expression A(1), B(2), C(3); Expression ABC(composeThree, A, B, C); // Check keys set expected = list_of(1)(2)(3); EXPECT(expected == ABC.keys()); } /* ************************************************************************* */ // Some Ceres Snippets copied for testing // Copyright 2010, 2011, 2012 Google Inc. All rights reserved. template inline T &RowMajorAccess(T *base, int rows, int cols, int i, int j) { return base[cols * i + j]; } inline double RandDouble() { double r = static_cast(rand()); return r / RAND_MAX; } // A structure for projecting a 3x4 camera matrix and a // homogeneous 3D point, to a 2D inhomogeneous point. struct Projective { // Function that takes P and X as separate vectors: // P, X -> x template bool operator()(A const P[12], A const X[4], A x[2]) const { A PX[3]; for (int i = 0; i < 3; ++i) { PX[i] = RowMajorAccess(P, 3, 4, i, 0) * X[0] + RowMajorAccess(P, 3, 4, i, 1) * X[1] + RowMajorAccess(P, 3, 4, i, 2) * X[2] + RowMajorAccess(P, 3, 4, i, 3) * X[3]; } if (PX[2] != 0.0) { x[0] = PX[0] / PX[2]; x[1] = PX[1] / PX[2]; return true; } return false; } Vector2 operator()(const MatrixRowMajor& P, const Vector4& X) const { Vector2 x; if (operator()(P.data(), X.data(), x.data())) return x; else throw std::runtime_error("Projective fails"); } }; /* ************************************************************************* */ #include template struct manifold_traits { typedef T type; static const size_t dimension = T::dimension; typedef Eigen::Matrix tangent; static tangent localCoordinates(const T& t1, const T& t2) { return t1.localCoordinates(t2); } static type retract(const type& t, const tangent& d) { return t.retract(d); } }; // Adapt constant size Eigen::Matrix types as manifold types template struct manifold_traits > { BOOST_STATIC_ASSERT(M!=Eigen::Dynamic && N!=Eigen::Dynamic); typedef Eigen::Matrix type; static const size_t dimension = M * N; typedef Eigen::Matrix tangent; static tangent localCoordinates(const type& t1, const type& t2) { type diff = t2 - t1; return tangent(Eigen::Map(diff.data())); } static type retract(const type& t, const tangent& d) { type sum = t + Eigen::Map(d.data()); return sum; } }; // Test dimension traits TEST(Expression, Traits) { EXPECT_LONGS_EQUAL(2, manifold_traits::dimension); EXPECT_LONGS_EQUAL(8, manifold_traits::dimension); } template Matrix numericalDerivative21(boost::function h, const X1& x1, const X2& x2, double delta = 1e-5) { Y hx = h(x1, x2); double factor = 1.0 / (2.0 * delta); static const size_t m = manifold_traits::dimension, n = manifold_traits::dimension; Eigen::Matrix d; d.setZero(); Matrix H = zeros(m, n); for (size_t j = 0; j < n; j++) { d(j) += delta; Vector hxplus = manifold_traits::localCoordinates(hx, h(manifold_traits::retract(x1, d), x2)); d(j) -= 2 * delta; Vector hxmin = manifold_traits::localCoordinates(hx, h(manifold_traits::retract(x1, d), x2)); d(j) += delta; H.block(0, j) << (hxplus - hxmin) * factor; } return H; } template Matrix numericalDerivative22(boost::function h, const X1& x1, const X2& x2, double delta = 1e-5) { Y hx = h(x1, x2); double factor = 1.0 / (2.0 * delta); static const size_t m = manifold_traits::dimension, n = manifold_traits::dimension; Eigen::Matrix d; d.setZero(); Matrix H = zeros(m, n); for (size_t j = 0; j < n; j++) { d(j) += delta; Vector hxplus = manifold_traits::localCoordinates(hx, h(x1, manifold_traits::retract(x2, d))); d(j) -= 2 * delta; Vector hxmin = manifold_traits::localCoordinates(hx, h(x1, manifold_traits::retract(x2, d))); d(j) += delta; H.block(0, j) << (hxplus - hxmin) * factor; } return H; } /* ************************************************************************* */ // Test Ceres AutoDiff TEST(Expression, AutoDiff) { using ceres::internal::AutoDiff; // Instantiate function Projective projective; // Make arguments typedef Eigen::Matrix M; M P; P << 1, 0, 0, 0, 0, 1, 0, 5, 0, 0, 1, 0; Vector4 X(10, 0, 5, 1); // Apply the mapping, to get image point b_x. Vector expected = Vector2(2, 1); Vector2 actual = projective(P, X); EXPECT(assert_equal(expected,actual,1e-9)); // Get expected derivatives Matrix E1 = numericalDerivative21(Projective(), P, X); Matrix E2 = numericalDerivative22(Projective(), P, X); // Get derivatives with AutoDiff Vector2 actual2; MatrixRowMajor H1(2, 12), H2(2, 4); double *parameters[] = { P.data(), X.data() }; double *jacobians[] = { H1.data(), H2.data() }; CHECK( (AutoDiff::Differentiate( projective, parameters, 2, actual2.data(), jacobians))); EXPECT(assert_equal(E1,H1,1e-8)); EXPECT(assert_equal(E2,H2,1e-8)); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */