#include <EssentialMatrixFactor.h>
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< GaussianFactor > | linearize (const Values &x) const override |
const SharedNoiseModel & | noiseModel () 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... | |
KeyVector & | keys () |
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 KeyVector & | keys () 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< This > | shared_ptr |
Public Types inherited from gtsam::NonlinearFactor | |
typedef boost::shared_ptr< This > | shared_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... | |
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.
|
private |
Definition at line 215 of file EssentialMatrixFactor.h.
|
private |
Definition at line 216 of file EssentialMatrixFactor.h.
|
inline |
Constructor
key1 | Essential Matrix variable key |
key2 | Inverse depth variable key |
pA | point in first camera, in calibrated coordinates |
pB | point in second camera, in calibrated coordinates |
bRc | extra rotation between "body" and "camera" frame |
model | noise model should be in calibrated coordinates, as well |
Definition at line 231 of file EssentialMatrixFactor.h.
|
inline |
Constructor
key1 | Essential Matrix variable key |
key2 | Inverse depth variable key |
pA | point in first camera, in pixel coordinates |
pB | point in second camera, in pixel coordinates |
K | calibration object, will be used only in constructor |
model | noise model should be in pixels, as well |
Definition at line 246 of file EssentialMatrixFactor.h.
|
inlineoverridevirtual |
Reimplemented from gtsam::EssentialMatrixFactor2.
Definition at line 253 of file EssentialMatrixFactor.h.
|
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.
|
inlineoverridevirtual |
Reimplemented from gtsam::EssentialMatrixFactor2.
Definition at line 259 of file EssentialMatrixFactor.h.
|
private |
Rotation from body to camera frame.
Definition at line 218 of file EssentialMatrixFactor.h.