Public Types | Public Member Functions | Protected Attributes | Private Types | List of all members
gtsam::Factor Class Reference

#include <Factor.h>

Inheritance diagram for gtsam::Factor:
Inheritance graph
[legend]

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< Factorshared_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 KeyVectorkeys () 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
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 
template<class Archive >
void serialize (Archive &ar, const unsigned int)
 

Detailed Description

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.

Definition at line 54 of file Factor.h.

Member Typedef Documentation

typedef KeyVector::const_iterator gtsam::Factor::const_iterator

Const iterator over keys.

Definition at line 67 of file Factor.h.

typedef KeyVector::iterator gtsam::Factor::iterator

Iterator over keys.

Definition at line 64 of file Factor.h.

typedef boost::shared_ptr<Factor> gtsam::Factor::shared_ptr
private

A shared_ptr to this class.

Definition at line 60 of file Factor.h.

typedef Factor gtsam::Factor::This
private

This class.

Definition at line 59 of file Factor.h.

Constructor & Destructor Documentation

gtsam::Factor::Factor ( )
inlineprotected

Default constructor for I/O

Definition at line 78 of file Factor.h.

template<typename CONTAINER >
gtsam::Factor::Factor ( const CONTAINER &  keys)
inlineexplicitprotected

Construct factor from container of keys. This constructor is used internally from derived factor constructors, either from a container of keys or from a boost::assign::list_of.

Definition at line 83 of file Factor.h.

template<typename ITERATOR >
gtsam::Factor::Factor ( ITERATOR  first,
ITERATOR  last 
)
inlineprotected

Construct factor from iterator keys. This constructor may be used internally from derived factor constructors, although our code currently does not use this.

Definition at line 88 of file Factor.h.

virtual gtsam::Factor::~Factor ( )
virtualdefault

Default destructor.

Member Function Documentation

Key gtsam::Factor::back ( ) const
inline

Last key.

Definition at line 118 of file Factor.h.

const_iterator gtsam::Factor::begin ( ) const
inline

Iterator at beginning of involved variable keys

Definition at line 127 of file Factor.h.

iterator gtsam::Factor::begin ( )
inline

Iterator at beginning of involved variable keys

Definition at line 166 of file Factor.h.

const_iterator gtsam::Factor::end ( ) const
inline

Iterator at end of involved variable keys

Definition at line 130 of file Factor.h.

iterator gtsam::Factor::end ( )
inline

Iterator at end of involved variable keys

Definition at line 169 of file Factor.h.

bool gtsam::Factor::equals ( const This other,
double  tol = 1e-9 
) const
protected

check equality

Definition at line 42 of file Factor.cpp.

const_iterator gtsam::Factor::find ( Key  key) const
inline

find

Definition at line 121 of file Factor.h.

template<typename ITERATOR >
static Factor gtsam::Factor::FromIterators ( ITERATOR  first,
ITERATOR  last 
)
inlinestaticprotected

Construct factor from iterator keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

Definition at line 99 of file Factor.h.

template<typename CONTAINER >
static Factor gtsam::Factor::FromKeys ( const CONTAINER &  keys)
inlinestaticprotected

Construct factor from container of keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

Definition at line 93 of file Factor.h.

Key gtsam::Factor::front ( ) const
inline

First key.

Definition at line 115 of file Factor.h.

const KeyVector& gtsam::Factor::keys ( ) const
inline

Access the factor's involved variable keys.

Definition at line 124 of file Factor.h.

KeyVector& gtsam::Factor::keys ( )
inline
Returns
keys involved in this factor

Definition at line 163 of file Factor.h.

void gtsam::Factor::print ( const std::string &  s = "Factor",
const KeyFormatter formatter = DefaultKeyFormatter 
) const
virtual

print

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.

void gtsam::Factor::printKeys ( const std::string &  s = "Factor",
const KeyFormatter formatter = DefaultKeyFormatter 
) const
virtual

print only keys

Reimplemented in gtsam::SymbolicFactor.

Definition at line 35 of file Factor.cpp.

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

Definition at line 175 of file Factor.h.

size_t gtsam::Factor::size ( ) const
inline
Returns
the number of variables involved in this factor

Definition at line 135 of file Factor.h.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 173 of file Factor.h.

Member Data Documentation

KeyVector gtsam::Factor::keys_
protected

The keys involved in this factor.

Definition at line 72 of file Factor.h.


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


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