/** * @file numericalDerivative.h * @brief Some functions to compute numerical derivatives * @author Frank Dellaert */ // \callgraph #pragma once #include "Matrix.h" namespace gtsam { /** * Compute numerical derivative in arument 1 of unary function * @param h unary function yielding m-vector * @param x n-dimensional value at which to evaluate h * @param delta increment for numerical derivative * @return m*n Jacobian computed via central differencing */ Matrix NumericalDerivative11 (Vector (*h)(const Vector&), const Vector& x, double delta=1e-5); /** * templated version (starts with LOWERCASE n) * Class Y is the output arguement * Class X is the input argument * both classes need dim, exmap, vector */ template Matrix numericalDerivative11 (Y (*h)(const X&), const X& x, double delta=1e-5) { Vector hx = h(x).vector(); double factor = 1.0/(2.0*delta); const size_t m = hx.size(), n = x.dim(); Vector d(n,0.0); Matrix H = zeros(m,n); for (size_t j=0;j Matrix numericalDerivative21 (Y (*h)(const X1&, const X2&), const X1& x1, const X2& x2, double delta=1e-5) { Vector hx = h(x1,x2).vector(); double factor = 1.0/(2.0*delta); const size_t m = hx.size(), n = x1.dim(); Vector d(n,0.0); Matrix H = zeros(m,n); for (size_t j=0;j Matrix numericalDerivative22 (Y (*h)(const X1&, const X2&), const X1& x1, const X2& x2, double delta=1e-5) { Vector hx = h(x1,x2).vector(); double factor = 1.0/(2.0*delta); const size_t m = hx.size(), n = x2.dim(); Vector d(n,0.0); Matrix H = zeros(m,n); for (size_t j=0;j Matrix numericalDerivative31 (Y (*h)(const X1&, const X2&, const X3&), const X1& x1, const X2& x2, const X3& x3, double delta=1e-5) { Vector hx = h(x1,x2,x3).vector(); double factor = 1.0/(2.0*delta); const size_t m = hx.size(), n = x1.dim(); Vector d(n,0.0); Matrix H = zeros(m,n); for (size_t j=0;j