fixing compilation problem in numericalHessian and re-enable the unittest

release/4.3a0
Duy-Nguyen Ta 2011-04-10 17:47:22 +00:00
parent 6a444b558d
commit 10b37db234
2 changed files with 41 additions and 40 deletions

View File

@ -465,9 +465,10 @@ namespace gtsam {
* @return n*n Hessian matrix computed via central differencing
*/
template<class X>
inline Matrix numericalHessian(const boost::function<double(const X&)>& f, const X& x, double delta=1e-5) {
return numericalDerivative11<X>(
boost::function<LieVector(const X&)>(boost::bind(numericalGradient<X>, f, _1, delta)), x, delta);
inline Matrix numericalHessian(boost::function<double(const X&)> f, const X& x, double delta=1e-5) {
Vector (*numGrad)(boost::function<double(const X&)>,const X&, double) = &numericalGradient<X>;
return numericalDerivative11<X>(boost::function<Vector(const X&)>(boost::bind(
numGrad, f, _1, delta)), x, delta);
}
template<class X>

View File

@ -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); }