gtsam  4.0.0
gtsam
gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 > Class Template Referenceabstract

Detailed Description

template<class VALUE1, class VALUE2, class VALUE3>
class gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >

A convenient base class for creating your own NoiseModelFactor with 3 variables.

To derive from this class, implement evaluateError().

+ Inheritance diagram for gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >:

Public Member Functions

 NoiseModelFactor3 ()
 Default Constructor for I/O.
 
 NoiseModelFactor3 (const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3)
 Constructor. More...
 
Key key1 () const
 methods to retrieve keys
 
Key key2 () const
 
Key key3 () const
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const
 Calls the 3-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class. More...
 
virtual Vector evaluateError (const X1 &, const X2 &, const X3 &, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const =0
 Override this method to finish implementing a trinary factor. More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor ()
 Default constructor for I/O only.
 
virtual ~NoiseModelFactor ()
 Destructor.
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 Constructor.
 
virtual void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 Print.
 
virtual bool equals (const NonlinearFactor &f, double tol=1e-9) const
 Check if two factors are equal.
 
virtual size_t dim () const
 get the dimension of the factor (number of rows on linearization)
 
const SharedNoiseModelnoiseModel () const
 access to the noise model
 
Vector whitenedError (const Values &c) const
 Vector of errors, whitened This is the raw error, i.e., i.e. More...
 
virtual double error (const Values &c) const
 Calculate the error of the factor. More...
 
boost::shared_ptr< GaussianFactorlinearize (const Values &x) const
 Linearize a non-linearFactorN to get a GaussianFactor, \( Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \) Hence \( b = z - h(x) = - \mathtt{error\_vector}(x) \).
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 Default constructor for I/O only.
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 Constructor from a collection of the keys involved in this factor.
 
virtual ~NonlinearFactor ()
 Destructor.
 
virtual bool active (const Values &) const
 Checks whether a factor should be used based on a set of values. More...
 
virtual shared_ptr clone () const
 Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses. More...
 
shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 Creates a shared_ptr clone of the factor with different keys using a map from old->new keys.
 
shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys. More...
 
- Public Member Functions inherited from gtsam::Factor
Key front () const
 First key.
 
Key back () const
 Last key.
 
const_iterator find (Key key) const
 find
 
const KeyVectorkeys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 Iterator at beginning of involved variable keys.
 
const_iterator end () const
 Iterator at end of involved variable keys.
 
size_t size () const
 
void print (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print
 
void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
KeyVectorkeys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 

Public Types

typedef VALUE1 X1
 
typedef VALUE2 X2
 
typedef VALUE3 X3
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 Noise model.
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Protected Types

typedef NoiseModelFactor Base
 
typedef NoiseModelFactor3< VALUE1, VALUE2, VALUE3 > 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
 

Friends

class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 Constructor - only for subclasses, as this does not set keys.
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 Default constructor for I/O.
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor.
 

Constructor & Destructor Documentation

◆ NoiseModelFactor3()

template<class VALUE1, class VALUE2, class VALUE3>
gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >::NoiseModelFactor3 ( const SharedNoiseModel noiseModel,
Key  j1,
Key  j2,
Key  j3 
)
inline

Constructor.

Parameters
noiseModelshared pointer to noise model
j1key of the first variable
j2key of the second variable
j3key of the third variable

Member Function Documentation

◆ evaluateError()

template<class VALUE1, class VALUE2, class VALUE3>
virtual Vector gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >::evaluateError ( const X1 &  ,
const X2 &  ,
const X3 &  ,
boost::optional< Matrix & >  H1 = boost::none,
boost::optional< Matrix & >  H2 = boost::none,
boost::optional< Matrix & >  H3 = boost::none 
) const
pure virtual

Override this method to finish implementing a trinary factor.

If any of the optional Matrix reference arguments are specified, it should compute both the function evaluation and its derivative(s) in X1 (and/or X2, X3).

Implemented in gtsam::ImuFactor2, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::InvDepthFactorVariant3b, gtsam::PendulumFactorPk1, gtsam::MagFactor3, gtsam::AHRSFactor, gtsam::PendulumFactorPk, gtsam::DiscreteEulerPoincareHelicopter, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::PendulumFactor2, gtsam::PendulumFactor1, and gtsam::VelocityConstraint3.

◆ unwhitenedError()

template<class VALUE1, class VALUE2, class VALUE3>
virtual Vector gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >::unwhitenedError ( const Values x,
boost::optional< std::vector< Matrix > & >  H = boost::none 
) const
inlinevirtual

Calls the 3-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class.

Implements gtsam::NoiseModelFactor.


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