#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... | |
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 KeyVector & | keys () 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 | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Protected Attributes | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Private Types | |
typedef std::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) |
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 |
|
inline |
check equality
Definition at line 42 of file Factor.cpp.
|
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::HybridConditional, gtsam::HybridNonlinearFactor, gtsam::HybridGaussianFactor, gtsam::SymbolicFactor, gtsam::NonlinearFactor, gtsam::DiscreteFactor, and gtsam::GaussianFactor.
Definition at line 47 of file Factor.cpp.
|
inline |
|
inlinestaticprotected |
|
inlinestaticprotected |
|
inline |
|
inline |
|
virtual |
Reimplemented in gtsam::SymbolicConditional, gtsam::TableFactor, gtsam::SymbolicFactor, 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::HybridGaussianConditional, gtsam::HybridFactor, gtsam::HybridConditional, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::DiscreteFactor, gtsam::DiscreteDistribution, gtsam::DiscreteLookupTable, gtsam::DiscreteConditional, gtsam::DecisionTreeFactor, gtsam::LinearContainerFactor, gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::ImuFactor2, NonlinearMeasurementModel, gtsam::EssentialMatrixFactor3, gtsam::NonlinearEquality1< VALUE >, gtsam::CombinedImuFactor, gtsam::NoiseModelFactor, gtsam::ImuFactor, gtsam::LinearizedHessianFactor, gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::Pose3AttitudeFactor, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartFactorBase< StereoCamera >, gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >, gtsam::EssentialMatrixFactor2, gtsam::HybridNonlinearFactor, NonlinearMotionModel, gtsam::GPSFactor2, gtsam::ProjectionFactorRollingShutter, gtsam::Rot3AttitudeFactor, gtsam::SmartStereoProjectionFactorPP, gtsam::LinearizedJacobianFactor, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::SmartStereoProjectionPoseFactor, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::NonlinearEquality< VALUE >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::SmartStereoProjectionFactor, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, 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::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::MagPoseFactor< POSE >, gtsam::BetweenFactor< VALUE >, gtsam::EssentialMatrixFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::SmartRangeFactor, gtsam::GPSFactor, gtsam::EssentialMatrixConstraint, gtsam::PoseRotationPrior< POSE >, gtsam::BarometricFactor, gtsam::RelativeElevationFactor, gtsam::RotateFactor, gtsam::DummyFactor< CAMERA >, gtsam::GaussianFactor, gtsam::JacobianFactor, gtsam::HessianFactor, gtsam::BayesTreeOrphanWrapper< HybridBayesTreeClique >, gtsam::HybridGaussianFactor, gtsam::LinearInequality, gtsam::LinearEquality, gtsam::LinearCost, gtsam::Domain, gtsam::SingleValue, gtsam::AllDiff, gtsam::BinaryAllDiff, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::VelocityConstraint, gtsam::FullIMUFactor< POSE >, gtsam::IMUFactor< POSE >, gtsam::AHRSFactor, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactorEM< VALUE >, gtsam::CustomFactor, gtsam::PriorFactor< VALUE >, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PoseBetweenFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::BinaryMeasurement< T >, gtsam::ShonanFactor< d >, gtsam::AntiFactor, gtsam::BiasedGPSFactor, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::WhiteNoiseFactor, gtsam::GaussianDensity, and gtsam::GaussianConditional.
Definition at line 29 of file Factor.cpp.
|
virtual |
|
inline |
|
protected |