diff --git a/gtsam_unstable/nonlinear/tests/testExpression.cpp b/gtsam_unstable/nonlinear/tests/testExpression.cpp index b7f1cae5e..28d160799 100644 --- a/gtsam_unstable/nonlinear/tests/testExpression.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpression.cpp @@ -346,6 +346,22 @@ struct TangentVector { typedef Eigen::Matrix::value, 1> type; }; +// default localCoordinates +template +struct localCoordinates { + typename TangentVector::type operator()(const T& t1, const T& t2) { + return t1.localCoordinates(t2); + } +}; + +// default retract +template +struct retract { + T operator()(const T& t, const typename TangentVector::type& d) { + return t.retract(d); + } +}; + // Fixed size Eigen::Matrix type template @@ -358,6 +374,24 @@ struct dimension > : public integral_consta BOOST_STATIC_ASSERT(M!=Eigen::Dynamic && N!=Eigen::Dynamic); }; +template +struct localCoordinates > { + typedef Eigen::Matrix T; + typedef typename TangentVector::type result_type; + result_type operator()(const T& t1, const T& t2) { + T diff = t2 - t1; + return result_type(Eigen::Map(diff.data())); + } +}; + +template +struct retract > { + typedef Eigen::Matrix T; + T operator()(const T& t, const typename TangentVector::type& d) { + return t + Eigen::Map(d.data()); + } +}; + // Point2 template<> @@ -368,36 +402,6 @@ template<> struct dimension : public integral_constant { }; -template -struct manifold_traits { - typedef T type; - static typename TangentVector::type localCoordinates(const T& t1, - const T& t2) { - return t1.localCoordinates(t2); - } - static type retract(const type& t, const typename TangentVector::type& 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 typename TangentVector::type localCoordinates(const type& t1, - const type& t2) { - type diff = t2 - t1; - return typename TangentVector::type( - Eigen::Map::type>(diff.data())); - } - static type retract(const type& t, - const typename TangentVector::type& d) { - type sum = t + Eigen::Map(d.data()); - return sum; - } -}; - // is_manifold TEST(Expression, is_manifold) { EXPECT(!is_manifold::value); @@ -411,6 +415,12 @@ TEST(Expression, dimension) { EXPECT_LONGS_EQUAL(8, dimension::value); } +// localCoordinates +TEST(Expression, localCoordinates) { + EXPECT(localCoordinates()(Point2(0,0),Point2(1,0))==Vector2(1,0)); + EXPECT(localCoordinates()(Vector2(0,0),Vector2(1,0))==Vector2(1,0)); +} + /* ************************************************************************* */ // New-style numerical derivatives using manifold_traits template @@ -427,11 +437,9 @@ Matrix numericalDerivative(boost::function h, const X& x, for (size_t j = 0; j < N; j++) { d.setZero(); d(j) = delta; - Vector hxplus = manifold_traits::localCoordinates(hx, - h(manifold_traits::retract(x, d))); + Vector hxplus = localCoordinates()(hx, h(retract()(x, d))); d(j) = -delta; - Vector hxmin = manifold_traits::localCoordinates(hx, - h(manifold_traits::retract(x, d))); + Vector hxmin = localCoordinates()(hx, h(retract()(x, d))); H.block(0, j) << (hxplus - hxmin) * factor; } return H;