#include <NonlinearFactor.h>
Public Types | |
typedef boost::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 | ~NonlinearFactor () |
virtual double | error (const Values &c) const =0 |
virtual size_t | dim () const =0 |
virtual bool | active (const Values &) const |
virtual boost::shared_ptr< GaussianFactor > | linearize (const Values &c) const =0 |
virtual shared_ptr | clone () const |
shared_ptr | rekey (const std::map< Key, Key > &rekey_mapping) const |
shared_ptr | rekey (const KeyVector &new_keys) const |
Additional Inherited Members | |
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 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... | |
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) | |
bool | equals (const This &other, double tol=1e-9) const |
check equality More... | |
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
Definition at line 43 of file NonlinearFactor.h.
|
protected |
Definition at line 48 of file NonlinearFactor.h.
typedef boost::shared_ptr<This> gtsam::NonlinearFactor::shared_ptr |
Definition at line 53 of file NonlinearFactor.h.
|
protected |
Definition at line 49 of file NonlinearFactor.h.
|
inline |
Default constructor for I/O only
Definition at line 59 of file NonlinearFactor.h.
|
inline |
Constructor from a collection of the keys involved in this factor
Definition at line 65 of file NonlinearFactor.h.
|
inlinevirtual |
Destructor
Definition at line 83 of file NonlinearFactor.h.
|
inlinevirtual |
Checks whether a factor should be used based on a set of values. This is primarily used to implment 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, and gtsam::BoundingConstraint1< VALUE >.
Definition at line 106 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 TestNaryFactor, gtsam::example::smallOptimize::UnaryFactor, gtsam::NonlinearEquality2< VALUE >, gtsam::CombinedImuFactor, gtsam::ImuFactor2, TestFactor4, gtsam::EssentialMatrixFactor3, gtsam::NonlinearEquality1< VALUE >, simulated2D::GenericMeasurement< POSE, LANDMARK >, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::ImuFactor, gtsam::LinearizedHessianFactor, gtsam::PendulumFactorPk1, simulated2D::GenericOdometry< VALUE >, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::Pose3AttitudeFactor, gtsam::MagFactor3, simulated2D::inequality_constraints::MinDistanceConstraint< POSE, POINT >, gtsam::SmartRangeFactor, gtsam::NonlinearEquality< VALUE >, gtsam::AHRSFactor, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< gtsam::Point3 >, simulated2D::GenericPrior< VALUE >, gtsam::PendulumFactorPk, gtsam::MagFactor2, gtsam::GPSFactor2, gtsam::EssentialMatrixFactor2, simulated2D::inequality_constraints::MaxDistanceConstraint< VALUE >, simulated2DOriented::GenericOdometry< VALUE >, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::LinearContainerFactor, gtsam::LinearizedJacobianFactor, gtsam::Rot3AttitudeFactor, gtsam::MagFactor1, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, UnaryFactor, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::DiscreteEulerPoincareHelicopter, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::TriangulationFactor< CAMERA >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::RotateDirectionsFactor, gtsam::PendulumFactor2, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::FunctorizedFactor< R, T >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::VelocityConstraint, gtsam::BetweenFactor< VALUE >, gtsam::GPSFactor, gtsam::PriorFactor< VALUE >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::DummyFactor< CAMERA >, gtsam::EssentialMatrixConstraint, simulated2D::inequality_constraints::ScalarCoordConstraint1< VALUE, IDX >, gtsam::PoseBetweenFactor< POSE >, gtsam::EssentialMatrixFactor, gtsam::PosePriorFactor< POSE >, gtsam::PoseTranslationPrior< POSE >, gtsam::MagFactor, gtsam::AntiFactor, gtsam::FullIMUFactor< POSE >, gtsam::PoseRotationPrior< POSE >, gtsam::RangeFactor< A1, A2, T >, gtsam::IMUFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::PendulumFactor1, gtsam::RotateFactor, gtsam::Reconstruction, and gtsam::VelocityConstraint3.
Definition at line 118 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::LinearizedHessianFactor, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::NoiseModelFactor, NonlinearMotionModel, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::LinearizedJacobianFactor, gtsam::WhiteNoiseFactor, gtsam::ShonanGaugeFactor, gtsam::AntiFactor, gtsam::LinearContainerFactor, gtsam::KarcherMeanFactor< T >, and gtsam::DummyFactor< CAMERA >.
|
virtual |
Check if two factors are equal
Reimplemented in TestNaryFactor, gtsam::CombinedImuFactor, NonlinearMeasurementModel, gtsam::ImuFactor2, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::LinearizedHessianFactor, gtsam::ImuFactor, gtsam::InvDepthFactorVariant3b, gtsam::Pose3AttitudeFactor, gtsam::NoiseModelFactor, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::AHRSFactor, NonlinearMotionModel, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::GPSFactor2, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::LinearizedJacobianFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::Rot3AttitudeFactor, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::SmartStereoProjectionPoseFactor, gtsam::NonlinearEquality< VALUE >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::SmartStereoProjectionFactor, gtsam::SmartProjectionFactor< CAMERA >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::TriangulationFactor< CAMERA >, gtsam::FunctorizedFactor< R, T >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactorEM< VALUE >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BetweenFactor< VALUE >, gtsam::ExpressionFactor< T >, 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::GPSFactor, gtsam::InvDepthFactorVariant2, gtsam::PoseTranslationPrior< POSE >, gtsam::InvDepthFactorVariant3a, gtsam::EssentialMatrixConstraint, gtsam::InvDepthFactorVariant1, gtsam::PosePriorFactor< POSE >, gtsam::OrientedPlane3DirectionPrior, gtsam::AntiFactor, gtsam::BiasedGPSFactor, gtsam::LinearContainerFactor, gtsam::ShonanFactor< d >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::PoseToPointFactor, gtsam::IMUFactor< POSE >, and gtsam::DummyFactor< CAMERA >.
Definition at line 36 of file NonlinearFactor.cpp.
|
pure virtual |
Calculate the error of the factor This is typically equal to log-likelihood, e.g. in case of Gaussian. You can override this for systems with unusual noise models.
Implemented in gtsam::SmartStereoProjectionFactor, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, NonlinearMeasurementModel, gtsam::LinearizedHessianFactor, gtsam::NoiseModelFactor, NonlinearMotionModel, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::LinearizedJacobianFactor, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::NonlinearEquality< VALUE >, gtsam::WhiteNoiseFactor, gtsam::SmartStereoProjectionPoseFactor, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::BetweenFactorEM< VALUE >, gtsam::StereoFactor, gtsam::ShonanGaugeFactor, gtsam::AntiFactor, gtsam::LinearContainerFactor, gtsam::KarcherMeanFactor< T >, gtsam::DummyFactor< CAMERA >, and gtsam::PinholeFactor.
|
pure virtual |
linearize to a GaussianFactor
Implemented in gtsam::SmartStereoProjectionFactor, NonlinearMeasurementModel, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::LinearizedHessianFactor, gtsam::NoiseModelFactor, NonlinearMotionModel, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::NonlinearEquality< VALUE >, gtsam::WhiteNoiseFactor, gtsam::TriangulationFactor< CAMERA >, gtsam::LinearizedJacobianFactor, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::BetweenFactorEM< VALUE >, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< gtsam::Point3 >, gtsam::StereoFactor, gtsam::ShonanGaugeFactor, gtsam::LinearContainerFactor, gtsam::AntiFactor, gtsam::KarcherMeanFactor< T >, gtsam::DummyFactor< CAMERA >, and gtsam::PinholeFactor.
|
overridevirtual |
Reimplemented from gtsam::Factor.
Reimplemented in TestNaryFactor, NonlinearMeasurementModel, gtsam::EssentialMatrixFactor3, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::LinearizedHessianFactor, gtsam::NoiseModelFactor, gtsam::InvDepthFactorVariant3b, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, NonlinearMotionModel, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::EssentialMatrixFactor2, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::LinearizedJacobianFactor, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::SmartStereoProjectionPoseFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::WhiteNoiseFactor, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::SmartStereoProjectionFactor, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::RotateDirectionsFactor, gtsam::VelocityConstraint, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactorEM< VALUE >, 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::AntiFactor, gtsam::ShonanFactor< d >, gtsam::RelativeElevationFactor, gtsam::IMUFactor< POSE >, gtsam::BearingFactor< A1, A2, T >, gtsam::BiasedGPSFactor, gtsam::RotateFactor, gtsam::PoseToPointFactor, gtsam::OrientedPlane3Factor, and gtsam::DummyFactor< CAMERA >.
Definition at line 26 of file NonlinearFactor.cpp.
NonlinearFactor::shared_ptr gtsam::NonlinearFactor::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
Definition at line 41 of file NonlinearFactor.cpp.
NonlinearFactor::shared_ptr gtsam::NonlinearFactor::rekey | ( | const KeyVector & | new_keys | ) | const |
Clones a factor and fully replaces its keys
new_keys | is the full replacement set of keys |
Definition at line 54 of file NonlinearFactor.cpp.