gtsam 4.1.1
gtsam
|
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.
Public Member Functions | |
NoiseModelFactor () | |
Default constructor for I/O only. | |
~NoiseModelFactor () override | |
Destructor. | |
template<typename CONTAINER > | |
NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys) | |
Constructor. | |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
Print. More... | |
bool | equals (const NonlinearFactor &f, double tol=1e-9) const override |
Check if two factors are equal. More... | |
size_t | dim () const override |
get the dimension of the factor (number of rows on linearization) More... | |
const SharedNoiseModel & | noiseModel () 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... | |
Vector | unweightedWhitenedError (const Values &c) const |
Vector of errors, whitened, but unweighted by any loss function. | |
double | weight (const Values &c) const |
Compute the effective weight of the factor from the noise model. | |
double | error (const Values &c) const override |
Calculate the error of the factor. More... | |
boost::shared_ptr< GaussianFactor > | linearize (const Values &x) const override |
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) \). More... | |
shared_ptr | cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const |
Creates a shared_ptr clone of the factor with a new noise model. | |
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... | |
virtual 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. More... | |
virtual shared_ptr | rekey (const KeyVector &new_keys) const |
Clones a factor and fully replaces its keys. More... | |
virtual bool | sendable () const |
Should the factor be evaluated in the same thread as the caller This is to enable factors that has shared states (like the Python GIL lock) More... | |
Public Member Functions inherited from gtsam::Factor | |
virtual | ~Factor ()=default |
Default destructor. | |
KeyVector & | keys () |
iterator | begin () |
Iterator at beginning of involved variable keys. | |
iterator | end () |
Iterator at end of involved variable keys. | |
virtual void | printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print only keys More... | |
Key | front () const |
First key. | |
Key | back () const |
Last key. | |
const_iterator | find (Key key) const |
find | |
const KeyVector & | keys () 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 |
Public Types | |
typedef boost::shared_ptr< This > | shared_ptr |
Noise model. | |
Public Types inherited from gtsam::NonlinearFactor | |
typedef boost::shared_ptr< This > | shared_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... | |
|
inlineoverridevirtual |
get the dimension of the factor (number of rows on linearization)
Implements gtsam::NonlinearFactor.
|
overridevirtual |
Check if two factors are equal.
Reimplemented from gtsam::NonlinearFactor.
Reimplemented in gtsam::FullIMUFactor< POSE >, gtsam::IMUFactor< POSE >, gtsam::PoseToPointFactor, gtsam::PriorFactor< VALUE >, gtsam::ShonanFactor< d >, gtsam::BetweenFactor< VALUE >, gtsam::EssentialMatrixConstraint, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::OrientedPlane3DirectionPrior, gtsam::PoseRotationPrior< POSE >, gtsam::PoseTranslationPrior< POSE >, gtsam::BiasedGPSFactor, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::PoseBetweenFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< typename Range< A1, A1 >::result_type >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::SmartRangeFactor, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::TriangulationFactor< CAMERA >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant1, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant3a, gtsam::InvDepthFactorVariant3b, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, and gtsam::ProjectionFactorRollingShutter.
|
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.
|
overridevirtual |
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) \).
Implements gtsam::NonlinearFactor.
Reimplemented in gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< typename Range< A1, A1 >::result_type >, and gtsam::TriangulationFactor< CAMERA >.
|
overridevirtual |
Print.
Reimplemented from gtsam::NonlinearFactor.
Reimplemented in gtsam::PoseToPointFactor, gtsam::PriorFactor< VALUE >, gtsam::ShonanFactor< d >, gtsam::BetweenFactor< VALUE >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::BiasedGPSFactor, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::PoseBetweenFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::IMUFactor< POSE >, gtsam::VelocityConstraint, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< typename Range< A1, A1 >::result_type >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::EssentialMatrixConstraint, gtsam::EssentialMatrixFactor, gtsam::EssentialMatrixFactor2, gtsam::EssentialMatrixFactor3, gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::PoseRotationPrior< POSE >, gtsam::PoseTranslationPrior< POSE >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::RotateFactor, gtsam::RotateDirectionsFactor, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::ProjectionFactorRollingShutter, gtsam::RelativeElevationFactor, gtsam::SmartRangeFactor, gtsam::BearingFactor< A1, A2, T >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::RangeFactor< A1, A2, T >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant1, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant3b, gtsam::InvDepthFactorVariant3a, gtsam::LocalOrientedPlane3Factor, gtsam::OrientedPlane3DirectionPrior, gtsam::OrientedPlane3Factor, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, and gtsam::GeneralSFMFactor2< CALIBRATION >.
|
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::CustomFactor, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< typename Range< A1, A1 >::result_type >, gtsam::NoiseModelFactor1< VALUE >, gtsam::NoiseModelFactor1< ParameterMatrix< P > >, gtsam::NoiseModelFactor1< PoseRTV >, gtsam::NoiseModelFactor1< BASIS::Parameters >, gtsam::NoiseModelFactor1< EssentialMatrix >, gtsam::NoiseModelFactor1< Vector >, gtsam::NoiseModelFactor1< Rot >, gtsam::NoiseModelFactor1< T >, gtsam::NoiseModelFactor1< Pose3 >, gtsam::NoiseModelFactor1< NavState >, gtsam::NoiseModelFactor1< Rot2 >, gtsam::NoiseModelFactor1< Rot3 >, gtsam::NoiseModelFactor1< POSE >, gtsam::NoiseModelFactor1< ParameterMatrix< traits< T >::dimension > >, gtsam::NoiseModelFactor1< OrientedPlane3 >, gtsam::NoiseModelFactor1< Point3 >, gtsam::NoiseModelFactor1< ParameterMatrix< M > >, gtsam::NoiseModelFactor2< VALUE1, VALUE2 >, gtsam::NoiseModelFactor2< VALUE, VALUE >, gtsam::NoiseModelFactor2< Pose3, Point3 >, gtsam::NoiseModelFactor2< NavState, NavState >, gtsam::NoiseModelFactor2< Pose2, Point2 >, gtsam::NoiseModelFactor2< Pose3, Pose3 >, gtsam::NoiseModelFactor2< EssentialMatrix, double >, gtsam::NoiseModelFactor2< EssentialMatrix, CALIBRATION >, gtsam::NoiseModelFactor2< Rot, Rot >, gtsam::NoiseModelFactor2< POSE, POSE >, gtsam::NoiseModelFactor2< T1, T2 >, gtsam::NoiseModelFactor2< CAMERA, LANDMARK >, gtsam::NoiseModelFactor2< POSE, LANDMARK >, gtsam::NoiseModelFactor2< Pose3, Vector6 >, gtsam::NoiseModelFactor2< Pose3, Vector3 >, gtsam::NoiseModelFactor2< Point3, Point3 >, gtsam::NoiseModelFactor2< T, T >, gtsam::NoiseModelFactor2< Pose3, OrientedPlane3 >, gtsam::NoiseModelFactor2< SOn, SOn >, gtsam::NoiseModelFactor2< PoseRTV, PoseRTV >, gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 >, gtsam::NoiseModelFactor3< Rot3, Rot3, Vector3 >, gtsam::NoiseModelFactor3< Vector6, Vector6, Pose3 >, gtsam::NoiseModelFactor3< Pose3, Point3, CALIBRATION >, gtsam::NoiseModelFactor3< NavState, NavState, imuBias::ConstantBias >, gtsam::NoiseModelFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::NoiseModelFactor3< Pose3, Pose3, Vector3 >, gtsam::NoiseModelFactor3< Pose3, Pose3, OrientedPlane3 >, gtsam::NoiseModelFactor3< double, Unit3, Point3 >, gtsam::NoiseModelFactor3< double, double, double >, gtsam::NoiseModelFactor3< POSE, POSE, LANDMARK >, gtsam::NoiseModelFactor3< Pose3, Pose3, Point3 >, gtsam::NoiseModelFactor3< Pose3, Pose3, Vector6 >, gtsam::NoiseModelFactor3< POINT, TRANSFORM, POINT >, gtsam::NoiseModelFactor4< VALUE1, VALUE2, VALUE3, VALUE4 >, gtsam::NoiseModelFactor4< Pose2, Pose2, Pose2, Point2 >, gtsam::NoiseModelFactor4< POSE, VELOCITY, POSE, VELOCITY >, gtsam::NoiseModelFactor4< Pose2, Pose2, Pose2, Pose2 >, gtsam::NoiseModelFactor4< POSE, POSE, LANDMARK, Cal3_S2 >, gtsam::NoiseModelFactor5< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5 >, gtsam::NoiseModelFactor5< POSE, VELOCITY, IMUBIAS, POSE, VELOCITY >, gtsam::NoiseModelFactor5< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias >, gtsam::NoiseModelFactor6< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6 >, gtsam::NoiseModelFactor6< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias, imuBias::ConstantBias >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, and gtsam::SmartRangeFactor.
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