Public Member Functions | Private Types | List of all members
gtsam::Basis< DERIVED >::ManifoldEvaluationFunctor< T > Class Template Reference

#include <Basis.h>

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

Public Member Functions

T apply (const Matrix &P, OptionalJacobian< -1, -1 > H={}) const
 Manifold evaluation. More...
 
 ManifoldEvaluationFunctor ()
 For serialization. More...
 
 ManifoldEvaluationFunctor (size_t N, double x)
 Default Constructor. More...
 
 ManifoldEvaluationFunctor (size_t N, double x, double a, double b)
 Constructor, with interval [a,b]. More...
 
T operator() (const Matrix &P, OptionalJacobian< -1, -1 > H={}) const
 c++ sugar More...
 
- Public Member Functions inherited from gtsam::Basis< DERIVED >::VectorEvaluationFunctor
Vector apply (const Matrix &P, OptionalJacobian< -1, -1 > H={}) const
 M-dimensional evaluation. More...
 
Vector operator() (const Matrix &P, OptionalJacobian< -1, -1 > H={}) const
 c++ sugar More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VectorEvaluationFunctor ()
 For serialization. More...
 
 VectorEvaluationFunctor (size_t M, size_t N, double x)
 Default Constructor. More...
 
 VectorEvaluationFunctor (size_t M, size_t N, double x, double a, double b)
 Constructor, with interval [a,b]. More...
 

Private Types

enum  { M = traits<T>::dimension }
 
using Base = VectorEvaluationFunctor
 

Additional Inherited Members

- Protected Types inherited from gtsam::Basis< DERIVED >::VectorEvaluationFunctor
using Jacobian = Eigen::Matrix< double, -1, -1 >
 
- Protected Member Functions inherited from gtsam::Basis< DERIVED >::VectorEvaluationFunctor
void calculateJacobian ()
 
- Protected Member Functions inherited from gtsam::Basis< DERIVED >::EvaluationFunctor
double apply (const typename DERIVED::Parameters &p, OptionalJacobian<-1, -1 > H={}) const
 Regular 1D evaluation. More...
 
 EvaluationFunctor ()
 For serialization. More...
 
 EvaluationFunctor (size_t N, double x)
 Constructor with interval [a,b]. More...
 
 EvaluationFunctor (size_t N, double x, double a, double b)
 Constructor with interval [a,b]. More...
 
double operator() (const typename DERIVED::Parameters &p, OptionalJacobian<-1, -1 > H={}) const
 c++ sugar More...
 
void print (const std::string &s="") const
 
- Protected Attributes inherited from gtsam::Basis< DERIVED >::VectorEvaluationFunctor
Jacobian H_
 
size_t M_
 
- Protected Attributes inherited from gtsam::Basis< DERIVED >::EvaluationFunctor
Weights weights_
 

Detailed Description

template<typename DERIVED>
template<class T>
class gtsam::Basis< DERIVED >::ManifoldEvaluationFunctor< T >

Manifold EvaluationFunctor at a given x, applied to a parameter Matrix. This functor is used to evaluate a parameterized function at a given scalar value x. When given a specific M*N parameters, returns an M-vector the M corresponding functions at x, possibly with Jacobians wrpt the parameters.

The difference with the VectorEvaluationFunctor is that after computing the M*1 vector xi=F(x;P), with x a scalar and P the M*N parameter vector, we also retract xi back to the T manifold. For example, if T==Rot3, then we first compute a 3-vector xi using x and P, and then map that 3-vector xi back to the Rot3 manifold, yielding a valid 3D rotation.

Definition at line 293 of file Basis.h.

Member Typedef Documentation

◆ Base

template<typename DERIVED >
template<class T >
using gtsam::Basis< DERIVED >::ManifoldEvaluationFunctor< T >::Base = VectorEvaluationFunctor
private

Definition at line 295 of file Basis.h.

Member Enumeration Documentation

◆ anonymous enum

template<typename DERIVED >
template<class T >
anonymous enum
private
Enumerator

Definition at line 294 of file Basis.h.

Constructor & Destructor Documentation

◆ ManifoldEvaluationFunctor() [1/3]

template<typename DERIVED >
template<class T >
gtsam::Basis< DERIVED >::ManifoldEvaluationFunctor< T >::ManifoldEvaluationFunctor ( )
inline

For serialization.

Definition at line 299 of file Basis.h.

◆ ManifoldEvaluationFunctor() [2/3]

template<typename DERIVED >
template<class T >
gtsam::Basis< DERIVED >::ManifoldEvaluationFunctor< T >::ManifoldEvaluationFunctor ( size_t  N,
double  x 
)
inline

Default Constructor.

Definition at line 302 of file Basis.h.

◆ ManifoldEvaluationFunctor() [3/3]

template<typename DERIVED >
template<class T >
gtsam::Basis< DERIVED >::ManifoldEvaluationFunctor< T >::ManifoldEvaluationFunctor ( size_t  N,
double  x,
double  a,
double  b 
)
inline

Constructor, with interval [a,b].

Definition at line 305 of file Basis.h.

Member Function Documentation

◆ apply()

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

Manifold evaluation.

Definition at line 309 of file Basis.h.

◆ operator()()

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

c++ sugar

Definition at line 327 of file Basis.h.


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


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:13:07