Public Types | Public Member Functions | Private Types | Private Attributes | List of all members
gtsam::EssentialTransferFactorK< K > Class Template Reference

Transfers points between views using essential matrices, optimizes for calibrations of the views, as well. Note that the EssentialMatrixFactor4 does something similar but without transfer. More...

#include <TransferFactor.h>

Inheritance diagram for gtsam::EssentialTransferFactorK< K >:
Inheritance graph
[legend]

Public Types

using Base = NoiseModelFactorN< EM, EM, K, K, K >
 
using shared_ptr = std::shared_ptr< This >
 
using This = EssentialTransferFactorK< K >
 
- Public Types inherited from gtsam::NoiseModelFactorN< EssentialMatrix, EssentialMatrix, K, K, K >
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...
 

Public Member Functions

size_t dim () const override
 Return the dimension of the factor. More...
 
 EssentialTransferFactorK (EdgeKey edge1, EdgeKey edge2, const std::vector< Triplet > &triplets, const SharedNoiseModel &model=nullptr)
 Constructor that accepts a vector of point triplets. More...
 
Vector evaluateError (const EM &E1, const EM &E2, const K &Ka, const K &Kb, const K &Kc, OptionalMatrixType H1=nullptr, OptionalMatrixType H2=nullptr, OptionalMatrixType H3=nullptr, OptionalMatrixType H4=nullptr, OptionalMatrixType H5=nullptr) const override
 Evaluate error function. More...
 
Vector2 TransferError (const Matrix3 &Eca, const K &Ka, const Point2 &pa, const Matrix3 &Ecb, const K &Kb, const Point2 &pb, const K &Kc, const Point2 &pc) const
 Transfer points pa and pb to view c and evaluate error. More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactorN< EssentialMatrix, EssentialMatrix, K, K, K >
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
 
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)
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
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 clone () 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

using EM = EssentialMatrix
 
using Triplet = std::tuple< Point2, Point2, Point2 >
 

Private Attributes

std::vector< Triplettriplets_
 Point triplets. More...
 
- Private Attributes inherited from gtsam::TransferEdges< EssentialMatrix >
uint32_t c_
 The transfer target. More...
 
EdgeKey edge1_
 
EdgeKey edge2_
 The two EdgeKeys. More...
 

Additional Inherited Members

- Protected Types inherited from gtsam::NoiseModelFactorN< EssentialMatrix, EssentialMatrix, K, K, K >
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...
 
- Private Member Functions inherited from gtsam::TransferEdges< EssentialMatrix >
std::pair< Matrix3, Matrix3 > getMatrices (const EssentialMatrix &F1, const EssentialMatrix &F2) const
 Create Matrix3 objects based on EdgeKey configurations. More...
 
 TransferEdges (EdgeKey edge1, EdgeKey edge2)
 
- Static Private Member Functions inherited from gtsam::TransferEdges< EssentialMatrix >
static size_t ViewA (const EdgeKey &edge1, const EdgeKey &edge2)
 Returns the view A index based on the EdgeKeys. More...
 
static size_t ViewB (const EdgeKey &edge1, const EdgeKey &edge2)
 Returns the view B index based on the EdgeKeys. More...
 
static size_t ViewC (const EdgeKey &edge1, const EdgeKey &edge2)
 Returns the view C index based on the EdgeKeys. More...
 

Detailed Description

template<typename K>
class gtsam::EssentialTransferFactorK< K >

Transfers points between views using essential matrices, optimizes for calibrations of the views, as well. Note that the EssentialMatrixFactor4 does something similar but without transfer.

Note
Derives calibration keys from edges, and uses symbol 'k'.

This factor is templated on the calibration class K and extends the TransferFactor for EssentialMatrices. It involves two essential matrices and three calibration objects (Ka, Kb, Kc). The evaluateError function calibrates the image points, calls the base class's transfer method, and computes the error using bulk numerical differentiation.

Definition at line 224 of file TransferFactor.h.

Member Typedef Documentation

◆ Base

template<typename K >
using gtsam::EssentialTransferFactorK< K >::Base = NoiseModelFactorN<EM, EM, K, K, K>

Definition at line 232 of file TransferFactor.h.

◆ EM

template<typename K >
using gtsam::EssentialTransferFactorK< K >::EM = EssentialMatrix
private

Definition at line 227 of file TransferFactor.h.

◆ shared_ptr

template<typename K >
using gtsam::EssentialTransferFactorK< K >::shared_ptr = std::shared_ptr<This>

Definition at line 234 of file TransferFactor.h.

◆ This

template<typename K >
using gtsam::EssentialTransferFactorK< K >::This = EssentialTransferFactorK<K>

Definition at line 233 of file TransferFactor.h.

◆ Triplet

template<typename K >
using gtsam::EssentialTransferFactorK< K >::Triplet = std::tuple<Point2, Point2, Point2>
private

Definition at line 228 of file TransferFactor.h.

Constructor & Destructor Documentation

◆ EssentialTransferFactorK()

template<typename K >
gtsam::EssentialTransferFactorK< K >::EssentialTransferFactorK ( EdgeKey  edge1,
EdgeKey  edge2,
const std::vector< Triplet > &  triplets,
const SharedNoiseModel model = nullptr 
)
inline

Constructor that accepts a vector of point triplets.

Parameters
edge1First EdgeKey specifying E1: (a, c) or (c, a)
edge2Second EdgeKey specifying E2: (b, c) or (c, b)
tripletsA vector of triplets containing (pa, pb, pc)
modelAn optional SharedNoiseModel

Definition at line 244 of file TransferFactor.h.

Member Function Documentation

◆ dim()

template<typename K >
size_t gtsam::EssentialTransferFactorK< K >::dim ( ) const
inlineoverridevirtual

Return the dimension of the factor.

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 299 of file TransferFactor.h.

◆ evaluateError()

template<typename K >
Vector gtsam::EssentialTransferFactorK< K >::evaluateError ( const EM E1,
const EM E2,
const K Ka,
const K Kb,
const K Kc,
OptionalMatrixType  H1 = nullptr,
OptionalMatrixType  H2 = nullptr,
OptionalMatrixType  H3 = nullptr,
OptionalMatrixType  H4 = nullptr,
OptionalMatrixType  H5 = nullptr 
) const
inlineoverride

Evaluate error function.

Definition at line 265 of file TransferFactor.h.

◆ TransferError()

template<typename K >
Vector2 gtsam::EssentialTransferFactorK< K >::TransferError ( const Matrix3 &  Eca,
const K Ka,
const Point2 pa,
const Matrix3 &  Ecb,
const K Kb,
const Point2 pb,
const K Kc,
const Point2 pc 
) const
inline

Transfer points pa and pb to view c and evaluate error.

Definition at line 255 of file TransferFactor.h.

Member Data Documentation

◆ triplets_

template<typename K >
std::vector<Triplet> gtsam::EssentialTransferFactorK< K >::triplets_
private

Point triplets.

Definition at line 229 of file TransferFactor.h.


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


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