diff --git a/gtsam/base/concepts.h b/gtsam/base/concepts.h index b7eba2635..c2c530429 100644 --- a/gtsam/base/concepts.h +++ b/gtsam/base/concepts.h @@ -363,9 +363,11 @@ struct traits_x : public internal::ScalarTraits {}; // traits for any double Eigen matrix template struct traits_x< Eigen::Matrix > { + BOOST_STATIC_ASSERT_MSG(M != Eigen::Dynamic && N != Eigen::Dynamic, + "This traits class only supports fixed-size matrices."); // Typedefs required by all manifold types. typedef vector_space_tag structure_category; - enum { dimension = (M == Eigen::Dynamic ? Eigen::Dynamic : (N == Eigen::Dynamic ? Eigen::Dynamic : M * N)) }; + enum { dimension = M * N }; typedef Eigen::Matrix TangentVector; typedef OptionalJacobian ChartJacobian; typedef Eigen::Matrix ManifoldType; @@ -405,8 +407,7 @@ struct traits_x< Eigen::Matrix > { ChartJacobian Hv = boost::none) { if (Horigin) *Horigin = Eye(origin); if (Hv) *Hv = Eye(origin); - return origin + - Eigen::Map >(v.data(), origin.rows(), origin.cols()); + return origin + Eigen::Map >(v.data(), origin.rows(), origin.cols()); } static ManifoldType Compose(const ManifoldType& m1, @@ -444,7 +445,7 @@ struct traits_x< Eigen::Matrix > { if (Hm) *Hm = Eye(m); TangentVector result(GetDimension(m)); Eigen::Map >( - result.data(), m.rows(), m.cols()) = m; + result.data()) = m; return result; } @@ -453,7 +454,7 @@ struct traits_x< Eigen::Matrix > { ManifoldType m; m.setZero(); if (Hv) *Hv = Eye(m); return m + - Eigen::Map >(v.data(), m.rows(), m.cols()); + Eigen::Map >(v.data()); } }; diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index c1ee87a26..0a783037a 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -70,7 +70,7 @@ Vector numericalGradient(boost::function h, const X& x, double factor = 1.0 / (2.0 * delta); BOOST_STATIC_ASSERT_MSG( - (boost::is_base_of::structure_category_tag>::value), + (boost::is_base_of::structure_category>::value), "Template argument X must be a manifold type."); static const int N = traits_x::dimension; BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type."); @@ -300,10 +300,11 @@ inline Matrix numericalHessian(boost::function f, const X& x, double delta = 1e-5) { BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X must be a manifold type."); + typedef Eigen::Matrix::dimension, 1> VectorD; typedef boost::function F; - typedef boost::function G; + typedef boost::function G; G ng = static_cast(numericalGradient ); - return numericalDerivative11(boost::bind(ng, f, _1, delta), x, + return numericalDerivative11(boost::bind(ng, f, _1, delta), x, delta); }