Class for Hybrid Bayes tree orphan subtrees. More...
#include <HybridBayesTree.h>
Public Types | |
typedef HybridConditional | Base |
typedef HybridBayesTreeClique | CliqueType |
Public Types inherited from gtsam::HybridConditional | |
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... | |
enum | Category { Category::None, Category::Discrete, Category::Continuous, Category::Hybrid } |
Enum to help with categorizing hybrid factors. 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 | |
BayesTreeOrphanWrapper (const std::shared_ptr< CliqueType > &clique) | |
Construct a new Bayes Tree Orphan Wrapper object. More... | |
void | print (const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print utility More... | |
Public Member Functions inherited from gtsam::HybridConditional | |
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< HybridGaussianConditional > &hybridGaussianCond) | |
Construct a new Hybrid Conditional object. More... | |
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... | |
HybridGaussianConditional::shared_ptr | asHybrid () const |
Return HybridConditional as a HybridGaussianConditional. 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... | |
AlgebraicDecisionTree< Key > | errorTree (const VectorValues &values) const override |
Compute error of the HybridConditional as a tree. More... | |
double | logProbability (const HybridValues &values) const override |
Return the log-probability (or density) of the underlying conditional. More... | |
double | negLogConstant () 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\n", 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... | |
virtual double | negLogConstant () const |
All conditional types need to implement this as the negative log of the normalization constant to make it such that error>=0. More... | |
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 () |
Public Attributes | |
std::shared_ptr< CliqueType > | clique |
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) |
Protected Attributes inherited from gtsam::HybridConditional | |
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_ |
Class for Hybrid Bayes tree orphan subtrees.
This object stores parent keys in our base type factor so that eliminating those parent keys will pull this subtree into the elimination.
This is a template instantiation for hybrid Bayes tree cliques, storing both the regular keys and discrete keys in the HybridConditional.
Definition at line 147 of file HybridBayesTree.h.
Definition at line 150 of file HybridBayesTree.h.
Definition at line 149 of file HybridBayesTree.h.
|
inline |
Construct a new Bayes Tree Orphan Wrapper object.
clique | Bayes tree clique. |
Definition at line 159 of file HybridBayesTree.h.
|
inlineoverridevirtual |
std::shared_ptr<CliqueType> gtsam::BayesTreeOrphanWrapper< HybridBayesTreeClique >::clique |
Definition at line 152 of file HybridBayesTree.h.