#include <NonlinearFactor.h>
Public Types | |
typedef std::shared_ptr< This > | shared_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... | |
Protected Types | |
typedef Factor | Base |
typedef NonlinearFactor | This |
Standard Constructors | |
NonlinearFactor () | |
template<typename CONTAINER > | |
NonlinearFactor (const CONTAINER &keys) | |
Testable | |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
virtual bool | equals (const NonlinearFactor &f, double tol=1e-9) const |
Standard Interface | |
virtual double | error (const Values &c) const |
double | error (const HybridValues &c) const override |
virtual size_t | dim () const =0 |
virtual bool | active (const Values &) const |
virtual std::shared_ptr< GaussianFactor > | linearize (const Values &c) const =0 |
virtual shared_ptr | clone () const |
virtual shared_ptr | rekey (const std::map< Key, Key > &rekey_mapping) const |
virtual shared_ptr | rekey (const KeyVector &new_keys) const |
virtual bool | sendable () const |
Additional Inherited Members | |
Public Member Functions inherited from gtsam::Factor | |
virtual | ~Factor ()=default |
Default destructor. More... | |
bool | empty () const |
Whether the factor is empty (involves zero variables). More... | |
Key | front () const |
First key. More... | |
Key | back () const |
Last key. More... | |
const_iterator | find (Key key) const |
find More... | |
const KeyVector & | keys () 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... | |
bool | equals (const This &other, double tol=1e-9) const |
check equality More... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Protected Member Functions inherited from gtsam::Factor | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
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) |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Nonlinear factor base class
This is the base class for all factor types, as well as conditionals, which are implemented as specialized factors. This class does not store any data other than its keys. Derived classes store data such as matrices and probability tables.
The error
method is used to evaluate the factor, and is the only method that is required to be implemented in derived classes, although it has a default implementation that throws an exception.
There are five broad classes of factors that derive from Factor:
Definition at line 68 of file NonlinearFactor.h.
|
protected |
Definition at line 73 of file NonlinearFactor.h.
typedef std::shared_ptr<This> gtsam::NonlinearFactor::shared_ptr |
Definition at line 78 of file NonlinearFactor.h.
|
protected |
Definition at line 74 of file NonlinearFactor.h.
|
inline |
Default constructor for I/O only
Definition at line 84 of file NonlinearFactor.h.
|
inline |
Constructor from a collection of the keys involved in this factor
Definition at line 90 of file NonlinearFactor.h.
|
inlinevirtual |
Checks whether a factor should be used based on a set of values. This is primarily used to implement inequality constraints that require a variable active set. For all others, the default implementation returning true solves this problem.
In an inequality/bounding constraint, this active() returns true when the constraint is NOT fulfilled.
Reimplemented in gtsam::BoundingConstraint2< VALUE1, VALUE2 >, gtsam::BoundingConstraint2< VALUE, VALUE >, gtsam::BoundingConstraint2< POSE, POINT >, gtsam::AntiFactor, gtsam::BoundingConstraint1< VALUE >, and FixActiveFactor.
Definition at line 141 of file NonlinearFactor.h.
|
inlinevirtual |
Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses
By default, throws exception if subclass does not implement the function.
Reimplemented in gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::example::smallOptimize::UnaryFactor, gtsam::NonlinearEquality2< T >, gtsam::ImuFactor2, gtsam::EssentialMatrixFactor3, simulated2D::GenericMeasurement< POSE, LANDMARK >, gtsam::NonlinearEquality1< VALUE >, gtsam::CombinedImuFactor, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::ImuFactor, gtsam::LinearizedHessianFactor, gtsam::PendulumFactorPk1, simulated2D::GenericOdometry< VALUE >, gtsam::Pose3AttitudeFactor, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::MagFactor3, gtsam::SmartRangeFactor, simulated2D::inequality_constraints::MinDistanceConstraint< POSE, POINT >, gtsam::NonlinearEquality< VALUE >, gtsam::AHRSFactor, gtsam::EssentialMatrixFactor2, simulated2D::GenericPrior< VALUE >, gtsam::MagFactor2, gtsam::PendulumFactorPk, gtsam::GPSFactor2, gtsam::ProjectionFactorRollingShutter, simulated2D::inequality_constraints::MaxDistanceConstraint< VALUE >, simulated2DOriented::GenericOdometry< VALUE >, gtsam::Rot3AttitudeFactor, gtsam::LinearContainerFactor, gtsam::LinearizedJacobianFactor, gtsam::MagFactor1, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::DiscreteEulerPoincareHelicopter, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::RotateDirectionsFactor, gtsam::TriangulationFactor< CAMERA >, gtsam::PendulumFactor2, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::FunctorizedFactor< R, T >, gtsam::PartialPriorFactor< VALUE >, gtsam::MagPoseFactor< POSE >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactor< VALUE >, gtsam::EssentialMatrixFactor, gtsam::VelocityConstraint, gtsam::PriorFactor< VALUE >, gtsam::GPSFactor, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::BarometricFactor, gtsam::EssentialMatrixConstraint, gtsam::DummyFactor< CAMERA >, gtsam::PoseBetweenFactor< POSE >, simulated2D::inequality_constraints::ScalarCoordConstraint1< VALUE, IDX >, gtsam::PosePriorFactor< POSE >, gtsam::MagFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::AntiFactor, gtsam::IMUFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::PendulumFactor1, gtsam::Reconstruction, gtsam::RotateFactor, and gtsam::VelocityConstraint3.
Definition at line 153 of file NonlinearFactor.h.
|
pure virtual |
get the dimension of the factor (number of rows on linearization)
Implemented in gtsam::BetweenFactorEM< VALUE >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, NonlinearMeasurementModel, gtsam::EssentialTransferFactorK< K >, gtsam::LinearizedHessianFactor, gtsam::NoiseModelFactor, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, NonlinearMotionModel, gtsam::SmartFactorBase< CAMERA >, gtsam::LinearizedJacobianFactor, gtsam::WhiteNoiseFactor, gtsam::ShonanGaugeFactor, gtsam::LinearContainerFactor, gtsam::AntiFactor, gtsam::KarcherMeanFactor< T >, and gtsam::DummyFactor< CAMERA >.
|
virtual |
Check if two factors are equal
Reimplemented in gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::InvDepthFactorVariant3b, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::ProjectionFactorRollingShutter, gtsam::SmartStereoProjectionFactorPP, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::SmartStereoProjectionPoseFactor, gtsam::SmartStereoProjectionFactor, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::TriangulationFactor< CAMERA >, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant3a, gtsam::InvDepthFactorVariant1, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::FunctorizedFactor< R, T >, gtsam::FunctorizedFactor< T, Matrix >, gtsam::FunctorizedFactor< Vector, Matrix >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< double, Matrix >, NonlinearMeasurementModel, gtsam::NoiseModelFactor, NonlinearMotionModel, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::NonlinearEquality< VALUE >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactorEM< VALUE >, gtsam::SmartRangeFactor, gtsam::LinearContainerFactor, gtsam::DummyFactor< CAMERA >, gtsam::ImuFactor2, gtsam::CombinedImuFactor, gtsam::LinearizedHessianFactor, gtsam::ImuFactor, gtsam::Pose3AttitudeFactor, gtsam::GPSFactor2, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::Rot3AttitudeFactor, gtsam::LinearizedJacobianFactor, gtsam::MagPoseFactor< POSE >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BetweenFactor< VALUE >, gtsam::PriorFactor< VALUE >, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PoseBetweenFactor< POSE >, gtsam::GPSFactor, gtsam::OrientedPlane3DirectionPrior, gtsam::PoseTranslationPrior< POSE >, gtsam::BarometricFactor, gtsam::EssentialMatrixConstraint, gtsam::PosePriorFactor< POSE >, gtsam::BiasedGPSFactor, gtsam::ShonanFactor< d >, gtsam::PoseRotationPrior< POSE >, gtsam::AntiFactor, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::RelativeElevationFactor, gtsam::FullIMUFactor< POSE >, gtsam::IMUFactor< POSE >, and gtsam::AHRSFactor.
Definition at line 45 of file NonlinearFactor.cpp.
|
overridevirtual |
All factor types need to implement an error function. In factor graphs, this is the negative log-likelihood.
Reimplemented from gtsam::Factor.
Definition at line 30 of file NonlinearFactor.cpp.
|
virtual |
Reimplemented in gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::WhiteNoiseFactor, gtsam::BetweenFactorEM< VALUE >, gtsam::SmartStereoProjectionFactor, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartStereoProjectionFactorPP, gtsam::SmartStereoProjectionPoseFactor, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::StereoFactor, gtsam::PinholeFactor, NonlinearMeasurementModel, gtsam::NoiseModelFactor, gtsam::LinearizedHessianFactor, NonlinearMotionModel, gtsam::LinearizedJacobianFactor, gtsam::NonlinearEquality< VALUE >, gtsam::ShonanGaugeFactor, gtsam::LinearContainerFactor, gtsam::AntiFactor, gtsam::KarcherMeanFactor< T >, gtsam::DummyFactor< CAMERA >, and gtsam::TransformBtwRobotsUnaryFactor< VALUE >.
Definition at line 25 of file NonlinearFactor.cpp.
|
pure virtual |
linearize to a GaussianFactor
Implemented in gtsam::NoiseModelFactor, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::NonlinearEquality< VALUE >, gtsam::WhiteNoiseFactor, gtsam::TriangulationFactor< CAMERA >, gtsam::BetweenFactorEM< VALUE >, gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartStereoProjectionFactor, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::SmartStereoProjectionFactorPP, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::StereoFactor, gtsam::PinholeFactor, NonlinearMeasurementModel, gtsam::LinearizedHessianFactor, NonlinearMotionModel, gtsam::LinearizedJacobianFactor, gtsam::LinearContainerFactor, gtsam::ShonanGaugeFactor, gtsam::AntiFactor, gtsam::KarcherMeanFactor< T >, gtsam::DummyFactor< CAMERA >, and gtsam::TransformBtwRobotsUnaryFactor< VALUE >.
|
overridevirtual |
Reimplemented from gtsam::Factor.
Reimplemented in gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::OrientedPlane3Factor, gtsam::OrientedPlane3DirectionPrior, gtsam::LocalOrientedPlane3Factor, gtsam::InvDepthFactorVariant3a, gtsam::InvDepthFactorVariant3b, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant1, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EssentialMatrixFactor4< CALIBRATION >, NonlinearMeasurementModel, gtsam::EssentialMatrixFactor3, gtsam::NoiseModelFactor, gtsam::LinearizedHessianFactor, gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::EssentialMatrixFactor2, NonlinearMotionModel, gtsam::ProjectionFactorRollingShutter, gtsam::SmartStereoProjectionFactorPP, gtsam::LinearizedJacobianFactor, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::SmartStereoProjectionPoseFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::SmartStereoProjectionFactor, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::SmartProjectionFactor< CAMERA >, gtsam::FunctorizedFactor< T, Matrix >, gtsam::FunctorizedFactor< Vector, Matrix >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< double, Matrix >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::RotateDirectionsFactor, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::BetweenFactor< VALUE >, gtsam::EssentialMatrixFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::SmartRangeFactor, gtsam::EssentialMatrixConstraint, gtsam::PoseRotationPrior< POSE >, gtsam::RelativeElevationFactor, gtsam::RotateFactor, gtsam::DummyFactor< CAMERA >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::VelocityConstraint, gtsam::FullIMUFactor< POSE >, gtsam::IMUFactor< POSE >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactorEM< VALUE >, gtsam::PriorFactor< VALUE >, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PoseBetweenFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::ShonanFactor< d >, gtsam::AntiFactor, gtsam::BiasedGPSFactor, gtsam::PoseToPointFactor< POSE, POINT >, and gtsam::WhiteNoiseFactor.
Definition at line 35 of file NonlinearFactor.cpp.
|
virtual |
Clones a factor and fully replaces its keys
new_keys | is the full replacement set of keys |
Reimplemented in gtsam::LinearContainerFactor.
Definition at line 63 of file NonlinearFactor.cpp.
|
virtual |
Creates a shared_ptr clone of the factor with different keys using a map from old->new keys
Reimplemented in gtsam::LinearContainerFactor.
Definition at line 50 of file NonlinearFactor.cpp.
|
inlinevirtual |
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)
Reimplemented in gtsam::CustomFactor.
Definition at line 176 of file NonlinearFactor.h.