#include <Basis.h>
Public Member Functions | |
Vector | apply (const Matrix &P, OptionalJacobian< -1, -1 > H={}) const |
Vector | operator() (const Matrix &P, OptionalJacobian< -1, -1 > H={}) const |
c++ sugar More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | VectorDerivativeFunctor () |
For serialization. More... | |
VectorDerivativeFunctor (size_t M, size_t N, double x) | |
Default Constructor. More... | |
VectorDerivativeFunctor (size_t M, size_t N, double x, double a, double b) | |
Constructor, with optional interval [a,b]. More... | |
Protected Types | |
using | Jacobian = Eigen::Matrix< double, -1, -1 > |
Protected Member Functions | |
void | calculateJacobian () |
Protected Member Functions inherited from gtsam::Basis< DERIVED >::DerivativeFunctorBase | |
DerivativeFunctorBase () | |
For serialization. More... | |
DerivativeFunctorBase (size_t N, double x) | |
DerivativeFunctorBase (size_t N, double x, double a, double b) | |
void | print (const std::string &s="") const |
Protected Attributes | |
Jacobian | H_ |
size_t | M_ |
Protected Attributes inherited from gtsam::Basis< DERIVED >::DerivativeFunctorBase | |
Weights | weights_ |
VectorDerivativeFunctor at a given x, applied to a parameter Matrix.
This functor is used to evaluate the derivatives of a parameterized function at a given scalar value x. When given a specific M*N parameters, returns an M-vector the M corresponding function derivatives at x, possibly with Jacobians wrpt the parameters.
|
protected |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlineprotected |
Calculate the M*(M*N)
Jacobian of this functor with respect to the M*N parameter matrix P
. We flatten assuming column-major order, e.g., if N=3 and M=2, we have H =[ w(0) 0 w(1) 0 w(2) 0 0 w(0) 0 w(1) 0 w(2) ] i.e., the Kronecker product of weights_ with the MxM identity matrix.
|
inline |
|
protected |
|
protected |