#include <Factor.h>
Public Types | |
typedef KeyVector::const_iterator | const_iterator |
Const iterator over keys. More... | |
typedef KeyVector::iterator | iterator |
Iterator over keys. More... | |
Public Member Functions | |
virtual | ~Factor ()=default |
Default destructor. More... | |
Protected Attributes | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Private Types | |
typedef boost::shared_ptr< Factor > | shared_ptr |
A shared_ptr to this class. More... | |
typedef Factor | This |
This class. More... | |
Standard Constructors | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
template<typename CONTAINER > | |
static Factor | FromKeys (const CONTAINER &keys) |
template<typename ITERATOR > | |
static Factor | FromIterators (ITERATOR first, ITERATOR last) |
Standard Interface | |
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 |
Testable | |
bool | equals (const This &other, double tol=1e-9) const |
check equality More... | |
virtual void | print (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print More... | |
virtual void | printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print only keys More... | |
Advanced Interface | |
class | boost::serialization::access |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
template<class Archive > | |
void | serialize (Archive &ar, const unsigned int) |
This is the base class for all factor types. It is templated on a KEY type, which will be the type used to label variables. Key types currently in use in gtsam are Index with symbolic (IndexFactor, SymbolicFactorGraph) and Gaussian factors (GaussianFactor, JacobianFactor, HessianFactor, GaussianFactorGraph), and Key with nonlinear factors (NonlinearFactor, NonlinearFactorGraph). though currently only IndexFactor and IndexConditional derive from this class, using Index keys. This class does not store any data other than its keys. Derived classes store data such as matrices and probability tables.
Note that derived classes must redefine the ConditionalType and shared_ptr typedefs to refer to the associated conditional and shared_ptr types of the derived class. See IndexFactor, JacobianFactor, etc. for examples.
This class is not virtual for performance reasons - derived symbolic classes, IndexFactor and IndexConditional, need to be created and destroyed quickly during symbolic elimination. GaussianFactor and NonlinearFactor are virtual.
typedef KeyVector::const_iterator gtsam::Factor::const_iterator |
typedef KeyVector::iterator gtsam::Factor::iterator |
|
private |
|
private |
|
inlineprotected |
|
inlineexplicitprotected |
|
inlineprotected |
|
virtualdefault |
Default destructor.
|
inline |
|
inline |
|
inline |
|
inline |
|
protected |
check equality
Definition at line 42 of file Factor.cpp.
|
inline |
|
inlinestaticprotected |
|
inlinestaticprotected |
|
inline |
|
inline |
|
virtual |
Reimplemented in TestNaryFactor, gtsam::CombinedImuFactor, gtsam::ImuFactor2, NonlinearMeasurementModel, gtsam::NonlinearEquality1< VALUE >, gtsam::EssentialMatrixFactor3, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::LinearizedHessianFactor, gtsam::ImuFactor, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::JacobianFactor, gtsam::HessianFactor, gtsam::Pose3AttitudeFactor, gtsam::NoiseModelFactor, gtsam::InvDepthFactorVariant3b, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::AHRSFactor, NonlinearMotionModel, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::GPSFactor2, gtsam::EssentialMatrixFactor2, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::LinearizedJacobianFactor, gtsam::Rot3AttitudeFactor, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::SmartStereoProjectionPoseFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::WhiteNoiseFactor, gtsam::NonlinearEquality< VALUE >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::SymbolicConditional, gtsam::LinearInequality, 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::FunctorizedFactor< R, T >, gtsam::LinearEquality, gtsam::RotateDirectionsFactor, gtsam::SymbolicFactor, gtsam::LinearCost, gtsam::VelocityConstraint, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::GaussianConditional, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::DiscreteConditional, gtsam::BetweenFactorEM< VALUE >, gtsam::BetweenFactor< VALUE >, gtsam::PoseTranslationPrior< POSE >, gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::DiscreteFactor, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< gtsam::Point3 >, gtsam::RangeFactor< A1, A2, T >, gtsam::SmartRangeFactor, gtsam::DecisionTreeFactor, gtsam::PriorFactor< VALUE >, gtsam::GPSFactor, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::NonlinearFactor, gtsam::EssentialMatrixConstraint, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::BinaryMeasurement< T >, gtsam::InvDepthFactorVariant3a, gtsam::OrientedPlane3DirectionPrior, gtsam::PoseRotationPrior< POSE >, gtsam::Domain, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactorVariant1, gtsam::EssentialMatrixFactor, gtsam::FullIMUFactor< POSE >, gtsam::LocalOrientedPlane3Factor, gtsam::PosePriorFactor< POSE >, gtsam::LinearContainerFactor, gtsam::AntiFactor, gtsam::ShonanFactor< d >, gtsam::RelativeElevationFactor, gtsam::IMUFactor< POSE >, gtsam::GaussianDensity, gtsam::GaussianFactor, gtsam::BearingFactor< A1, A2, T >, gtsam::BiasedGPSFactor, gtsam::SingleValue, gtsam::RotateFactor, gtsam::PoseToPointFactor, gtsam::OrientedPlane3Factor, gtsam::AllDiff, gtsam::DummyFactor< CAMERA >, and gtsam::BinaryAllDiff.
Definition at line 29 of file Factor.cpp.
|
virtual |
|
inlineprivate |
|
inline |
|
friend |
|
protected |