Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
gtsam::Basis< DERIVED >::VectorDerivativeFunctor Class Reference

#include <Basis.h>

Inheritance diagram for gtsam::Basis< DERIVED >::VectorDerivativeFunctor:
Inheritance graph
[legend]

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_
 

Detailed Description

template<typename DERIVED>
class gtsam::Basis< DERIVED >::VectorDerivativeFunctor

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.

Definition at line 390 of file Basis.h.

Member Typedef Documentation

◆ Jacobian

template<typename DERIVED>
using gtsam::Basis< DERIVED >::VectorDerivativeFunctor::Jacobian = Eigen::Matrix<double, -1, -1>
protected

Definition at line 392 of file Basis.h.

Constructor & Destructor Documentation

◆ VectorDerivativeFunctor() [1/3]

template<typename DERIVED>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW gtsam::Basis< DERIVED >::VectorDerivativeFunctor::VectorDerivativeFunctor ( )
inline

For serialization.

Definition at line 413 of file Basis.h.

◆ VectorDerivativeFunctor() [2/3]

template<typename DERIVED>
gtsam::Basis< DERIVED >::VectorDerivativeFunctor::VectorDerivativeFunctor ( size_t  M,
size_t  N,
double  x 
)
inline

Default Constructor.

Definition at line 416 of file Basis.h.

◆ VectorDerivativeFunctor() [3/3]

template<typename DERIVED>
gtsam::Basis< DERIVED >::VectorDerivativeFunctor::VectorDerivativeFunctor ( size_t  M,
size_t  N,
double  x,
double  a,
double  b 
)
inline

Constructor, with optional interval [a,b].

Definition at line 422 of file Basis.h.

Member Function Documentation

◆ apply()

template<typename DERIVED>
Vector gtsam::Basis< DERIVED >::VectorDerivativeFunctor::apply ( const Matrix P,
OptionalJacobian< -1, -1 >  H = {} 
) const
inline

Definition at line 427 of file Basis.h.

◆ calculateJacobian()

template<typename DERIVED>
void gtsam::Basis< DERIVED >::VectorDerivativeFunctor::calculateJacobian ( )
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.

Definition at line 405 of file Basis.h.

◆ operator()()

template<typename DERIVED>
Vector gtsam::Basis< DERIVED >::VectorDerivativeFunctor::operator() ( const Matrix P,
OptionalJacobian< -1, -1 >  H = {} 
) const
inline

c++ sugar

Definition at line 433 of file Basis.h.

Member Data Documentation

◆ H_

template<typename DERIVED>
Jacobian gtsam::Basis< DERIVED >::VectorDerivativeFunctor::H_
protected

Definition at line 393 of file Basis.h.

◆ M_

template<typename DERIVED>
size_t gtsam::Basis< DERIVED >::VectorDerivativeFunctor::M_
protected

Definition at line 395 of file Basis.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:15