#include <HybridConditional.h>
Public Types | |
typedef Conditional< BaseFactor, This > | BaseConditional |
Typedef to our conditional base class. More... | |
typedef HybridFactor | BaseFactor |
Typedef to our factor base class. More... | |
typedef std::shared_ptr< This > | shared_ptr |
shared_ptr to this class More... | |
typedef HybridConditional | This |
Typedef to this class. More... | |
Public Types inherited from gtsam::HybridFactor | |
typedef Factor | Base |
Our base class. More... | |
typedef std::shared_ptr< HybridFactor > | shared_ptr |
shared_ptr to this class More... | |
typedef HybridFactor | This |
This class. More... | |
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 Types inherited from gtsam::Conditional< HybridFactor, HybridConditional > | |
typedef std::pair< typename HybridFactor ::const_iterator, typename HybridFactor ::const_iterator > | ConstFactorRange |
typedef ConstFactorRangeIterator | Frontals |
typedef ConstFactorRangeIterator | Parents |
Public Member Functions | |
Standard Constructors | |
HybridConditional ()=default | |
Default constructor needed for serialization. More... | |
HybridConditional (const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, size_t nFrontals) | |
Construct a new Hybrid Conditional object. More... | |
HybridConditional (const KeyVector &continuousFrontals, const DiscreteKeys &discreteFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents) | |
Construct a new Hybrid Conditional object. More... | |
HybridConditional (const std::shared_ptr< GaussianConditional > &continuousConditional) | |
Construct a new Hybrid Conditional object. More... | |
HybridConditional (const std::shared_ptr< DiscreteConditional > &discreteConditional) | |
Construct a new Hybrid Conditional object. More... | |
HybridConditional (const std::shared_ptr< GaussianMixture > &gaussianMixture) | |
Construct a new Hybrid Conditional object. More... | |
Testable | |
void | print (const std::string &s="Hybrid Conditional: ", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
GTSAM-style print. More... | |
bool | equals (const HybridFactor &other, double tol=1e-9) const override |
GTSAM-style equals. More... | |
Standard Interface | |
GaussianMixture::shared_ptr | asMixture () const |
Return HybridConditional as a GaussianMixture. More... | |
GaussianConditional::shared_ptr | asGaussian () const |
Return HybridConditional as a GaussianConditional. More... | |
DiscreteConditional::shared_ptr | asDiscrete () const |
Return conditional as a DiscreteConditional. More... | |
std::shared_ptr< Factor > | inner () const |
Get the type-erased pointer to the inner type. More... | |
double | error (const HybridValues &values) const override |
Return the error of the underlying conditional. More... | |
double | logProbability (const HybridValues &values) const override |
Return the log-probability (or density) of the underlying conditional. More... | |
double | logNormalizationConstant () const override |
double | evaluate (const HybridValues &values) const override |
Return the probability (or density) of the underlying conditional. More... | |
bool | frontalsIn (const VectorValues &measurements) const |
Check if VectorValues measurements contains all frontal keys. More... | |
Public Member Functions inherited from gtsam::HybridFactor | |
HybridFactor ()=default | |
HybridFactor (const KeyVector &keys) | |
Construct hybrid factor from continuous keys. More... | |
HybridFactor (const DiscreteKeys &discreteKeys) | |
Construct hybrid factor from discrete keys. More... | |
HybridFactor (const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys) | |
Construct a new Hybrid Factor object. More... | |
void | print (const std::string &s="HybridFactor\, const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print More... | |
bool | isDiscrete () const |
True if this is a factor of discrete variables only. More... | |
bool | isContinuous () const |
True if this is a factor of continuous variables only. More... | |
bool | isHybrid () const |
True is this is a Discrete-Continuous factor. More... | |
size_t | nrContinuous () const |
Return the number of continuous variables in this factor. More... | |
const DiscreteKeys & | discreteKeys () const |
Return the discrete keys for this factor. More... | |
const KeyVector & | continuousKeys () const |
Return only the continuous keys for this factor. More... | |
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 KeyVector & | keys () 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... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Public Member Functions inherited from gtsam::Conditional< HybridFactor, HybridConditional > | |
void | print (const std::string &s="Conditional", const KeyFormatter &formatter=DefaultKeyFormatter) const |
bool | equals (const This &c, double tol=1e-9) const |
virtual | ~Conditional () |
size_t | nrFrontals () const |
size_t | nrParents () const |
Key | firstFrontalKey () const |
Frontals | frontals () const |
Parents | parents () const |
double | operator() (const HybridValues &x) const |
Evaluate probability density, sugar. More... | |
double | normalizationConstant () const |
size_t & | nrFrontals () |
HybridFactor ::const_iterator | beginFrontals () const |
HybridFactor ::iterator | beginFrontals () |
HybridFactor ::const_iterator | endFrontals () const |
HybridFactor ::iterator | endFrontals () |
HybridFactor ::const_iterator | beginParents () const |
HybridFactor ::iterator | beginParents () |
HybridFactor ::const_iterator | endParents () const |
HybridFactor ::iterator | endParents () |
Protected Attributes | |
std::shared_ptr< Factor > | inner_ |
Type-erased pointer to the inner type. More... | |
Protected Attributes inherited from gtsam::HybridFactor | |
KeyVector | continuousKeys_ |
Record continuous keys for book-keeping. More... | |
DiscreteKeys | discreteKeys_ |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Protected Attributes inherited from gtsam::Conditional< HybridFactor, HybridConditional > | |
size_t | nrFrontals_ |
Additional Inherited Members | |
Static Public Member Functions inherited from gtsam::Conditional< HybridFactor, HybridConditional > | |
static bool | CheckInvariants (const HybridConditional &conditional, const VALUES &x) |
Protected Member Functions inherited from gtsam::Factor | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
Protected Member Functions inherited from gtsam::Conditional< HybridFactor, HybridConditional > | |
Conditional () | |
Conditional (size_t nrFrontals) | |
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) |
Hybrid Conditional Density
As a type-erased variant of:
The reason why this is important is that Conditional<T>
is a CRTP class. CRTP is static polymorphism such that all CRTP classes, while bearing the same name, are different classes not sharing a vtable. This prevents them from being contained in any container, and thus it is impossible to dynamically cast between them. A better option, as illustrated here, is treating them as an implementation detail - such that the hybrid mechanism does not know what is inside the HybridConditional. This prevents us from having diamond inheritances, and neutralized the need to change other components of GTSAM to make hybrid elimination work.
A great reference to the type-erasure pattern is Eduardo Madrid's CppCon talk (https://www.youtube.com/watch?v=s082Qmd_nHs).
Definition at line 59 of file HybridConditional.h.
Typedef to our conditional base class.
Definition at line 68 of file HybridConditional.h.
Typedef to our factor base class.
Definition at line 66 of file HybridConditional.h.
typedef std::shared_ptr<This> gtsam::HybridConditional::shared_ptr |
shared_ptr to this class
Definition at line 65 of file HybridConditional.h.
Typedef to this class.
Definition at line 64 of file HybridConditional.h.
|
default |
Default constructor needed for serialization.
|
inline |
Construct a new Hybrid Conditional object.
continuousKeys | Vector of keys for continuous variables. |
discreteKeys | Keys and cardinalities for discrete variables. |
nFrontals | The number of frontal variables in the conditional. |
Definition at line 88 of file HybridConditional.h.
gtsam::HybridConditional::HybridConditional | ( | const KeyVector & | continuousFrontals, |
const DiscreteKeys & | discreteFrontals, | ||
const KeyVector & | continuousParents, | ||
const DiscreteKeys & | discreteParents | ||
) |
Construct a new Hybrid Conditional object.
continuousFrontals | Vector of keys for continuous variables. |
discreteFrontals | Keys and cardinalities for discrete variables. |
continuousParents | Vector of keys for parent continuous variables. |
discreteParents | Keys and cardinalities for parent discrete variables. |
Definition at line 27 of file HybridConditional.cpp.
gtsam::HybridConditional::HybridConditional | ( | const std::shared_ptr< GaussianConditional > & | continuousConditional | ) |
Construct a new Hybrid Conditional object.
continuousConditional | Conditional used to create the HybridConditional. |
Definition at line 41 of file HybridConditional.cpp.
gtsam::HybridConditional::HybridConditional | ( | const std::shared_ptr< DiscreteConditional > & | discreteConditional | ) |
Construct a new Hybrid Conditional object.
discreteConditional | Conditional used to create the HybridConditional. |
Definition at line 49 of file HybridConditional.cpp.
gtsam::HybridConditional::HybridConditional | ( | const std::shared_ptr< GaussianMixture > & | gaussianMixture | ) |
Construct a new Hybrid Conditional object.
gaussianMixture | Gaussian Mixture Conditional used to create the HybridConditional. |
Definition at line 57 of file HybridConditional.cpp.
|
inline |
Return conditional as a DiscreteConditional.
Definition at line 171 of file HybridConditional.h.
|
inline |
Return HybridConditional as a GaussianConditional.
Definition at line 162 of file HybridConditional.h.
|
inline |
Return HybridConditional as a GaussianMixture.
Definition at line 153 of file HybridConditional.h.
|
overridevirtual |
GTSAM-style equals.
Reimplemented from gtsam::HybridFactor.
Definition at line 104 of file HybridConditional.cpp.
|
overridevirtual |
Return the error of the underlying conditional.
Reimplemented from gtsam::Factor.
Definition at line 125 of file HybridConditional.cpp.
|
overridevirtual |
Return the probability (or density) of the underlying conditional.
Reimplemented from gtsam::Conditional< HybridFactor, HybridConditional >.
Definition at line 170 of file HybridConditional.cpp.
|
inline |
Check if VectorValues measurements
contains all frontal keys.
Definition at line 195 of file HybridConditional.h.
|
inline |
Get the type-erased pointer to the inner type.
Definition at line 176 of file HybridConditional.h.
|
overridevirtual |
Return the log normalization constant. Note this is 0.0 for discrete and hybrid conditionals, but depends on the continuous parameters for Gaussian conditionals.
Reimplemented from gtsam::Conditional< HybridFactor, HybridConditional >.
Definition at line 155 of file HybridConditional.cpp.
|
overridevirtual |
Return the log-probability (or density) of the underlying conditional.
Reimplemented from gtsam::Conditional< HybridFactor, HybridConditional >.
Definition at line 140 of file HybridConditional.cpp.
|
overridevirtual |
GTSAM-style print.
Reimplemented from gtsam::Factor.
Definition at line 68 of file HybridConditional.cpp.
|
protected |
Type-erased pointer to the inner type.
Definition at line 72 of file HybridConditional.h.