From 10b37db234ed4469a4db4d8b2937ded4c96107b9 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Sun, 10 Apr 2011 17:47:22 +0000 Subject: [PATCH] fixing compilation problem in numericalHessian and re-enable the unittest --- gtsam/base/numericalDerivative.h | 7 +- gtsam/base/tests/testNumericalDerivative.cpp | 74 ++++++++++---------- 2 files changed, 41 insertions(+), 40 deletions(-) diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index 96e1da05b..fb6f75fba 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -465,9 +465,10 @@ namespace gtsam { * @return n*n Hessian matrix computed via central differencing */ template - inline Matrix numericalHessian(const boost::function& f, const X& x, double delta=1e-5) { - return numericalDerivative11( - boost::function(boost::bind(numericalGradient, f, _1, delta)), x, delta); + inline Matrix numericalHessian(boost::function f, const X& x, double delta=1e-5) { + Vector (*numGrad)(boost::function,const X&, double) = &numericalGradient; + return numericalDerivative11(boost::function(boost::bind( + numGrad, f, _1, delta)), x, delta); } template diff --git a/gtsam/base/tests/testNumericalDerivative.cpp b/gtsam/base/tests/testNumericalDerivative.cpp index 023bb1718..7cdabbbe9 100644 --- a/gtsam/base/tests/testNumericalDerivative.cpp +++ b/gtsam/base/tests/testNumericalDerivative.cpp @@ -22,43 +22,43 @@ using namespace gtsam; -///* ************************************************************************* */ -//double f(const LieVector& x) { -// assert(x.size() == 2); -// return sin(x(0)) + cos(x(1)); -//} -// -///* ************************************************************************* */ -//TEST_UNSAFE(testNumericalDerivative, numericalHessian) { -// LieVector center(2, 1.0, 1.0); -// -// Matrix expected = Matrix_(2,2, -// -sin(center(0)), 0.0, -// 0.0, -cos(center(1))); -// -// Matrix actual = numericalHessian(f, center); -// -// EXPECT(assert_equal(expected, actual, 1e-5)); -//} -// -///* ************************************************************************* */ -//double f2(const LieVector& x) { -// assert(x.size() == 2); -// return sin(x(0)) * cos(x(1)); -//} -// -///* ************************************************************************* */ -//TEST_UNSAFE(testNumericalDerivative, numericalHessian2) { -// LieVector center(2, 0.5, 1.0); -// -// Matrix expected = Matrix_(2,2, -// -cos(center(1))*sin(center(0)), -sin(center(1))*cos(center(0)), -// -cos(center(0))*sin(center(1)), -sin(center(0))*cos(center(1))); -// -// Matrix actual = numericalHessian(f2, center); -// -// EXPECT(assert_equal(expected, actual, 1e-5)); -//} +/* ************************************************************************* */ +double f(const LieVector& x) { + assert(x.size() == 2); + return sin(x(0)) + cos(x(1)); +} + +/* ************************************************************************* */ +TEST_UNSAFE(testNumericalDerivative, numericalHessian) { + LieVector center(2, 1.0, 1.0); + + Matrix expected = Matrix_(2,2, + -sin(center(0)), 0.0, + 0.0, -cos(center(1))); + + Matrix actual = numericalHessian(f, center); + + EXPECT(assert_equal(expected, actual, 1e-5)); +} + +/* ************************************************************************* */ +double f2(const LieVector& x) { + assert(x.size() == 2); + return sin(x(0)) * cos(x(1)); +} + +/* ************************************************************************* */ +TEST_UNSAFE(testNumericalDerivative, numericalHessian2) { + LieVector center(2, 0.5, 1.0); + + Matrix expected = Matrix_(2,2, + -cos(center(1))*sin(center(0)), -sin(center(1))*cos(center(0)), + -cos(center(0))*sin(center(1)), -sin(center(0))*cos(center(1))); + + Matrix actual = numericalHessian(f2, center); + + EXPECT(assert_equal(expected, actual, 1e-5)); +} /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); }