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

#include <PartialPriorFactor.h>

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

Public Types

typedef VALUE T
 
- Public Types inherited from gtsam::NoiseModelFactor1< VALUE >
typedef VALUE X
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::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
 
bool equals (const NonlinearFactor &expected, double tol=1e-9) const override
 
Vector evaluateError (const T &p, boost::optional< Matrix & > H=boost::none) const override
 
const std::vector< size_t > & indices () const
 
 PartialPriorFactor (Key key, size_t idx, double prior, const SharedNoiseModel &model)
 
 PartialPriorFactor (Key key, const std::vector< size_t > &indices, const Vector &prior, const SharedNoiseModel &model)
 
void print (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
const Vectorprior () const
 
 ~PartialPriorFactor () override
 
- Public Member Functions inherited from gtsam::NoiseModelFactor1< VALUE >
 NoiseModelFactor1 ()
 
 ~NoiseModelFactor1 () override
 
Key key () const
 
 NoiseModelFactor1 (const SharedNoiseModel &noiseModel, Key key1)
 
Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
 
- 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
 
boost::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
 
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)
 
virtual ~NonlinearFactor ()
 
virtual bool active (const Values &) const
 
shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
shared_ptr rekey (const KeyVector &new_keys) const
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. 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...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Protected Types

typedef NoiseModelFactor1< VALUE > Base
 
typedef PartialPriorFactor< VALUE > This
 
- Protected Types inherited from gtsam::NoiseModelFactor1< VALUE >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor1< VALUE > This
 
- 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

 PartialPriorFactor ()
 
 PartialPriorFactor (Key key, const SharedNoiseModel &model)
 
- 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)
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 

Protected Attributes

std::vector< size_tindices_
 Indices of the measured tangent space parameters. More...
 
Vector prior_
 Measurement on tangent space parameters, in compressed form. More...
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Private Member Functions

template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Friends

class boost::serialization::access
 

Additional Inherited Members

- 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)
 

Detailed Description

template<class VALUE>
class gtsam::PartialPriorFactor< VALUE >

A class for a soft partial prior on any Lie type, with a mask over Expmap parameters. Note that this will use Logmap() to find a tangent space parameterization for the variable attached, so this may fail for highly nonlinear manifolds.

The prior vector used in this factor is stored in compressed form, such that it only contains values for measurements that are to be compared, and they are in the same order as VALUE::Logmap(). The provided indices will determine which components to extract in the error function.

Template Parameters
VALUEis the type of variable the prior effects

Definition at line 38 of file PartialPriorFactor.h.

Member Typedef Documentation

template<class VALUE>
typedef NoiseModelFactor1<VALUE> gtsam::PartialPriorFactor< VALUE >::Base
protected

Definition at line 47 of file PartialPriorFactor.h.

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

Definition at line 41 of file PartialPriorFactor.h.

template<class VALUE>
typedef PartialPriorFactor<VALUE> gtsam::PartialPriorFactor< VALUE >::This
protected

Definition at line 48 of file PartialPriorFactor.h.

Constructor & Destructor Documentation

template<class VALUE>
gtsam::PartialPriorFactor< VALUE >::PartialPriorFactor ( )
inlineprotected

default constructor - only use for serialization

Definition at line 54 of file PartialPriorFactor.h.

template<class VALUE>
gtsam::PartialPriorFactor< VALUE >::PartialPriorFactor ( Key  key,
const SharedNoiseModel model 
)
inlineprotected

constructor with just minimum requirements for a factor - allows more computation in the constructor. This should only be used by subclasses

Definition at line 60 of file PartialPriorFactor.h.

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

Definition at line 65 of file PartialPriorFactor.h.

template<class VALUE>
gtsam::PartialPriorFactor< VALUE >::PartialPriorFactor ( Key  key,
size_t  idx,
double  prior,
const SharedNoiseModel model 
)
inline

Single Element Constructor: Prior on a single parameter at index 'idx' in the tangent vector.

Definition at line 68 of file PartialPriorFactor.h.

template<class VALUE>
gtsam::PartialPriorFactor< VALUE >::PartialPriorFactor ( Key  key,
const std::vector< size_t > &  indices,
const Vector prior,
const SharedNoiseModel model 
)
inline

Indices Constructor: Specify the relevant measured indices in the tangent vector.

Definition at line 76 of file PartialPriorFactor.h.

Member Function Documentation

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

Reimplemented from gtsam::NonlinearFactor.

Definition at line 86 of file PartialPriorFactor.h.

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

equals

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 99 of file PartialPriorFactor.h.

template<class VALUE>
Vector gtsam::PartialPriorFactor< VALUE >::evaluateError ( const T p,
boost::optional< Matrix & >  H = boost::none 
) const
inlineoverridevirtual

implement functions needed to derive from Factor Returns a vector of errors for the measured tangent parameters.

Implements gtsam::NoiseModelFactor1< VALUE >.

Definition at line 109 of file PartialPriorFactor.h.

template<class VALUE>
const std::vector<size_t>& gtsam::PartialPriorFactor< VALUE >::indices ( ) const
inline

Definition at line 137 of file PartialPriorFactor.h.

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

implement functions needed for Testable print

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 93 of file PartialPriorFactor.h.

template<class VALUE>
const Vector& gtsam::PartialPriorFactor< VALUE >::prior ( ) const
inline

Definition at line 136 of file PartialPriorFactor.h.

template<class VALUE>
template<class ARCHIVE >
void gtsam::PartialPriorFactor< VALUE >::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 143 of file PartialPriorFactor.h.

Friends And Related Function Documentation

template<class VALUE>
friend class boost::serialization::access
friend

Serialization function

Definition at line 141 of file PartialPriorFactor.h.

Member Data Documentation

template<class VALUE>
std::vector<size_t> gtsam::PartialPriorFactor< VALUE >::indices_
protected

Indices of the measured tangent space parameters.

Definition at line 51 of file PartialPriorFactor.h.

template<class VALUE>
Vector gtsam::PartialPriorFactor< VALUE >::prior_
protected

Measurement on tangent space parameters, in compressed form.

Definition at line 50 of file PartialPriorFactor.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:19