gtsam  4.0.0
gtsam
gtsam::NoiseModelFactor Class Referenceabstract

Detailed Description

A nonlinear sum-of-squares factor with a zero-mean noise model implementing the density \( P(z|x) \propto exp -0.5*|z-h(x)|^2_C \) Templated on the parameter type X and the values structure Values There is no return type specified for h(x).

Instead, we require the derived class implements \( \mathtt{error\_vector}(x) = h(x)-z \approx A \delta x - b \) This allows a graph to have factors with measurements of mixed type.

The noise model is typically Gaussian, but robust and constrained error models are also supported.

+ Inheritance diagram for gtsam::NoiseModelFactor:

Public Member Functions

 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
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const =0
 Error function without the NoiseModel, \( z-h(x) \). More...
 
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 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 NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 

Protected Member Functions

 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
 

Protected Attributes

SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor.
 

Friends

class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

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

Member Function Documentation

◆ error()

double gtsam::NoiseModelFactor::error ( const Values c) const
virtual

Calculate the error of the factor.

This is the log-likelihood, e.g. \( 0.5(h(x)-z)^2/\sigma^2 \) in case of Gaussian. In this class, we take the raw prediction error \( h(x)-z \), ask the noise model to transform it to \( (h(x)-z)^2/\sigma^2 \), and then multiply by 0.5.

Implements gtsam::NonlinearFactor.

Reimplemented in gtsam::NonlinearEquality< VALUE >.

◆ unwhitenedError()

virtual Vector gtsam::NoiseModelFactor::unwhitenedError ( const Values x,
boost::optional< std::vector< Matrix > & >  H = boost::none 
) const
pure virtual

Error function without the NoiseModel, \( z-h(x) \).

Override this method to finish implementing an N-way factor. If the optional arguments is specified, it should compute both the function evaluation and its derivative(s) in H.

Implemented in gtsam::NoiseModelFactor6< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6 >, gtsam::NoiseModelFactor6< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias, imuBias::ConstantBias >, gtsam::NoiseModelFactor5< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5 >, gtsam::NoiseModelFactor5< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias >, gtsam::NoiseModelFactor5< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >, gtsam::NoiseModelFactor4< VALUE1, VALUE2, VALUE3, VALUE4 >, gtsam::NoiseModelFactor4< Pose2, Pose2, Pose2, Pose2 >, gtsam::NoiseModelFactor4< Pose2, Pose2, Pose2, Point2 >, gtsam::NoiseModelFactor4< POSE, POSE, LANDMARK, CALIBRATION >, gtsam::NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY >, gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >, gtsam::NoiseModelFactor3< Pose3, Point3, CALIBRATION >, gtsam::NoiseModelFactor3< NavState, NavState, imuBias::ConstantBias >, gtsam::NoiseModelFactor3< POSE, POSE, LANDMARK >, gtsam::NoiseModelFactor3< double, Unit3, Point3 >, gtsam::NoiseModelFactor3< Pose3, Pose3, Vector3 >, gtsam::NoiseModelFactor3< POINT, TRANSFORM, POINT >, gtsam::NoiseModelFactor3< Rot3, Rot3, Vector3 >, gtsam::NoiseModelFactor3< Pose3, Pose3, Vector6 >, gtsam::NoiseModelFactor3< Vector6, Vector6, Pose3 >, gtsam::NoiseModelFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::NoiseModelFactor3< double, double, double >, gtsam::NoiseModelFactor2< VALUE1, VALUE2 >, gtsam::NoiseModelFactor2< POSE, LANDMARK >, gtsam::NoiseModelFactor2< Pose3, Vector6 >, gtsam::NoiseModelFactor2< Point3, Point3 >, gtsam::NoiseModelFactor2< EssentialMatrix, double >, gtsam::NoiseModelFactor2< PoseRTV, PoseRTV >, gtsam::NoiseModelFactor2< Pose3, OrientedPlane3 >, gtsam::NoiseModelFactor2< Pose2, Point2 >, gtsam::NoiseModelFactor2< Pose3, Point3 >, gtsam::NoiseModelFactor2< Pose3, Pose3 >, gtsam::NoiseModelFactor2< POSE, POSE >, gtsam::NoiseModelFactor2< CAMERA, LANDMARK >, gtsam::NoiseModelFactor2< VALUE, VALUE >, gtsam::NoiseModelFactor2< Pose3, Vector3 >, gtsam::NoiseModelFactor1< VALUE >, gtsam::NoiseModelFactor1< Pose3 >, gtsam::NoiseModelFactor1< EssentialMatrix >, gtsam::NoiseModelFactor1< Rot3 >, gtsam::NoiseModelFactor1< POSE >, gtsam::NoiseModelFactor1< Rot2 >, gtsam::NoiseModelFactor1< PoseRTV >, gtsam::NoiseModelFactor1< NavState >, gtsam::NoiseModelFactor1< Point3 >, gtsam::NoiseModelFactor1< OrientedPlane3 >, gtsam::SmartRangeFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, and gtsam::ExpressionFactor< double >.

◆ whitenedError()

Vector gtsam::NoiseModelFactor::whitenedError ( const Values c) const

Vector of errors, whitened This is the raw error, i.e., i.e.

\( (h(x)-z)/\sigma \) in case of a Gaussian


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