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

#include <EssentialMatrixFactor.h>

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

Public Member Functions

gtsam::NonlinearFactor::shared_ptr clone () const override
 
 EssentialMatrixFactor3 (Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model)
 
template<class CALIBRATION >
 EssentialMatrixFactor3 (Key key1, Key key2, const Point2 &pA, const Point2 &pB, const Rot3 &cRb, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
 
Vector evaluateError (const EssentialMatrix &E, const double &d, boost::optional< Matrix & > DE=boost::none, boost::optional< Matrix & > Dd=boost::none) const override
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
- Public Member Functions inherited from gtsam::EssentialMatrixFactor2
 EssentialMatrixFactor2 (Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model)
 
template<class CALIBRATION >
 EssentialMatrixFactor2 (Key key1, Key key2, const Point2 &pA, const Point2 &pB, const SharedNoiseModel &model, boost::shared_ptr< CALIBRATION > K)
 
- Public Member Functions inherited from gtsam::NoiseModelFactor2< EssentialMatrix, double >
Key key1 () const
 
Key key2 () const
 
 NoiseModelFactor2 ()
 
 NoiseModelFactor2 (const SharedNoiseModel &noiseModel, Key j1, Key j2)
 
Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
 
 ~NoiseModelFactor2 () override
 
- 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
 
boost::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
 
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)
 
virtual ~NonlinearFactor ()
 
virtual bool active (const Values &) const
 
shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
shared_ptr rekey (const KeyVector &new_keys) const
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys 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
 

Private Types

typedef EssentialMatrixFactor2 Base
 
typedef EssentialMatrixFactor3 This
 

Private Attributes

Rot3 cRb_
 Rotation from body to camera frame. More...
 

Additional Inherited Members

- Public Types inherited from gtsam::NoiseModelFactor2< EssentialMatrix, double >
typedef EssentialMatrix X1
 
typedef double X2
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::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::NoiseModelFactor2< EssentialMatrix, double >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor2< EssentialMatrix, double > This
 
- 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)
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
- 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

Binary factor that optimizes for E and inverse depth d: assumes measurement in image 2 is perfect, and returns re-projection error in image 1 This version takes an extrinsic rotation to allow for omni-directional rigs

Definition at line 213 of file EssentialMatrixFactor.h.

Member Typedef Documentation

Definition at line 215 of file EssentialMatrixFactor.h.

Definition at line 216 of file EssentialMatrixFactor.h.

Constructor & Destructor Documentation

gtsam::EssentialMatrixFactor3::EssentialMatrixFactor3 ( Key  key1,
Key  key2,
const Point2 pA,
const Point2 pB,
const Rot3 cRb,
const SharedNoiseModel model 
)
inline

Constructor

Parameters
key1Essential Matrix variable key
key2Inverse depth variable key
pApoint in first camera, in calibrated coordinates
pBpoint in second camera, in calibrated coordinates
bRcextra rotation between "body" and "camera" frame
modelnoise model should be in calibrated coordinates, as well

Definition at line 231 of file EssentialMatrixFactor.h.

template<class CALIBRATION >
gtsam::EssentialMatrixFactor3::EssentialMatrixFactor3 ( Key  key1,
Key  key2,
const Point2 pA,
const Point2 pB,
const Rot3 cRb,
const SharedNoiseModel model,
boost::shared_ptr< CALIBRATION >  K 
)
inline

Constructor

Parameters
key1Essential Matrix variable key
key2Inverse depth variable key
pApoint in first camera, in pixel coordinates
pBpoint in second camera, in pixel coordinates
Kcalibration object, will be used only in constructor
modelnoise model should be in pixels, as well

Definition at line 246 of file EssentialMatrixFactor.h.

Member Function Documentation

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

Reimplemented from gtsam::EssentialMatrixFactor2.

Definition at line 253 of file EssentialMatrixFactor.h.

Vector gtsam::EssentialMatrixFactor3::evaluateError ( const EssentialMatrix ,
const double &  ,
boost::optional< Matrix & >  H1 = boost::none,
boost::optional< Matrix & >  H2 = boost::none 
) const
inlineoverridevirtual

Override this method to finish implementing a binary factor. If any of the optional Matrix reference arguments are specified, it should compute both the function evaluation and its derivative(s) in X1 (and/or X2).

Reimplemented from gtsam::EssentialMatrixFactor2.

Definition at line 270 of file EssentialMatrixFactor.h.

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

print

Reimplemented from gtsam::EssentialMatrixFactor2.

Definition at line 259 of file EssentialMatrixFactor.h.

Member Data Documentation

Rot3 gtsam::EssentialMatrixFactor3::cRb_
private

Rotation from body to camera frame.

Definition at line 218 of file EssentialMatrixFactor.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:08