gtsam  4.0.0
gtsam
gtsam::EssentialMatrixFactor Class Reference

Detailed Description

Factor that evaluates epipolar error p'Ep for given essential matrix.

+ Inheritance diagram for gtsam::EssentialMatrixFactor:

Public Member Functions

 EssentialMatrixFactor (Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
 Constructor. More...
 
template<class CALIBRATION >
 EssentialMatrixFactor (Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
 Constructor. More...
 
virtual gtsam::NonlinearFactor::shared_ptr clone () const
 
virtual void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 print
 
Vector evaluateError (const EssentialMatrix &E, boost::optional< Matrix & > H=boost::none) const
 vector of errors returns 1D vector
 
- Public Member Functions inherited from gtsam::NoiseModelFactor1< EssentialMatrix >
 NoiseModelFactor1 ()
 Default constructor for I/O only.
 
 NoiseModelFactor1 (const SharedNoiseModel &noiseModel, Key key1)
 Constructor. More...
 
Key key () const
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const
 Calls the 1-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class.
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor ()
 Default constructor for I/O only.
 
virtual ~NoiseModelFactor ()
 Destructor.
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 Constructor.
 
virtual bool equals (const NonlinearFactor &f, double tol=1e-9) const
 Check if two factors are equal.
 
virtual size_t dim () const
 get the dimension of the factor (number of rows on linearization)
 
const SharedNoiseModelnoiseModel () const
 access to the noise model
 
Vector whitenedError (const Values &c) const
 Vector of errors, whitened This is the raw error, i.e., i.e. More...
 
virtual double error (const Values &c) const
 Calculate the error of the factor. More...
 
boost::shared_ptr< GaussianFactorlinearize (const Values &x) const
 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) \).
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 Default constructor for I/O only.
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 Constructor from a collection of the keys involved in this factor.
 
virtual ~NonlinearFactor ()
 Destructor.
 
virtual bool active (const Values &) const
 Checks whether a factor should be used based on a set of values. More...
 
shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 Creates a shared_ptr clone of the factor with different keys using a map from old->new keys.
 
shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys. More...
 
- Public Member Functions inherited from gtsam::Factor
KeyVectorkeys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 
void print (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print
 
void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
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
 Iterator at beginning of involved variable keys.
 
const_iterator end () const
 Iterator at end of involved variable keys.
 
size_t size () const
 

Additional Inherited Members

- Public Types inherited from gtsam::NoiseModelFactor1< EssentialMatrix >
typedef EssentialMatrix X
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 Noise model.
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 
- Protected Types inherited from gtsam::NoiseModelFactor1< EssentialMatrix >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor1< EssentialMatrixThis
 
- Protected Types inherited from gtsam::NoiseModelFactor
typedef NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 Constructor - only for subclasses, as this does not set keys.
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 Default constructor for I/O.
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor.
 

Constructor & Destructor Documentation

◆ EssentialMatrixFactor() [1/2]

gtsam::EssentialMatrixFactor::EssentialMatrixFactor ( Key  key,
const Point2 pA,
const Point2 pB,
const SharedNoiseModel model 
)
inline

Constructor.

Parameters
keyEssential Matrix variable key
pApoint in first camera, in calibrated coordinates
pBpoint in second camera, in calibrated coordinates
modelnoise model is about dot product in ideal, homogeneous coordinates

◆ EssentialMatrixFactor() [2/2]

template<class CALIBRATION >
gtsam::EssentialMatrixFactor::EssentialMatrixFactor ( Key  key,
const Point2 pA,
const Point2 pB,
const SharedNoiseModel model,
boost::shared_ptr< CALIBRATION >  K 
)
inline

Constructor.

Parameters
keyEssential Matrix variable key
pApoint in first camera, in pixel coordinates
pBpoint in second camera, in pixel coordinates
modelnoise model is about dot product in ideal, homogeneous coordinates
Kcalibration object, will be used only in constructor

Member Function Documentation

◆ clone()

virtual gtsam::NonlinearFactor::shared_ptr gtsam::EssentialMatrixFactor::clone ( ) const
inlinevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.


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