Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Member Functions | Friends | List of all members
gtsam::NoiseModelFactor Class Referenceabstract

#include <NonlinearFactor.h>

Inherits gtsam::NonlinearFactor.

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

Public Types

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

shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
size_t dim () const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) 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)
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
Vector unweightedWhitenedError (const Values &c) const
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const =0
 
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
 
virtual shared_ptr clone () 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 NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 

Protected Member Functions

 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

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

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.

Definition at line 154 of file NonlinearFactor.h.

Member Typedef Documentation

Definition at line 159 of file NonlinearFactor.h.

typedef boost::shared_ptr<This> gtsam::NoiseModelFactor::shared_ptr

Noise model

Definition at line 166 of file NonlinearFactor.h.

Definition at line 160 of file NonlinearFactor.h.

Constructor & Destructor Documentation

gtsam::NoiseModelFactor::NoiseModelFactor ( )
inline

Default constructor for I/O only

Definition at line 169 of file NonlinearFactor.h.

gtsam::NoiseModelFactor::~NoiseModelFactor ( )
inlineoverride

Destructor

Definition at line 172 of file NonlinearFactor.h.

template<typename CONTAINER >
gtsam::NoiseModelFactor::NoiseModelFactor ( const SharedNoiseModel noiseModel,
const CONTAINER &  keys 
)
inline

Constructor

Definition at line 178 of file NonlinearFactor.h.

gtsam::NoiseModelFactor::NoiseModelFactor ( const SharedNoiseModel noiseModel)
inlineprotected

Constructor - only for subclasses, as this does not set keys.

Definition at line 186 of file NonlinearFactor.h.

Member Function Documentation

NoiseModelFactor::shared_ptr gtsam::NoiseModelFactor::cloneWithNewNoiseModel ( const SharedNoiseModel  newNoise) const

Creates a shared_ptr clone of the factor with a new noise model

Definition at line 80 of file NonlinearFactor.cpp.

size_t gtsam::NoiseModelFactor::dim ( ) const
inlineoverridevirtual

get the dimension of the factor (number of rows on linearization)

Implements gtsam::NonlinearFactor.

Reimplemented in NonlinearMeasurementModel, and NonlinearMotionModel.

Definition at line 198 of file NonlinearFactor.h.

bool gtsam::NoiseModelFactor::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
overridevirtual

Check if two factors are equal

Reimplemented from gtsam::NonlinearFactor.

Reimplemented in TestNaryFactor, NonlinearMeasurementModel, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::InvDepthFactorVariant3b, NonlinearMotionModel, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BetweenFactor< VALUE >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< gtsam::Point3 >, gtsam::PriorFactor< VALUE >, gtsam::SmartRangeFactor, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::PoseTranslationPrior< POSE >, gtsam::InvDepthFactorVariant3a, gtsam::EssentialMatrixConstraint, gtsam::InvDepthFactorVariant1, gtsam::PosePriorFactor< POSE >, gtsam::OrientedPlane3DirectionPrior, gtsam::BiasedGPSFactor, gtsam::ShonanFactor< d >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::PoseToPointFactor, and gtsam::IMUFactor< POSE >.

Definition at line 71 of file NonlinearFactor.cpp.

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

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 NonlinearMeasurementModel, and NonlinearMotionModel.

Definition at line 127 of file NonlinearFactor.cpp.

boost::shared_ptr< GaussianFactor > gtsam::NoiseModelFactor::linearize ( const Values x) const
overridevirtual
const SharedNoiseModel& gtsam::NoiseModelFactor::noiseModel ( ) const
inline

access to the noise model

Definition at line 203 of file NonlinearFactor.h.

void gtsam::NoiseModelFactor::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtual

Print

Reimplemented from gtsam::NonlinearFactor.

Reimplemented in TestNaryFactor, NonlinearMeasurementModel, gtsam::EssentialMatrixFactor3, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::InvDepthFactorVariant3b, NonlinearMotionModel, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::EssentialMatrixFactor2, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::RotateDirectionsFactor, gtsam::VelocityConstraint, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::BetweenFactor< VALUE >, gtsam::PoseTranslationPrior< POSE >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< gtsam::Point3 >, gtsam::RangeFactor< A1, A2, T >, gtsam::SmartRangeFactor, gtsam::PriorFactor< VALUE >, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::EssentialMatrixConstraint, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant3a, gtsam::OrientedPlane3DirectionPrior, gtsam::PoseRotationPrior< POSE >, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactorVariant1, gtsam::EssentialMatrixFactor, gtsam::FullIMUFactor< POSE >, gtsam::LocalOrientedPlane3Factor, gtsam::PosePriorFactor< POSE >, gtsam::ShonanFactor< d >, gtsam::RelativeElevationFactor, gtsam::IMUFactor< POSE >, gtsam::BearingFactor< A1, A2, T >, gtsam::BiasedGPSFactor, gtsam::RotateFactor, gtsam::PoseToPointFactor, and gtsam::OrientedPlane3Factor.

Definition at line 63 of file NonlinearFactor.cpp.

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

Definition at line 257 of file NonlinearFactor.h.

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

Vector of errors, whitened, but unweighted by any loss function

Definition at line 105 of file NonlinearFactor.cpp.

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::NoiseModelFactor6< double, double, double, double, double, double >, gtsam::NoiseModelFactor5< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5 >, gtsam::NoiseModelFactor5< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias >, gtsam::NoiseModelFactor5< double, double, double, double, double >, gtsam::NoiseModelFactor5< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >, gtsam::NoiseModelFactor4< VALUE1, VALUE2, VALUE3, VALUE4 >, gtsam::NoiseModelFactor4< double, double, double, double >, 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::NoiseModelFactor3< Pose3, Pose3, OrientedPlane3 >, gtsam::NoiseModelFactor2< VALUE1, VALUE2 >, gtsam::NoiseModelFactor2< POSE, LANDMARK >, gtsam::NoiseModelFactor2< Point2, Point2 >, gtsam::NoiseModelFactor2< Pose3, Vector6 >, gtsam::NoiseModelFactor2< Point3, Point3 >, gtsam::NoiseModelFactor2< EssentialMatrix, double >, gtsam::NoiseModelFactor2< PoseRTV, PoseRTV >, gtsam::NoiseModelFactor2< SOn, SOn >, gtsam::NoiseModelFactor2< Pose3, OrientedPlane3 >, gtsam::NoiseModelFactor2< Rot, Rot >, gtsam::NoiseModelFactor2< Pose2, Point2 >, gtsam::NoiseModelFactor2< Pose3, Point3 >, gtsam::NoiseModelFactor2< Pose3, Pose3 >, gtsam::NoiseModelFactor2< POSE, POSE >, gtsam::NoiseModelFactor2< CAMERA, LANDMARK >, gtsam::NoiseModelFactor2< NavState, NavState >, gtsam::NoiseModelFactor2< T1, T2 >, gtsam::NoiseModelFactor2< VALUE, VALUE >, gtsam::NoiseModelFactor2< POSE, POINT >, gtsam::NoiseModelFactor2< Pose3, Vector3 >, gtsam::NoiseModelFactor1< VALUE >, gtsam::NoiseModelFactor1< Pose2 >, gtsam::NoiseModelFactor1< EssentialMatrix >, gtsam::NoiseModelFactor1< Pose3 >, gtsam::NoiseModelFactor1< Rot3 >, gtsam::NoiseModelFactor1< POSE >, gtsam::NoiseModelFactor1< Rot2 >, gtsam::NoiseModelFactor1< PoseRTV >, gtsam::NoiseModelFactor1< T >, gtsam::NoiseModelFactor1< NavState >, gtsam::NoiseModelFactor1< OrientedPlane3 >, gtsam::NoiseModelFactor1< Point3 >, gtsam::NoiseModelFactor1< Point2 >, gtsam::NoiseModelFactor1< Rot >, gtsam::SmartRangeFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, and gtsam::ExpressionFactor< gtsam::Point3 >.

double gtsam::NoiseModelFactor::weight ( const Values c) const

Compute the effective weight of the factor from the noise model.

Definition at line 112 of file NonlinearFactor.cpp.

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

Definition at line 98 of file NonlinearFactor.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 255 of file NonlinearFactor.h.

Member Data Documentation

SharedNoiseModel gtsam::NoiseModelFactor::noiseModel_
protected

Definition at line 162 of file NonlinearFactor.h.


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


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