GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Protected Types | Protected Attributes | List of all members
gtsam::CustomFactor Class Reference
Inheritance diagram for gtsam::CustomFactor:
Inheritance graph
[legend]
Collaboration diagram for gtsam::CustomFactor:
Collaboration graph
[legend]

Public Types

typedef std::shared_ptr< Thisshared_ptr
 
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Public Member Functions

 CustomFactor ()=default
 
 CustomFactor (const SharedNoiseModel &noiseModel, const KeyVector &keys, const CustomErrorFunction &errorFunction)
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
void print (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
bool sendable () const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
size_t dim () const override
 
const SharedNoiseModelnoiseModel () const
 access to the noise model
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
Vector whitenedError (const Values &c) const
 
Vector unweightedWhitenedError (const Values &c) const
 
double weight (const Values &c) const
 
double error (const Values &c) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
Testable
bool equals (const This &other, double tol=1e-9) const
 check equality
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
Standard Interface
double error (const HybridValues &c) const override
 
virtual bool active (const Values &) const
 
virtual shared_ptr clone () const
 
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 
Standard Interface
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 KeyVectorkeys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
Advanced Interface
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Protected Types

using Base = NoiseModelFactor
 
using This = CustomFactor
 

Static Protected Member Functions

Standard Constructors
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 

Protected Attributes

CustomErrorFunction error_function_
 
SharedNoiseModel noiseModel_
 
KeyVector keys_
 The keys involved in this factor.
 

Member Typedef Documentation

◆ shared_ptr

typedef std::shared_ptr<This> gtsam::NoiseModelFactor::shared_ptr
inherited

Noise model

Constructor & Destructor Documentation

◆ CustomFactor() [1/2]

gtsam::CustomFactor::CustomFactor ( )
default

Default Constructor for I/O

◆ CustomFactor() [2/2]

gtsam::CustomFactor::CustomFactor ( const SharedNoiseModel noiseModel,
const KeyVector keys,
const CustomErrorFunction &  errorFunction 
)
inline

Constructor

Parameters
noiseModelshared pointer to noise model
keyskeys of the variables
errorFunctionthe error functional

Member Function Documentation

◆ active()

virtual bool gtsam::NonlinearFactor::active ( const Values ) const
inlinevirtualinherited

Checks whether a factor should be used based on a set of values. This is primarily used to implement inequality constraints that require a variable active set. For all others, the default implementation returning true solves this problem.

In an inequality/bounding constraint, this active() returns true when the constraint is NOT fulfilled.

Returns
true if the constraint is active

Reimplemented in gtsam::BoundingConstraint2< VALUE1, VALUE2 >, gtsam::AntiFactor, and gtsam::BoundingConstraint1< VALUE >.

◆ begin() [1/2]

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

Iterator at beginning of involved variable keys

◆ begin() [2/2]

iterator gtsam::Factor::begin ( )
inlineinherited

Iterator at beginning of involved variable keys

◆ clone()

virtual shared_ptr gtsam::NonlinearFactor::clone ( ) const
inlinevirtualinherited

Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses

By default, throws exception if subclass does not implement the function.

Reimplemented in gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::NonlinearEquality2< T >, gtsam::CombinedImuFactor, gtsam::ImuFactor2, gtsam::EssentialMatrixFactor3, gtsam::NonlinearEquality1< VALUE >, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::ImuFactor, gtsam::LinearizedHessianFactor, gtsam::PendulumFactorPk1, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::MagFactor3, gtsam::Pose3AttitudeFactor, gtsam::SmartRangeFactor, gtsam::NonlinearEquality< VALUE >, gtsam::AHRSFactor, gtsam::EssentialMatrixFactor2, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::MagFactor2, gtsam::PendulumFactorPk, gtsam::GPSFactor2, gtsam::ProjectionFactorRollingShutter, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::LinearContainerFactor, gtsam::LinearizedJacobianFactor, gtsam::Rot3AttitudeFactor, gtsam::MagFactor1, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::DiscreteEulerPoincareHelicopter, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::RotateDirectionsFactor, gtsam::PendulumFactor2, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::FunctorizedFactor< R, T >, gtsam::PartialPriorFactor< VALUE >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::MagPoseFactor< POSE >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactor< VALUE >, gtsam::EssentialMatrixFactor, gtsam::VelocityConstraint, gtsam::PriorFactor< VALUE >, gtsam::GPSFactor, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::BarometricFactor, gtsam::EssentialMatrixConstraint, gtsam::DummyFactor, gtsam::PoseBetweenFactor< POSE >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::PosePriorFactor< POSE >, gtsam::MagFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::AntiFactor, gtsam::RangeFactor< A1, A2, T >, gtsam::IMUFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::PendulumFactor1, gtsam::Reconstruction, gtsam::RotateFactor, and gtsam::VelocityConstraint3.

◆ cloneWithNewNoiseModel()

shared_ptr gtsam::NoiseModelFactor::cloneWithNewNoiseModel ( const SharedNoiseModel  newNoise) const
inherited

Creates a shared_ptr clone of the factor with a new noise model

◆ dim()

size_t gtsam::NoiseModelFactor::dim ( ) const
inlineoverridevirtualinherited

get the dimension of the factor (number of rows on linearization)

Implements gtsam::NonlinearFactor.

◆ end() [1/2]

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

Iterator at end of involved variable keys

◆ end() [2/2]

iterator gtsam::Factor::end ( )
inlineinherited

Iterator at end of involved variable keys

◆ equals()

bool gtsam::NoiseModelFactor::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
overridevirtualinherited

Check if two factors are equal

Reimplemented from gtsam::NonlinearFactor.

Reimplemented in gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::InvDepthFactorVariant3b, gtsam::ProjectionFactorRollingShutter, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::TriangulationFactor< CAMERA >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BetweenFactor< VALUE >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::PriorFactor< VALUE >, gtsam::SmartRangeFactor, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::OrientedPlane3DirectionPrior, gtsam::PoseTranslationPrior< POSE >, gtsam::InvDepthFactorVariant3a, gtsam::EssentialMatrixConstraint, gtsam::InvDepthFactorVariant1, gtsam::PosePriorFactor< POSE >, gtsam::BiasedGPSFactor, gtsam::ShonanFactor< d >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::RelativeElevationFactor, and gtsam::IMUFactor< POSE >.

◆ error() [1/2]

double gtsam::NonlinearFactor::error ( const HybridValues c) const
overridevirtualinherited

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

Reimplemented from gtsam::Factor.

◆ error() [2/2]

double gtsam::NoiseModelFactor::error ( const Values c) const
overridevirtualinherited

Calculate the error of the factor. This is the log-likelihood, e.g. \( 0.5(h(x)-z)^2/\sigma^2 \) in case of Gaussian. In this class, we take the raw prediction error \( h(x)-z \), ask the noise model to transform it to \( (h(x)-z)^2/\sigma^2 \), and then multiply by 0.5.

Reimplemented from gtsam::NonlinearFactor.

◆ FromIterators()

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

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 >
static Factor gtsam::Factor::FromKeys ( const CONTAINER &  keys)
inlinestaticprotectedinherited

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()

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

◆ linearize()

std::shared_ptr<GaussianFactor> gtsam::NoiseModelFactor::linearize ( const Values x) const
overridevirtualinherited

Linearize a non-linearFactorN to get a GaussianFactor, \( Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \) Hence \( b = z - h(x) = - \mathtt{error\_vector}(x) \)

Implements gtsam::NonlinearFactor.

Reimplemented in gtsam::TriangulationFactor< CAMERA >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, and gtsam::ExpressionFactor< double >.

◆ print()

void gtsam::CustomFactor::print ( const std::string &  s,
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtual

print

Reimplemented from gtsam::Factor.

◆ rekey() [1/2]

virtual shared_ptr gtsam::NonlinearFactor::rekey ( const std::map< Key, Key > &  rekey_mapping) const
virtualinherited

Creates a shared_ptr clone of the factor with different keys using a map from old->new keys

Reimplemented in gtsam::LinearContainerFactor.

◆ rekey() [2/2]

virtual shared_ptr gtsam::NonlinearFactor::rekey ( const KeyVector new_keys) const
virtualinherited

Clones a factor and fully replaces its keys

Parameters
new_keysis the full replacement set of keys

Reimplemented in gtsam::LinearContainerFactor.

◆ sendable()

bool gtsam::CustomFactor::sendable ( ) const
inlineoverridevirtual

Mark not sendable

Reimplemented from gtsam::NonlinearFactor.

◆ size()

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

◆ unweightedWhitenedError()

Vector gtsam::NoiseModelFactor::unweightedWhitenedError ( const Values c) const
inherited

Vector of errors, whitened, but unweighted by any loss function

◆ unwhitenedError() [1/2]

Vector gtsam::CustomFactor::unwhitenedError ( const Values x,
OptionalMatrixVecType  H = nullptr 
) const
overridevirtual

Calls the errorFunction closure, which is a std::function object One can check if a derivative is needed in the errorFunction by checking the length of Jacobian array

Implements gtsam::NoiseModelFactor.

◆ unwhitenedError() [2/2]

Vector gtsam::NoiseModelFactor::unwhitenedError ( const Values x,
std::vector< Matrix > &  H 
) const
inlineinherited

support taking in the actual vector instead of the pointer as well to get access to this version of the function from derived classes one will need to use the "using" keyword and specify that like this: public: using NoiseModelFactor::unwhitenedError;

◆ weight()

double gtsam::NoiseModelFactor::weight ( const Values c) const
inherited

Compute the effective weight of the factor from the noise model.

◆ whitenedError()

Vector gtsam::NoiseModelFactor::whitenedError ( const Values c) const
inherited

Vector of errors, whitened This is the raw error, i.e., i.e. \( (h(x)-z)/\sigma \) in case of a Gaussian


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