Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
gtsam::BetweenFactor< VALUE > Class Template Reference

#include <BetweenFactor.h>

Inheritance diagram for gtsam::BetweenFactor< VALUE >:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< BetweenFactorshared_ptr
 
typedef VALUE T
 
- Public Types inherited from gtsam::NoiseModelFactorN< VALUE, VALUE >
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...
 

Public Member Functions

gtsam::NonlinearFactor::shared_ptr clone () const override
 
 ~BetweenFactor () override
 
Standard Constructors
 BetweenFactor ()
 
 BetweenFactor (Key key1, Key key2, const VALUE &measured, const SharedNoiseModel &model=nullptr)
 
Testable
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print with optional string More...
 
bool equals (const NonlinearFactor &expected, double tol=1e-9) const override
 assert equality up to a tolerance More...
 
NoiseModelFactorN methods
Vector evaluateError (const T &p1, const T &p2, OptionalMatrixType H1, OptionalMatrixType H2) const override
 evaluate error, returns vector of errors size of tangent space More...
 
Standard interface
const VALUE & measured () const
 return the measurement More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactorN< VALUE, VALUE >
Key key () const
 
virtual Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const =0
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) 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

enum  { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }
 
typedef NoiseModelFactorN< VALUE, VALUE > Base
 
typedef BetweenFactor< VALUE > This
 

Private Member Functions

 GTSAM_CONCEPT_ASSERT (IsLieGroup< VALUE >)
 
 GTSAM_CONCEPT_ASSERT (IsTestable< VALUE >)
 

Private Attributes

VALUE measured_
 

Additional Inherited Members

- Protected Types inherited from gtsam::NoiseModelFactorN< VALUE, VALUE >
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 VALUE>
class gtsam::BetweenFactor< VALUE >

A class for a measurement predicted by "between(config[key1],config[key2])"

Template Parameters
VALUEthe Value type

Definition at line 40 of file BetweenFactor.h.

Member Typedef Documentation

◆ Base

template<class VALUE >
typedef NoiseModelFactorN<VALUE, VALUE> gtsam::BetweenFactor< VALUE >::Base
private

Definition at line 53 of file BetweenFactor.h.

◆ shared_ptr

template<class VALUE >
typedef std::shared_ptr<BetweenFactor> gtsam::BetweenFactor< VALUE >::shared_ptr

Definition at line 63 of file BetweenFactor.h.

◆ T

template<class VALUE >
typedef VALUE gtsam::BetweenFactor< VALUE >::T

Definition at line 48 of file BetweenFactor.h.

◆ This

template<class VALUE >
typedef BetweenFactor<VALUE> gtsam::BetweenFactor< VALUE >::This
private

Definition at line 52 of file BetweenFactor.h.

Member Enumeration Documentation

◆ anonymous enum

template<class VALUE >
anonymous enum
private
Enumerator
NeedsToAlign 

Definition at line 151 of file BetweenFactor.h.

Constructor & Destructor Documentation

◆ BetweenFactor() [1/2]

template<class VALUE >
gtsam::BetweenFactor< VALUE >::BetweenFactor ( )
inline

default constructor - only use for serialization

Definition at line 69 of file BetweenFactor.h.

◆ BetweenFactor() [2/2]

template<class VALUE >
gtsam::BetweenFactor< VALUE >::BetweenFactor ( Key  key1,
Key  key2,
const VALUE &  measured,
const SharedNoiseModel model = nullptr 
)
inline

Constructor

Definition at line 72 of file BetweenFactor.h.

◆ ~BetweenFactor()

template<class VALUE >
gtsam::BetweenFactor< VALUE >::~BetweenFactor ( )
inlineoverride

Definition at line 79 of file BetweenFactor.h.

Member Function Documentation

◆ clone()

template<class VALUE >
gtsam::NonlinearFactor::shared_ptr gtsam::BetweenFactor< VALUE >::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

Definition at line 82 of file BetweenFactor.h.

◆ equals()

template<class VALUE >
bool gtsam::BetweenFactor< VALUE >::equals ( const NonlinearFactor expected,
double  tol = 1e-9 
) const
inlineoverridevirtual

assert equality up to a tolerance

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 101 of file BetweenFactor.h.

◆ evaluateError()

template<class VALUE >
Vector gtsam::BetweenFactor< VALUE >::evaluateError ( const T p1,
const T p2,
OptionalMatrixType  H1,
OptionalMatrixType  H2 
) const
inlineoverride

evaluate error, returns vector of errors size of tangent space

Definition at line 111 of file BetweenFactor.h.

◆ GTSAM_CONCEPT_ASSERT() [1/2]

template<class VALUE >
gtsam::BetweenFactor< VALUE >::GTSAM_CONCEPT_ASSERT ( IsLieGroup< VALUE >  )
private

◆ GTSAM_CONCEPT_ASSERT() [2/2]

template<class VALUE >
gtsam::BetweenFactor< VALUE >::GTSAM_CONCEPT_ASSERT ( IsTestable< VALUE >  )
private

◆ measured()

template<class VALUE >
const VALUE& gtsam::BetweenFactor< VALUE >::measured ( ) const
inline

return the measurement

Definition at line 131 of file BetweenFactor.h.

◆ print()

template<class VALUE >
void gtsam::BetweenFactor< VALUE >::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlineoverridevirtual

print with optional string

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 90 of file BetweenFactor.h.

Member Data Documentation

◆ measured_

template<class VALUE >
VALUE gtsam::BetweenFactor< VALUE >::measured_
private

Definition at line 55 of file BetweenFactor.h.


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


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:13:44