diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index cc1cbdb51..a9a088108 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -67,28 +67,29 @@ struct FixedSizeMatrix { } /** - * Numerically compute gradient of scalar function + * @brief Numerically compute gradient of scalar function + * @return n-dimensional gradient computed via central differencing * Class X is the input argument * The class X needs to have dim, expmap, logmap + * int N is the dimension of the X input value if variable dimension type but known at test time */ -template -typename internal::FixedSizeMatrix::type numericalGradient(boost::function h, const X& x, - double delta = 1e-5) { + +template ::dimension> +typename Eigen::Matrix numericalGradient( + boost::function h, const X& x, double delta = 1e-5) { double factor = 1.0 / (2.0 * delta); BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X must be a manifold type."); - static const int N = traits::dimension; - BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type."); - - typedef typename traits::TangentVector TangentX; + BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type or N must be specified."); // Prepare a tangent vector to perturb x with, only works for fixed size - TangentX d; + typename traits::TangentVector d; d.setZero(); - Eigen::Matrix g; g.setZero(); // Can be fixed size + Eigen::Matrix g; + g.setZero(); for (int j = 0; j < N; j++) { d(j) = delta; double hxplus = h(traits::Retract(x, d)); @@ -108,37 +109,34 @@ typename internal::FixedSizeMatrix::type numericalGradient(boost::function +template ::dimension> // TODO Should compute fixed-size matrix -typename internal::FixedSizeMatrix::type numericalDerivative11(boost::function h, const X& x, - double delta = 1e-5) { - +typename internal::FixedSizeMatrix::type numericalDerivative11( + boost::function h, const X& x, double delta = 1e-5) { typedef typename internal::FixedSizeMatrix::type Matrix; BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument Y must be a manifold type."); typedef traits TraitsY; - typedef typename TraitsY::TangentVector TangentY; BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), "Template argument X must be a manifold type."); - static const int N = traits::dimension; - BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type."); + BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type or N must be specified."); typedef traits TraitsX; - typedef typename TraitsX::TangentVector TangentX; // get value at x, and corresponding chart const Y hx = h(x); // Bit of a hack for now to find number of rows - const TangentY zeroY = TraitsY::Local(hx, hx); + const typename TraitsY::TangentVector zeroY = TraitsY::Local(hx, hx); const size_t m = zeroY.size(); // Prepare a tangent vector to perturb x with, only works for fixed size - TangentX dx; + Eigen::Matrix dx; dx.setZero(); // Fill in Jacobian H @@ -146,9 +144,9 @@ typename internal::FixedSizeMatrix::type numericalDerivative11(boost::funct const double factor = 1.0 / (2.0 * delta); for (int j = 0; j < N; j++) { dx(j) = delta; - const TangentY dy1 = TraitsY::Local(hx, h(TraitsX::Retract(x, dx))); + const auto dy1 = TraitsY::Local(hx, h(TraitsX::Retract(x, dx))); dx(j) = -delta; - const TangentY dy2 = TraitsY::Local(hx, h(TraitsX::Retract(x, dx))); + const auto dy2 = TraitsY::Local(hx, h(TraitsX::Retract(x, dx))); dx(j) = 0; H.col(j) << (dy1 - dy2) * factor; }