|
|
class | boost::serialization::access |
| | Serialization function.
|
|
|
| Factor () |
| | Default constructor for I/O.
|
| template<typename CONTAINER> |
| | Factor (const CONTAINER &keys) |
| | Construct factor from container of keys.
|
| template<typename ITERATOR> |
| | Factor (ITERATOR first, ITERATOR last) |
| | Construct factor from iterator keys.
|
| template<typename CONTAINER> |
| static Factor | FromKeys (const CONTAINER &keys) |
| | Construct factor from container of keys.
|
| template<typename ITERATOR> |
| static Factor | FromIterators (ITERATOR first, ITERATOR last) |
| | Construct factor from iterator keys.
|
|
|
virtual | ~Factor ()=default |
| | Default destructor.
|
|
bool | empty () const |
| | Whether the factor is empty (involves zero variables).
|
|
Key | front () const |
| | First key.
|
|
Key | back () const |
| | Last key.
|
|
const_iterator | find (Key key) const |
| | find
|
|
const KeyVector & | keys () const |
| | Access the factor's involved variable keys.
|
|
const_iterator | begin () const |
| | Iterator at beginning of involved variable keys.
|
|
const_iterator | end () const |
| | Iterator at end of involved variable keys.
|
| virtual double | error (const HybridValues &c) const |
| | All factor types need to implement an error function.
|
| size_t | size () const |
| virtual void | print (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
| | print
|
| virtual void | printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
| | print only keys
|
|
bool | equals (const This &other, double tol=1e-9) const |
| | check equality
|
| KeyVector & | keys () |
|
iterator | begin () |
| | Iterator at beginning of involved variable keys.
|
|
iterator | end () |
| | Iterator at end of involved variable keys.
|
|
|
typedef KeyVector::iterator | iterator |
| | Iterator over keys.
|
|
typedef KeyVector::const_iterator | const_iterator |
| | Const iterator over keys.
|
|
|
KeyVector | keys_ |
| | The keys involved in this factor.
|
◆ Factor() [1/2]
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.
◆ Factor() [2/2]
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.
◆ error()
All factor types need to implement an error function.
In factor graphs, this is the negative log-likelihood.
Reimplemented in gtsam::DecisionTreeFactor, gtsam::DiscreteConditional, gtsam::DiscreteFactor, gtsam::GaussianFactor, gtsam::GaussianMixture, gtsam::GaussianMixtureFactor, gtsam::HessianFactor, gtsam::HybridConditional, gtsam::JacobianFactor, gtsam::MixtureFactor, gtsam::NonlinearFactor, gtsam::SymbolicConditional, and gtsam::SymbolicFactor.
◆ FromIterators()
template<typename ITERATOR>
| 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.
◆ FromKeys()
template<typename CONTAINER>
| 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.
◆ keys()
- Returns
- keys involved in this factor
◆ print()
| void gtsam::Factor::print |
( |
const std::string & | s = "Factor", |
|
|
const KeyFormatter & | formatter = DefaultKeyFormatter ) const |
|
virtual |
print
Reimplemented in gtsam::AHRSFactor, gtsam::AntiFactor, gtsam::BarometricFactor, gtsam::BayesTreeOrphanWrapper< HybridBayesTreeClique >, gtsam::BearingFactor< A1, A2, T >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::BetweenFactor< VALUE >, gtsam::BinaryMeasurement< T >, gtsam::CombinedImuFactor, gtsam::CustomFactor, gtsam::DecisionTreeFactor, gtsam::DiscreteConditional, gtsam::DiscreteDistribution, gtsam::DiscreteFactor, gtsam::DiscreteLookupTable, gtsam::EssentialMatrixConstraint, gtsam::EssentialMatrixFactor2, gtsam::EssentialMatrixFactor3, gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::EssentialMatrixFactor, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >, gtsam::ExpressionFactor< typename Range< A1, A1 >::result_type >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::FunctorizedFactor< R, T >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::FunctorizedFactor< double, typename BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::GaussianConditional, gtsam::GaussianDensity, gtsam::GaussianFactor, gtsam::GaussianMixture, gtsam::GaussianMixtureFactor, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::GPSFactor2, gtsam::GPSFactor, gtsam::HessianFactor, gtsam::HybridConditional, gtsam::HybridFactor, gtsam::ImuFactor2, gtsam::ImuFactor, gtsam::JacobianFactor, gtsam::LinearContainerFactor, gtsam::MagPoseFactor< POSE >, gtsam::MixtureFactor, gtsam::NoiseModelFactor, gtsam::NonlinearEquality1< VALUE >, gtsam::NonlinearEquality< VALUE >, gtsam::NonlinearFactor, gtsam::OrientedPlane3DirectionPrior, gtsam::OrientedPlane3Factor, gtsam::Pose3AttitudeFactor, gtsam::PoseRotationPrior< POSE >, gtsam::PoseTranslationPrior< POSE >, gtsam::PriorFactor< VALUE >, gtsam::RangeFactor< A1, A2, T >, gtsam::RangeFactor< A1, A2 >, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::RangeFactorWithTransform< A1, A2 >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::RegularImplicitSchurFactor< CAMERA >, gtsam::Rot3AttitudeFactor, gtsam::RotateDirectionsFactor, gtsam::RotateFactor, gtsam::ShonanFactor< d >, gtsam::ShonanFactor< 2 >, gtsam::ShonanFactor< 3 >, gtsam::SmartFactorBase< CAMERA >, gtsam::SmartFactorBase< PinholePose< CALIBRATION > >, gtsam::SmartProjectionFactor< CAMERA >, gtsam::SmartProjectionFactor< Camera >, gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >, gtsam::SmartProjectionPoseFactor< CALIBRATION >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SymbolicConditional, gtsam::SymbolicFactor, gtsam::TriangulationFactor< CAMERA >, and gtsam::WhiteNoiseFactor.
◆ printKeys()
| void gtsam::Factor::printKeys |
( |
const std::string & | s = "Factor", |
|
|
const KeyFormatter & | formatter = DefaultKeyFormatter ) const |
|
virtual |
◆ size()
| size_t gtsam::Factor::size |
( |
| ) |
const |
|
inline |
- Returns
- the number of variables involved in this factor
The documentation for this class was generated from the following files:
- /build/gtsam-Xg031d/gtsam-4.2.0+dfsg/gtsam/inference/Factor.h
- /build/gtsam-Xg031d/gtsam-4.2.0+dfsg/gtsam/inference/Factor.cpp