Public Member Functions | Private Types | Private Attributes | List of all members
gtsam::EssentialMatrixFactor Class Reference

#include <EssentialMatrixFactor.h>

Inheritance diagram for gtsam::EssentialMatrixFactor:
Inheritance graph
[legend]

Public Member Functions

gtsam::NonlinearFactor::shared_ptr clone () const override
 
 EssentialMatrixFactor (Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
 
template<class CALIBRATION >
 EssentialMatrixFactor (Key key, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, std::shared_ptr< CALIBRATION > K)
 
Vector evaluateError (const EssentialMatrix &E, OptionalMatrixType H) const override
 vector of errors returns 1D vector More...
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactorN< EssentialMatrix >
Key key () const
 
virtual Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const =0
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
 ~NoiseModelFactorN () override
 
 NoiseModelFactorN ()
 Default Constructor for I/O. More...
 
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
 
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys)
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
virtual Vector evaluateError (const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
 
Vector evaluateError (const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
 
Vector evaluateError (const ValueTypes &... x) const
 
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
AreAllMatrixPtrs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
Key key1 () const
 
Key key2 () const
 
Key key3 () const
 
Key key4 () const
 
Key key5 () const
 
Key key6 () const
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
size_t dim () const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const Values &c) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const SharedNoiseModelnoiseModel () const
 access to the noise model More...
 
 NoiseModelFactor ()
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 
Vector unweightedWhitenedError (const Values &c) const
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
double weight (const Values &c) const
 
Vector whitenedError (const Values &c) const
 
 ~NoiseModelFactor () override
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 
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
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
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 KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
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...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Private Types

typedef NoiseModelFactorN< EssentialMatrixBase
 
typedef EssentialMatrixFactor This
 

Private Attributes

Vector3 vA_
 
Vector3 vB_
 Homogeneous versions, in ideal coordinates. More...
 

Additional Inherited Members

- Public Types inherited from gtsam::NoiseModelFactorN< EssentialMatrix >
enum  
 N is the number of variables (N-way factor) More...
 
using ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef std::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::NonlinearFactor
typedef std::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys. More...
 
typedef KeyVector::iterator iterator
 Iterator over keys. More...
 
- Protected Types inherited from gtsam::NoiseModelFactorN< EssentialMatrix >
using Base = NoiseModelFactor
 
using KeyType = Key
 
using MatrixTypeT = Matrix
 
using OptionalMatrixTypeT = Matrix *
 
using This = NoiseModelFactorN< ValueTypes... >
 
using IsConvertible = typename std::enable_if< std::is_convertible< From, To >::value, void >::type
 
using IndexIsValid = typename std::enable_if<(I >=1) &&(I<=N), void >::type
 
using ContainerElementType = typename std::decay< decltype(*std::declval< Container >().begin())>::type
 
using IsContainerOfKeys = IsConvertible< ContainerElementType< Container >, Key >
 
using AreAllMatrixRefs = std::enable_if_t<(... &&std::is_convertible< Args, Matrix & >::value), Ret >
 
using IsMatrixPointer = std::is_same< typename std::decay_t< Arg >, Matrix * >
 
using IsNullpointer = std::is_same< typename std::decay_t< Arg >, std::nullptr_t >
 
using AreAllMatrixPtrs = std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret >
 
- 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)
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

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

Definition at line 34 of file EssentialMatrixFactor.h.

Member Typedef Documentation

◆ Base

Definition at line 37 of file EssentialMatrixFactor.h.

◆ This

Definition at line 38 of file EssentialMatrixFactor.h.

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

Definition at line 53 of file EssentialMatrixFactor.h.

◆ EssentialMatrixFactor() [2/2]

template<class CALIBRATION >
gtsam::EssentialMatrixFactor::EssentialMatrixFactor ( Key  key,
const Point2 pA,
const Point2 pB,
const SharedNoiseModel model,
std::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

Definition at line 70 of file EssentialMatrixFactor.h.

Member Function Documentation

◆ clone()

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

Reimplemented from gtsam::NonlinearFactor.

Definition at line 80 of file EssentialMatrixFactor.h.

◆ evaluateError()

Vector gtsam::EssentialMatrixFactor::evaluateError ( const EssentialMatrix E,
OptionalMatrixType  H 
) const
inlineoverride

vector of errors returns 1D vector

Definition at line 96 of file EssentialMatrixFactor.h.

◆ print()

void gtsam::EssentialMatrixFactor::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlineoverridevirtual

print

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 86 of file EssentialMatrixFactor.h.

Member Data Documentation

◆ vA_

Vector3 gtsam::EssentialMatrixFactor::vA_
private

Definition at line 35 of file EssentialMatrixFactor.h.

◆ vB_

Vector3 gtsam::EssentialMatrixFactor::vB_
private

Homogeneous versions, in ideal coordinates.

Definition at line 35 of file EssentialMatrixFactor.h.


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


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:15:22