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

#include <TransformBtwRobotsUnaryFactorEM.h>

Inheritance diagram for gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< TransformBtwRobotsUnaryFactorEMshared_ptr
 
typedef VALUE T
 
- 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

Vector calcIndicatorProb (const Values &x) const
 
Vector calcIndicatorProb (const Values &x, const Vector &err) const
 
NonlinearFactor::shared_ptr clone () const override
 
size_t dim () const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const Values &x) const override
 
SharedGaussian get_model_inlier () const
 
Matrix get_model_inlier_cov () const
 
SharedGaussian get_model_outlier () const
 
Matrix get_model_outlier_cov () const
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
void print (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
void setValAValB (const Values &valA, const Values &valB)
 
 TransformBtwRobotsUnaryFactorEM ()
 
 TransformBtwRobotsUnaryFactorEM (Key key, const VALUE &measured, Key keyA, Key keyB, const Values &valA, const Values &valB, const SharedGaussian &model_inlier, const SharedGaussian &model_outlier, const double prior_inlier, const double prior_outlier, const bool flag_bump_up_near_zero_probs=false, const bool start_with_M_step=false)
 
Vector unwhitenedError (const Values &x) const
 
void updateNoiseModels (const Values &values, const Marginals &marginals)
 
void updateNoiseModels (const Values &values, const NonlinearFactorGraph &graph)
 
void updateNoiseModels_givenCovs (const Values &values, const Matrix &cov1, const Matrix &cov2, const Matrix &cov12)
 
Vector whitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const
 
Vector whitenedError (const Values &x, std::vector< Matrix > &H) const
 
 ~TransformBtwRobotsUnaryFactorEM () 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 NonlinearFactor Base
 
typedef TransformBtwRobotsUnaryFactorEM< VALUE > This
 

Private Attributes

bool flag_bump_up_near_zero_probs_
 
Key key_
 
Key keyA_
 
Key keyB_
 
VALUE measured_
 
SharedGaussian model_inlier_
 
SharedGaussian model_outlier_
 
double prior_inlier_
 
double prior_outlier_
 
bool start_with_M_step_
 
Values valA_
 
Values valB_
 

Additional Inherited Members

- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- 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::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

template<class VALUE>
class gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >

A class for a measurement predicted by "between(config[key1],config[key2])"

Template Parameters
VALUEthe Value type

Definition at line 37 of file TransformBtwRobotsUnaryFactorEM.h.

Member Typedef Documentation

◆ Base

template<class VALUE>
typedef NonlinearFactor gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::Base
private

Definition at line 46 of file TransformBtwRobotsUnaryFactorEM.h.

◆ shared_ptr

template<class VALUE>
typedef std::shared_ptr<TransformBtwRobotsUnaryFactorEM> gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::shared_ptr

concept check by type

Definition at line 75 of file TransformBtwRobotsUnaryFactorEM.h.

◆ T

template<class VALUE>
typedef VALUE gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::T

Definition at line 41 of file TransformBtwRobotsUnaryFactorEM.h.

◆ This

template<class VALUE>
typedef TransformBtwRobotsUnaryFactorEM<VALUE> gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::This
private

Definition at line 45 of file TransformBtwRobotsUnaryFactorEM.h.

Constructor & Destructor Documentation

◆ TransformBtwRobotsUnaryFactorEM() [1/2]

template<class VALUE>
gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::TransformBtwRobotsUnaryFactorEM ( )
inline

default constructor - only use for serialization

Definition at line 78 of file TransformBtwRobotsUnaryFactorEM.h.

◆ TransformBtwRobotsUnaryFactorEM() [2/2]

template<class VALUE>
gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::TransformBtwRobotsUnaryFactorEM ( Key  key,
const VALUE &  measured,
Key  keyA,
Key  keyB,
const Values valA,
const Values valB,
const SharedGaussian model_inlier,
const SharedGaussian model_outlier,
const double  prior_inlier,
const double  prior_outlier,
const bool  flag_bump_up_near_zero_probs = false,
const bool  start_with_M_step = false 
)
inline

Constructor

Definition at line 81 of file TransformBtwRobotsUnaryFactorEM.h.

◆ ~TransformBtwRobotsUnaryFactorEM()

template<class VALUE>
gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::~TransformBtwRobotsUnaryFactorEM ( )
inlineoverride

Definition at line 96 of file TransformBtwRobotsUnaryFactorEM.h.

Member Function Documentation

◆ calcIndicatorProb() [1/2]

template<class VALUE>
Vector gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::calcIndicatorProb ( const Values x) const
inline

Definition at line 256 of file TransformBtwRobotsUnaryFactorEM.h.

◆ calcIndicatorProb() [2/2]

template<class VALUE>
Vector gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::calcIndicatorProb ( const Values x,
const Vector err 
) const
inline

Definition at line 264 of file TransformBtwRobotsUnaryFactorEM.h.

◆ clone()

template<class VALUE>
NonlinearFactor::shared_ptr gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::clone ( ) const
inlineoverridevirtual

Clone

Reimplemented from gtsam::NonlinearFactor.

Definition at line 100 of file TransformBtwRobotsUnaryFactorEM.h.

◆ dim()

template<class VALUE>
size_t gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::dim ( ) const
inlineoverridevirtual

get the dimension of the factor (number of rows on linearization)

Implements gtsam::NonlinearFactor.

Definition at line 411 of file TransformBtwRobotsUnaryFactorEM.h.

◆ equals()

template<class VALUE>
bool gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
inlineoverridevirtual

equals

Reimplemented from gtsam::NonlinearFactor.

Definition at line 122 of file TransformBtwRobotsUnaryFactorEM.h.

◆ error()

template<class VALUE>
double gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::error ( const Values x) const
inlineoverridevirtual

Reimplemented from gtsam::NonlinearFactor.

Definition at line 154 of file TransformBtwRobotsUnaryFactorEM.h.

◆ get_model_inlier()

template<class VALUE>
SharedGaussian gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::get_model_inlier ( ) const
inline

Definition at line 315 of file TransformBtwRobotsUnaryFactorEM.h.

◆ get_model_inlier_cov()

template<class VALUE>
Matrix gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::get_model_inlier_cov ( ) const
inline

Definition at line 325 of file TransformBtwRobotsUnaryFactorEM.h.

◆ get_model_outlier()

template<class VALUE>
SharedGaussian gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::get_model_outlier ( ) const
inline

Definition at line 320 of file TransformBtwRobotsUnaryFactorEM.h.

◆ get_model_outlier_cov()

template<class VALUE>
Matrix gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::get_model_outlier_cov ( ) const
inline

Definition at line 330 of file TransformBtwRobotsUnaryFactorEM.h.

◆ linearize()

template<class VALUE>
std::shared_ptr<GaussianFactor> gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::linearize ( const Values x) const
inlineoverridevirtual

Linearize a non-linearFactorN to get a GaussianFactor, $ Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z $ Hence $ b = z - h(x) = - \mathtt{error\_vector}(x) $

Implements gtsam::NonlinearFactor.

Definition at line 165 of file TransformBtwRobotsUnaryFactorEM.h.

◆ print()

template<class VALUE>
void gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::print ( const std::string &  s,
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlineoverridevirtual

implement functions needed for Testable print

Reimplemented from gtsam::NonlinearFactor.

Definition at line 106 of file TransformBtwRobotsUnaryFactorEM.h.

◆ setValAValB()

template<class VALUE>
void gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::setValAValB ( const Values valA,
const Values valB 
)
inline

implement functions needed to derive from Factor

Definition at line 137 of file TransformBtwRobotsUnaryFactorEM.h.

◆ unwhitenedError()

template<class VALUE>
Vector gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::unwhitenedError ( const Values x) const
inline

Definition at line 298 of file TransformBtwRobotsUnaryFactorEM.h.

◆ updateNoiseModels() [1/2]

template<class VALUE>
void gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::updateNoiseModels ( const Values values,
const Marginals marginals 
)
inline

Definition at line 335 of file TransformBtwRobotsUnaryFactorEM.h.

◆ updateNoiseModels() [2/2]

template<class VALUE>
void gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::updateNoiseModels ( const Values values,
const NonlinearFactorGraph graph 
)
inline

Definition at line 350 of file TransformBtwRobotsUnaryFactorEM.h.

◆ updateNoiseModels_givenCovs()

template<class VALUE>
void gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::updateNoiseModels_givenCovs ( const Values values,
const Matrix cov1,
const Matrix cov2,
const Matrix cov12 
)
inline

Definition at line 368 of file TransformBtwRobotsUnaryFactorEM.h.

◆ whitenedError() [1/2]

template<class VALUE>
Vector gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::whitenedError ( const Values x,
OptionalMatrixVecType  H = nullptr 
) const
inline

A function overload to accept a vector<matrix> instead of a pointer to the said type.

Definition at line 185 of file TransformBtwRobotsUnaryFactorEM.h.

◆ whitenedError() [2/2]

template<class VALUE>
Vector gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::whitenedError ( const Values x,
std::vector< Matrix > &  H 
) const
inline

Definition at line 251 of file TransformBtwRobotsUnaryFactorEM.h.

Member Data Documentation

◆ flag_bump_up_near_zero_probs_

template<class VALUE>
bool gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::flag_bump_up_near_zero_probs_
private

Definition at line 65 of file TransformBtwRobotsUnaryFactorEM.h.

◆ key_

template<class VALUE>
Key gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::key_
private

Definition at line 48 of file TransformBtwRobotsUnaryFactorEM.h.

◆ keyA_

template<class VALUE>
Key gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::keyA_
private

Definition at line 54 of file TransformBtwRobotsUnaryFactorEM.h.

◆ keyB_

template<class VALUE>
Key gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::keyB_
private

Definition at line 55 of file TransformBtwRobotsUnaryFactorEM.h.

◆ measured_

template<class VALUE>
VALUE gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::measured_
private

Definition at line 50 of file TransformBtwRobotsUnaryFactorEM.h.

◆ model_inlier_

template<class VALUE>
SharedGaussian gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::model_inlier_
private

Definition at line 59 of file TransformBtwRobotsUnaryFactorEM.h.

◆ model_outlier_

template<class VALUE>
SharedGaussian gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::model_outlier_
private

Definition at line 60 of file TransformBtwRobotsUnaryFactorEM.h.

◆ prior_inlier_

template<class VALUE>
double gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::prior_inlier_
private

Definition at line 62 of file TransformBtwRobotsUnaryFactorEM.h.

◆ prior_outlier_

template<class VALUE>
double gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::prior_outlier_
private

Definition at line 63 of file TransformBtwRobotsUnaryFactorEM.h.

◆ start_with_M_step_

template<class VALUE>
bool gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::start_with_M_step_
mutableprivate

Definition at line 66 of file TransformBtwRobotsUnaryFactorEM.h.

◆ valA_

template<class VALUE>
Values gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::valA_
private

The measurement

Definition at line 52 of file TransformBtwRobotsUnaryFactorEM.h.

◆ valB_

template<class VALUE>
Values gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >::valB_
private

Definition at line 53 of file TransformBtwRobotsUnaryFactorEM.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:13