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

#include <EssentialMatrixConstraint.h>

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

Public Types

typedef std::shared_ptr< EssentialMatrixConstraintshared_ptr
 
- Public Types inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
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...
 

Public Member Functions

gtsam::NonlinearFactor::shared_ptr clone () const override
 
bool equals (const NonlinearFactor &expected, double tol=1e-9) const override
 
 EssentialMatrixConstraint ()
 
 EssentialMatrixConstraint (Key key1, Key key2, const EssentialMatrix &measuredE, const SharedNoiseModel &model)
 
Vector evaluateError (const Pose3 &p1, const Pose3 &p2, OptionalMatrixType Hp1, OptionalMatrixType Hp2) const override
 
const EssentialMatrixmeasured () const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
 ~EssentialMatrixConstraint () override
 
- Public Member Functions inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
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
 
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< Pose3, Pose3Base
 
typedef EssentialMatrixConstraint This
 

Private Attributes

EssentialMatrix measuredE_
 

Additional Inherited Members

- Static Public Attributes inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
constexpr static auto N
 N is the number of variables (N-way factor) More...
 
- Protected Types inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
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

Binary factor between two Pose3 variables induced by an EssentialMatrix measurement

Definition at line 30 of file EssentialMatrixConstraint.h.

Member Typedef Documentation

◆ Base

Definition at line 35 of file EssentialMatrixConstraint.h.

◆ shared_ptr

Definition at line 45 of file EssentialMatrixConstraint.h.

◆ This

Definition at line 34 of file EssentialMatrixConstraint.h.

Constructor & Destructor Documentation

◆ EssentialMatrixConstraint() [1/2]

gtsam::EssentialMatrixConstraint::EssentialMatrixConstraint ( )
inline

default constructor - only use for serialization

Definition at line 48 of file EssentialMatrixConstraint.h.

◆ EssentialMatrixConstraint() [2/2]

gtsam::EssentialMatrixConstraint::EssentialMatrixConstraint ( Key  key1,
Key  key2,
const EssentialMatrix measuredE,
const SharedNoiseModel model 
)
inline

Constructor

Parameters
key1key for first pose
key2key for second pose
measuredEmeasured EssentialMatrix
modelnoise model, 5D !

Definition at line 58 of file EssentialMatrixConstraint.h.

◆ ~EssentialMatrixConstraint()

gtsam::EssentialMatrixConstraint::~EssentialMatrixConstraint ( )
inlineoverride

Definition at line 63 of file EssentialMatrixConstraint.h.

Member Function Documentation

◆ clone()

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

Reimplemented from gtsam::NonlinearFactor.

Definition at line 67 of file EssentialMatrixConstraint.h.

◆ equals()

bool gtsam::EssentialMatrixConstraint::equals ( const NonlinearFactor expected,
double  tol = 1e-9 
) const
overridevirtual

equals

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 37 of file EssentialMatrixConstraint.cpp.

◆ evaluateError()

Vector gtsam::EssentialMatrixConstraint::evaluateError ( const Pose3 p1,
const Pose3 p2,
OptionalMatrixType  Hp1,
OptionalMatrixType  Hp2 
) const
override

implement functions needed to derive from Factor vector of errors

Definition at line 45 of file EssentialMatrixConstraint.cpp.

◆ measured()

const EssentialMatrix& gtsam::EssentialMatrixConstraint::measured ( ) const
inline

return the measured

Definition at line 88 of file EssentialMatrixConstraint.h.

◆ print()

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

implement functions needed for Testable print

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 28 of file EssentialMatrixConstraint.cpp.

Member Data Documentation

◆ measuredE_

EssentialMatrix gtsam::EssentialMatrixConstraint::measuredE_
private

Definition at line 37 of file EssentialMatrixConstraint.h.


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


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:23:43