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...
 
Standard Interface
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 KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
virtual double error (const HybridValues &c) const
 
size_t size () const
 
Testable
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...
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
Advanced Interface
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Protected Attributes

KeyVector keys_
 The keys involved in this factor. More...
 

Private Types

typedef std::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)
 

Detailed Description

Definition at line 69 of file Factor.h.

Member Typedef Documentation

◆ const_iterator

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

Const iterator over keys.

Definition at line 82 of file Factor.h.

◆ iterator

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

Iterator over keys.

Definition at line 79 of file Factor.h.

◆ shared_ptr

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

A shared_ptr to this class.

Definition at line 75 of file Factor.h.

◆ This

typedef Factor gtsam::Factor::This
private

This class.

Definition at line 74 of file Factor.h.

Constructor & Destructor Documentation

◆ Factor() [1/3]

gtsam::Factor::Factor ( )
inlineprotected

Default constructor for I/O

Definition at line 93 of file Factor.h.

◆ Factor() [2/3]

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 98 of file Factor.h.

◆ Factor() [3/3]

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 103 of file Factor.h.

◆ ~Factor()

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

Default destructor.

Member Function Documentation

◆ back()

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

Last key.

Definition at line 136 of file Factor.h.

◆ begin() [1/2]

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

Iterator at beginning of involved variable keys

Definition at line 145 of file Factor.h.

◆ begin() [2/2]

iterator gtsam::Factor::begin ( )
inline

Iterator at beginning of involved variable keys

Definition at line 187 of file Factor.h.

◆ empty()

bool gtsam::Factor::empty ( ) const
inline

Whether the factor is empty (involves zero variables).

Definition at line 130 of file Factor.h.

◆ end() [1/2]

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

Iterator at end of involved variable keys

Definition at line 148 of file Factor.h.

◆ end() [2/2]

iterator gtsam::Factor::end ( )
inline

Iterator at end of involved variable keys

Definition at line 190 of file Factor.h.

◆ equals()

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

check equality

Definition at line 42 of file Factor.cpp.

◆ error()

double gtsam::Factor::error ( const HybridValues c) const
virtual

All factor types need to implement an error function. In factor graphs, this is the negative log-likelihood.

Reimplemented in gtsam::TableFactor, gtsam::DecisionTreeFactor, gtsam::GaussianMixture, gtsam::HybridConditional, gtsam::MixtureFactor, gtsam::GaussianMixtureFactor, gtsam::SymbolicFactor, gtsam::NonlinearFactor, gtsam::DiscreteFactor, and gtsam::GaussianFactor.

Definition at line 47 of file Factor.cpp.

◆ find()

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

find

Definition at line 139 of file Factor.h.

◆ FromIterators()

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 114 of file Factor.h.

◆ FromKeys()

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 108 of file Factor.h.

◆ front()

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

First key.

Definition at line 133 of file Factor.h.

◆ keys() [1/2]

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

Access the factor's involved variable keys.

Definition at line 142 of file Factor.h.

◆ keys() [2/2]

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

Definition at line 184 of file Factor.h.

◆ print()

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

print

Reimplemented in TestNaryFactor, gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::ImuFactor2, NonlinearMeasurementModel, gtsam::EssentialMatrixFactor3, gtsam::NonlinearEquality1< VALUE >, gtsam::CombinedImuFactor, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::NoiseModelFactor, gtsam::ImuFactor, gtsam::LinearizedHessianFactor, gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::Pose3AttitudeFactor, gtsam::InvDepthFactorVariant3b, gtsam::JacobianFactor, gtsam::HessianFactor, gtsam::MixtureFactor, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::AHRSFactor, gtsam::EssentialMatrixFactor2, gtsam::BayesTreeOrphanWrapper< HybridBayesTreeClique >, NonlinearMotionModel, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::GPSFactor2, gtsam::TableFactor, gtsam::ProjectionFactorRollingShutter, gtsam::GaussianMixture, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::DiscreteConditional, gtsam::HybridConditional, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::SmartStereoProjectionFactorPP, gtsam::LinearizedJacobianFactor, gtsam::GaussianConditional, gtsam::Rot3AttitudeFactor, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::SmartStereoProjectionPoseFactor, gtsam::WhiteNoiseFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::GaussianMixtureFactor, gtsam::NonlinearEquality< VALUE >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::HybridFactor, gtsam::LinearInequality, gtsam::SmartStereoProjectionFactor, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::SymbolicConditional, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::FunctorizedFactor< R, T >, 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::NonlinearFactor, gtsam::VelocityConstraint, gtsam::LinearEquality, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::MagPoseFactor< POSE >, gtsam::LinearCost, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::DecisionTreeFactor, gtsam::SymbolicFactor, gtsam::BetweenFactor< VALUE >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactorEM< VALUE >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::EssentialMatrixFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< gtsam::Point3 >, gtsam::SmartRangeFactor, gtsam::CustomFactor, gtsam::PriorFactor< VALUE >, gtsam::DiscreteDistribution, gtsam::GPSFactor, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::RangeFactor< A1, A2, T >, gtsam::OrientedPlane3DirectionPrior, gtsam::EssentialMatrixConstraint, gtsam::PoseRotationPrior< POSE >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::BarometricFactor, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant3a, gtsam::LocalOrientedPlane3Factor, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactorVariant1, gtsam::DiscreteFactor, gtsam::FullIMUFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::BinaryMeasurement< T >, gtsam::LinearContainerFactor, gtsam::ShonanFactor< d >, gtsam::RelativeElevationFactor, gtsam::IMUFactor< POSE >, gtsam::AntiFactor, gtsam::GaussianFactor, gtsam::BiasedGPSFactor, gtsam::GaussianDensity, gtsam::Domain, gtsam::DiscreteLookupTable, gtsam::BearingFactor< A1, A2, T >, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::RotateFactor, gtsam::OrientedPlane3Factor, gtsam::SingleValue, gtsam::DummyFactor< CAMERA >, gtsam::AllDiff, and gtsam::BinaryAllDiff.

Definition at line 29 of file Factor.cpp.

◆ printKeys()

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.

◆ size()

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

Definition at line 159 of file Factor.h.

Member Data Documentation

◆ keys_

KeyVector gtsam::Factor::keys_
protected

The keys involved in this factor.

Definition at line 87 of file Factor.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:18