GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Protected Attributes | List of all members
gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION > Class Template Reference

#include <MultiProjectionFactor.h>

Inheritance diagram for gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >:
Inheritance graph
[legend]
Collaboration diagram for gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >:
Collaboration graph
[legend]

Public Types

typedef NoiseModelFactor Base
 shorthand for base class type
 
typedef MultiProjectionFactor< POSE, LANDMARK, CALIBRATION > This
 shorthand for this class
 
typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor
 
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Public Member Functions

 MultiProjectionFactor ()
 Default constructor.
 
 MultiProjectionFactor (const Vector &measured, const SharedNoiseModel &model, KeySet poseKeys, Key pointKey, const std::shared_ptr< CALIBRATION > &K, std::optional< POSE > body_P_sensor={})
 
 MultiProjectionFactor (const Vector &measured, const SharedNoiseModel &model, KeySet poseKeys, Key pointKey, const std::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality, std::optional< POSE > body_P_sensor={})
 
 ~MultiProjectionFactor () override
 
NonlinearFactor::shared_ptr clone () const override
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 Evaluate error h(x)-z and optionally derivatives.
 
Vector evaluateError (const Pose3 &pose, const Point3 &point, OptionalJacobian< 2, 6 > H1={}, OptionalJacobian< 2, 3 > H2={}) const
 
const Vector & measured () const
 
const std::shared_ptr< CALIBRATION > calibration () const
 
bool verboseCheirality () const
 
bool throwCheirality () const
 
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 rekey (const std::map< Key, Key > &rekey_mapping) const
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 
virtual bool sendable () 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 ()
 

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

Vector measured_
 2D measurement for each of the n views
 
std::shared_ptr< CALIBRATION > K_
 shared pointer to calibration object
 
std::optional< POSE > body_P_sensor_
 The pose of the sensor in the body frame.
 
bool throwCheirality_
 If true, rethrows Cheirality exceptions (default: false)
 
bool verboseCheirality_
 If true, prints text for Cheirality exceptions (default: false)
 
SharedNoiseModel noiseModel_
 
KeyVector keys_
 The keys involved in this factor.
 

Detailed Description

template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
class gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >

Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here. i.e. the main building block for visual SLAM.

Constructor & Destructor Documentation

◆ MultiProjectionFactor() [1/2]

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::MultiProjectionFactor ( const Vector &  measured,
const SharedNoiseModel model,
KeySet  poseKeys,
Key  pointKey,
const std::shared_ptr< CALIBRATION > &  K,
std::optional< POSE >  body_P_sensor = {} 
)
inline

Constructor TODO: Mark argument order standard (keys, measurement, parameters)

Parameters
measuredis the 2n dimensional location of the n points in the n views (the measurements)
modelis the standard deviation (current version assumes that the uncertainty is the same for all views)
poseKeysis the set of indices corresponding to the cameras observing the same landmark
pointKeyis the index of the landmark
Kshared pointer to the constant calibration
body_P_sensoris the transform from body to sensor frame (default identity)

◆ MultiProjectionFactor() [2/2]

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::MultiProjectionFactor ( const Vector &  measured,
const SharedNoiseModel model,
KeySet  poseKeys,
Key  pointKey,
const std::shared_ptr< CALIBRATION > &  K,
bool  throwCheirality,
bool  verboseCheirality,
std::optional< POSE >  body_P_sensor = {} 
)
inline

Constructor with exception-handling flags TODO: Mark argument order standard (keys, measurement, parameters)

Parameters
measuredis the 2 dimensional location of point in image (the measurement)
modelis the standard deviation
poseKeyis the index of the camera
pointKeyis the index of the landmark
Kshared pointer to the constant calibration
throwCheiralitydetermines whether Cheirality exceptions are rethrown
verboseCheiralitydetermines whether exceptions are printed for Cheirality
body_P_sensoris the transform from body to sensor frame (default identity)

◆ ~MultiProjectionFactor()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::~MultiProjectionFactor ( )
inlineoverride

Virtual destructor

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

◆ calibration()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
const std::shared_ptr<CALIBRATION> gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::calibration ( ) const
inline

return the calibration object

◆ clone()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
NonlinearFactor::shared_ptr gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

◆ 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

◆ 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 >.

◆ measured()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
const Vector& gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::measured ( ) const
inline

return the measurements

◆ print()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
void gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlineoverridevirtual

print

Parameters
soptional string naming the factor
keyFormatteroptional formatter useful for printing Symbols

Reimplemented from gtsam::NoiseModelFactor.

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

virtual bool gtsam::NonlinearFactor::sendable ( ) const
inlinevirtualinherited

Should the factor be evaluated in the same thread as the caller This is to enable factors that has shared states (like the Python GIL lock)

Reimplemented in gtsam::CustomFactor.

◆ size()

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

◆ throwCheirality()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
bool gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::throwCheirality ( ) const
inline

return flag for throwing cheirality exceptions

◆ unweightedWhitenedError()

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

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

◆ unwhitenedError()

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;

◆ verboseCheirality()

template<class POSE , class LANDMARK , class CALIBRATION = Cal3_S2>
bool gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >::verboseCheirality ( ) const
inline

return verbosity

◆ 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: