Public Member Functions | Private Types | List of all members
gtsam::ComponentDerivativeFactor< BASIS > Class Template Reference

#include <BasisFactors.h>

Inheritance diagram for gtsam::ComponentDerivativeFactor< BASIS >:
Inheritance graph
[legend]

Public Member Functions

 ComponentDerivativeFactor ()
 
 ComponentDerivativeFactor (Key key, const double &z, const SharedNoiseModel &model, const size_t P, const size_t N, size_t i, double x)
 Construct a new ComponentDerivativeFactor object. More...
 
 ComponentDerivativeFactor (Key key, const double &z, const SharedNoiseModel &model, const size_t P, const size_t N, size_t i, double x, double a, double b)
 Construct a new ComponentDerivativeFactor object. More...
 
virtual ~ComponentDerivativeFactor ()
 
- Public Member Functions inherited from gtsam::FunctorizedFactor< double, Matrix >
NonlinearFactor::shared_ptr clone () const override
 
Vector evaluateError (const Matrix &params, OptionalMatrixType H) const override
 
 FunctorizedFactor ()
 
 FunctorizedFactor (Key key, const double &z, const SharedNoiseModel &model, const std::function< double(Matrix, OptionalMatrixType)> func)
 
 ~FunctorizedFactor () override
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
bool equals (const NonlinearFactor &other, double tol=1e-9) const override
 
- Public Member Functions inherited from gtsam::NoiseModelFactorN< Matrix >
Key key () const
 
 ~NoiseModelFactorN () override
 
 NoiseModelFactorN ()
 Default Constructor for I/O. More...
 
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
 
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys)
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
virtual Vector evaluateError (const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
 
Vector evaluateError (const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
 
Vector evaluateError (const ValueTypes &... x) const
 
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
AreAllMatrixPtrs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
Key key1 () const
 
Key key2 () const
 
Key key3 () const
 
Key key4 () const
 
Key key5 () const
 
Key key6 () const
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
size_t dim () const override
 
double error (const Values &c) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const SharedNoiseModelnoiseModel () const
 access to the noise model More...
 
 NoiseModelFactor ()
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 
Vector unweightedWhitenedError (const Values &c) const
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
double weight (const Values &c) const
 
Vector whitenedError (const Values &c) const
 
 ~NoiseModelFactor () override
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 
double error (const HybridValues &c) const override
 
virtual bool active (const Values &) const
 
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 
virtual bool sendable () const
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
bool empty () const
 Whether the factor is empty (involves zero variables). More...
 
Key front () const
 First key. More...
 
Key back () const
 Last key. More...
 
const_iterator find (Key key) const
 find More...
 
const KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Private Types

using Base = FunctorizedFactor< double, Matrix >
 
using Func = typename BASIS::ComponentDerivativeFunctor
 

Additional Inherited Members

- Public Types inherited from gtsam::NoiseModelFactorN< Matrix >
enum  
 N is the number of variables (N-way factor) More...
 
using ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef std::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::NonlinearFactor
typedef std::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys. More...
 
typedef KeyVector::iterator iterator
 Iterator over keys. More...
 
- Protected Types inherited from gtsam::NoiseModelFactorN< Matrix >
using Base = NoiseModelFactor
 
using KeyType = Key
 
using MatrixTypeT = Matrix
 
using OptionalMatrixTypeT = Matrix *
 
using This = NoiseModelFactorN< ValueTypes... >
 
using IsConvertible = typename std::enable_if< std::is_convertible< From, To >::value, void >::type
 
using IndexIsValid = typename std::enable_if<(I >=1) &&(I<=N), void >::type
 
using ContainerElementType = typename std::decay< decltype(*std::declval< Container >().begin())>::type
 
using IsContainerOfKeys = IsConvertible< ContainerElementType< Container >, Key >
 
using AreAllMatrixRefs = std::enable_if_t<(... &&std::is_convertible< Args, Matrix &>::value), Ret >
 
using IsMatrixPointer = std::is_same< typename std::decay_t< Arg >, Matrix *>
 
using IsNullpointer = std::is_same< typename std::decay_t< Arg >, std::nullptr_t >
 
using AreAllMatrixPtrs = std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret >
 
- Protected Types inherited from gtsam::NoiseModelFactor
typedef NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

template<class BASIS>
class gtsam::ComponentDerivativeFactor< BASIS >

A unary factor which enforces the evaluation of the derivative of a BASIS polynomial is equal to the scalar value at a specific index i of a vector-valued measurement z.

Parameters
BASISThe basis class to use e.g. Chebyshev2

Definition at line 379 of file BasisFactors.h.

Member Typedef Documentation

◆ Base

template<class BASIS >
using gtsam::ComponentDerivativeFactor< BASIS >::Base = FunctorizedFactor<double, Matrix>
private

Definition at line 381 of file BasisFactors.h.

◆ Func

template<class BASIS >
using gtsam::ComponentDerivativeFactor< BASIS >::Func = typename BASIS::ComponentDerivativeFunctor
private

Definition at line 382 of file BasisFactors.h.

Constructor & Destructor Documentation

◆ ComponentDerivativeFactor() [1/3]

template<class BASIS >
gtsam::ComponentDerivativeFactor< BASIS >::ComponentDerivativeFactor ( )
inline

Definition at line 385 of file BasisFactors.h.

◆ ComponentDerivativeFactor() [2/3]

template<class BASIS >
gtsam::ComponentDerivativeFactor< BASIS >::ComponentDerivativeFactor ( Key  key,
const double &  z,
const SharedNoiseModel model,
const size_t  P,
const size_t  N,
size_t  i,
double  x 
)
inline

Construct a new ComponentDerivativeFactor object.

Parameters
keyThe key to the parameter Matrix which represents the basis polynomial.
zThe scalar measurement value at a specific index i of the full measurement vector.
modelThe degree of the polynomial.
PSize of the control component derivative.
NThe degree of the polynomial.
iThe index for the evaluated vector to give us the desired scalar value.
xThe point at which to evaluate the basis polynomial.

Definition at line 401 of file BasisFactors.h.

◆ ComponentDerivativeFactor() [3/3]

template<class BASIS >
gtsam::ComponentDerivativeFactor< BASIS >::ComponentDerivativeFactor ( Key  key,
const double &  z,
const SharedNoiseModel model,
const size_t  P,
const size_t  N,
size_t  i,
double  x,
double  a,
double  b 
)
inline

Construct a new ComponentDerivativeFactor object.

Parameters
keyThe key to the parameter Matrix which represents the basis polynomial.
zThe scalar measurement value at a specific index i of the full measurement vector.
modelThe degree of the polynomial.
PSize of the control component derivative.
NThe degree of the polynomial.
iThe index for the evaluated vector to give us the desired scalar value.
xThe point at which to evaluate the basis polynomial.
aLower bound for the polynomial.
bUpper bound for the polynomial.

Definition at line 422 of file BasisFactors.h.

◆ ~ComponentDerivativeFactor()

template<class BASIS >
virtual gtsam::ComponentDerivativeFactor< BASIS >::~ComponentDerivativeFactor ( )
inlinevirtual

Definition at line 428 of file BasisFactors.h.


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


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