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

#include <HybridBayesNet.h>

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

Public Types

using Base = BayesNet< HybridConditional >
 
using ConditionalType = HybridConditional
 
using shared_ptr = std::shared_ptr< HybridBayesNet >
 
using sharedConditional = std::shared_ptr< ConditionalType >
 
using This = HybridBayesNet
 
- Public Types inherited from gtsam::BayesNet< HybridConditional >
typedef std::shared_ptr< HybridConditionalsharedConditional
 A shared pointer to a conditional. More...
 
- Public Types inherited from gtsam::FactorGraph< HybridConditional >
typedef FastVector< sharedFactor >::const_iterator const_iterator
 
typedef HybridConditional FactorType
 factor type More...
 
typedef FastVector< sharedFactor >::iterator iterator
 
typedef std::shared_ptr< HybridConditionalsharedFactor
 Shared pointer to a factor. More...
 
typedef sharedFactor value_type
 

Public Member Functions

Standard Constructors
 HybridBayesNet ()=default
 
Testable
void print (const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 GTSAM-style printing. More...
 
bool equals (const This &fg, double tol=1e-9) const
 GTSAM-style equals. More...
 
Standard Interface
void push_back (std::shared_ptr< HybridConditional > conditional)
 Add a hybrid conditional using a shared_ptr. More...
 
template<class Conditional >
void emplace_back (Conditional *conditional)
 
void push_back (HybridConditional &&conditional)
 
GaussianBayesNet choose (const DiscreteValues &assignment) const
 Get the Gaussian Bayes Net which corresponds to a specific discrete value assignment. More...
 
double evaluate (const HybridValues &values) const
 Evaluate hybrid probability density for given HybridValues. More...
 
double operator() (const HybridValues &values) const
 Evaluate hybrid probability density for given HybridValues, sugar. More...
 
HybridValues optimize () const
 Solve the HybridBayesNet by first computing the MPE of all the discrete variables and then optimizing the continuous variables based on the MPE assignment. More...
 
VectorValues optimize (const DiscreteValues &assignment) const
 Given the discrete assignment, return the optimized estimate for the selected Gaussian BayesNet. More...
 
DecisionTreeFactor::shared_ptr discreteConditionals () const
 Get all the discrete conditionals as a decision tree factor. More...
 
HybridValues sample (const HybridValues &given, std::mt19937_64 *rng) const
 Sample from an incomplete BayesNet, given missing variables. More...
 
HybridValues sample (std::mt19937_64 *rng) const
 Sample using ancestral sampling. More...
 
HybridValues sample (const HybridValues &given) const
 Sample from an incomplete BayesNet, use default rng. More...
 
HybridValues sample () const
 Sample using ancestral sampling, use default rng. More...
 
HybridBayesNet prune (size_t maxNrLeaves)
 Prune the Hybrid Bayes Net such that we have at most maxNrLeaves leaves. More...
 
AlgebraicDecisionTree< KeylogProbability (const VectorValues &continuousValues) const
 Compute conditional error for each discrete assignment, and return as a tree. More...
 
AlgebraicDecisionTree< Keyevaluate (const VectorValues &continuousValues) const
 Compute unnormalized probability q(μ|M), for each discrete assignment, and return as a tree. q(μ|M) is the unnormalized probability at the MLE point μ, conditioned on the discrete variables. More...
 
HybridGaussianFactorGraph toFactorGraph (const VectorValues &measurements) const
 
- Public Member Functions inherited from gtsam::BayesNet< HybridConditional >
void print (const std::string &s="BayesNet", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 
void dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 Output to graphviz format, stream version. More...
 
std::string dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 Output to graphviz format string. More...
 
void saveGraph (const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 output to file with graphviz format. More...
 
double logProbability (const HybridValues &x) const
 
double evaluate (const HybridValues &c) const
 
- Public Member Functions inherited from gtsam::FactorGraph< HybridConditional >
 FactorGraph (std::initializer_list< std::shared_ptr< DERIVEDFACTOR >> sharedFactors)
 
virtual ~FactorGraph ()=default
 
void reserve (size_t size)
 
IsDerived< DERIVEDFACTOR > push_back (std::shared_ptr< DERIVEDFACTOR > factor)
 Add a factor directly using a shared_ptr. More...
 
IsDerived< DERIVEDFACTOR > push_back (const DERIVEDFACTOR &factor)
 
IsDerived< DERIVEDFACTOR > emplace_shared (Args &&... args)
 Emplace a shared pointer to factor of given type. More...
 
IsDerived< DERIVEDFACTOR > add (std::shared_ptr< DERIVEDFACTOR > factor)
 add is a synonym for push_back. More...
 
HasDerivedElementType< ITERATOR > push_back (ITERATOR firstFactor, ITERATOR lastFactor)
 
HasDerivedValueType< ITERATOR > push_back (ITERATOR firstFactor, ITERATOR lastFactor)
 Push back many factors with an iterator (factors are copied) More...
 
HasDerivedElementType< CONTAINER > push_back (const CONTAINER &container)
 
HasDerivedValueType< CONTAINER > push_back (const CONTAINER &container)
 Push back non-pointer objects in a container (factors are copied). More...
 
void add (const FACTOR_OR_CONTAINER &factorOrContainer)
 
std::enable_if< std::is_base_of< This, typename CLIQUE::FactorGraphType >::value >::type push_back (const BayesTree< CLIQUE > &bayesTree)
 
FactorIndices add_factors (const CONTAINER &factors, bool useEmptySlots=false)
 
bool equals (const This &fg, double tol=1e-9) const
 Check equality up to tolerance. More...
 
size_t size () const
 
bool empty () const
 
const sharedFactor at (size_t i) const
 
sharedFactorat (size_t i)
 
const sharedFactor operator[] (size_t i) const
 
sharedFactoroperator[] (size_t i)
 
const_iterator begin () const
 
const_iterator end () const
 
sharedFactor front () const
 
sharedFactor back () const
 
double error (const HybridValues &values) const
 
iterator begin ()
 
iterator end ()
 
virtual void resize (size_t size)
 
void remove (size_t i)
 
void replace (size_t index, sharedFactor factor)
 
iterator erase (iterator item)
 
iterator erase (iterator first, iterator last)
 
void dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 Output to graphviz format, stream version. More...
 
std::string dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 Output to graphviz format string. More...
 
void saveGraph (const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 output to file with graphviz format. More...
 
size_t nrFactors () const
 
KeySet keys () const
 
KeyVector keyVector () const
 
bool exists (size_t idx) const
 

Private Member Functions

void updateDiscreteConditionals (const DecisionTreeFactor &prunedDecisionTree)
 Update the discrete conditionals with the pruned versions. More...
 

Additional Inherited Members

- Protected Member Functions inherited from gtsam::BayesNet< HybridConditional >
 BayesNet ()
 
 BayesNet (ITERATOR firstConditional, ITERATOR lastConditional)
 
 BayesNet (std::initializer_list< sharedConditional > conditionals)
 
- Protected Member Functions inherited from gtsam::FactorGraph< HybridConditional >
bool isEqual (const FactorGraph &other) const
 Check exact equality of the factor pointers. Useful for derived ==. More...
 
 FactorGraph ()
 
 FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor)
 
 FactorGraph (const CONTAINER &factors)
 
- Protected Attributes inherited from gtsam::FactorGraph< HybridConditional >
FastVector< sharedFactorfactors_
 

Detailed Description

A hybrid Bayes net is a collection of HybridConditionals, which can have discrete conditionals, Gaussian mixtures, or pure Gaussian conditionals.

Definition at line 35 of file HybridBayesNet.h.

Member Typedef Documentation

◆ Base

Definition at line 37 of file HybridBayesNet.h.

◆ ConditionalType

Definition at line 39 of file HybridBayesNet.h.

◆ shared_ptr

Definition at line 40 of file HybridBayesNet.h.

◆ sharedConditional

Definition at line 41 of file HybridBayesNet.h.

◆ This

Definition at line 38 of file HybridBayesNet.h.

Constructor & Destructor Documentation

◆ HybridBayesNet()

gtsam::HybridBayesNet::HybridBayesNet ( )
default

Construct empty Bayes net

Member Function Documentation

◆ choose()

GaussianBayesNet gtsam::HybridBayesNet::choose ( const DiscreteValues assignment) const

Get the Gaussian Bayes Net which corresponds to a specific discrete value assignment.

Parameters
assignmentThe discrete value assignment for the discrete keys.
Returns
GaussianBayesNet

Definition at line 213 of file HybridBayesNet.cpp.

◆ discreteConditionals()

DecisionTreeFactor::shared_ptr gtsam::HybridBayesNet::discreteConditionals ( ) const

Get all the discrete conditionals as a decision tree factor.

Returns
DecisionTreeFactor::shared_ptr

Definition at line 41 of file HybridBayesNet.cpp.

◆ emplace_back()

template<class Conditional >
void gtsam::HybridBayesNet::emplace_back ( Conditional conditional)
inline

Preferred: add a conditional directly using a pointer.

Examples: hbn.emplace_back(new GaussianMixture(...))); hbn.emplace_back(new GaussianConditional(...))); hbn.emplace_back(new DiscreteConditional(...)));

Definition at line 82 of file HybridBayesNet.h.

◆ equals()

bool gtsam::HybridBayesNet::equals ( const This fg,
double  tol = 1e-9 
) const

GTSAM-style equals.

Definition at line 36 of file HybridBayesNet.cpp.

◆ evaluate() [1/2]

double gtsam::HybridBayesNet::evaluate ( const HybridValues values) const

Evaluate hybrid probability density for given HybridValues.

Definition at line 336 of file HybridBayesNet.cpp.

◆ evaluate() [2/2]

AlgebraicDecisionTree< Key > gtsam::HybridBayesNet::evaluate ( const VectorValues continuousValues) const

Compute unnormalized probability q(μ|M), for each discrete assignment, and return as a tree. q(μ|M) is the unnormalized probability at the MLE point μ, conditioned on the discrete variables.

Parameters
continuousValuesContinuous values at which to compute the probability.
Returns
AlgebraicDecisionTree<Key>

Definition at line 329 of file HybridBayesNet.cpp.

◆ logProbability()

AlgebraicDecisionTree< Key > gtsam::HybridBayesNet::logProbability ( const VectorValues continuousValues) const

Compute conditional error for each discrete assignment, and return as a tree.

Parameters
continuousValuesContinuous values at which to compute the error.
Returns
AlgebraicDecisionTree<Key>

Definition at line 297 of file HybridBayesNet.cpp.

◆ operator()()

double gtsam::HybridBayesNet::operator() ( const HybridValues values) const
inline

Evaluate hybrid probability density for given HybridValues, sugar.

Definition at line 117 of file HybridBayesNet.h.

◆ optimize() [1/2]

HybridValues gtsam::HybridBayesNet::optimize ( ) const

Solve the HybridBayesNet by first computing the MPE of all the discrete variables and then optimizing the continuous variables based on the MPE assignment.

Returns
HybridValues

Definition at line 233 of file HybridBayesNet.cpp.

◆ optimize() [2/2]

VectorValues gtsam::HybridBayesNet::optimize ( const DiscreteValues assignment) const

Given the discrete assignment, return the optimized estimate for the selected Gaussian BayesNet.

Parameters
assignmentAn assignment of discrete values.
Returns
Values

Definition at line 250 of file HybridBayesNet.cpp.

◆ print()

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

GTSAM-style printing.

Reimplemented from gtsam::FactorGraph< HybridConditional >.

Definition at line 30 of file HybridBayesNet.cpp.

◆ prune()

HybridBayesNet gtsam::HybridBayesNet::prune ( size_t  maxNrLeaves)

Prune the Hybrid Bayes Net such that we have at most maxNrLeaves leaves.

Definition at line 176 of file HybridBayesNet.cpp.

◆ push_back() [1/2]

void gtsam::HybridBayesNet::push_back ( std::shared_ptr< HybridConditional conditional)
inline

Add a hybrid conditional using a shared_ptr.

This is the "native" push back, as this class stores hybrid conditionals.

Definition at line 69 of file HybridBayesNet.h.

◆ push_back() [2/2]

void gtsam::HybridBayesNet::push_back ( HybridConditional &&  conditional)
inline

Add a conditional using a shared_ptr, using implicit conversion to a HybridConditional.

This is useful when you create a conditional shared pointer as you need it somewhere else.

Example: auto shared_ptr_to_a_conditional = std::make_shared<GaussianMixture>(...); hbn.push_back(shared_ptr_to_a_conditional);

Definition at line 99 of file HybridBayesNet.h.

◆ sample() [1/4]

HybridValues gtsam::HybridBayesNet::sample ( const HybridValues given,
std::mt19937_64 *  rng 
) const

Sample from an incomplete BayesNet, given missing variables.

Example: std::mt19937_64 rng(42); VectorValues given = ...; auto sample = bn.sample(given, &rng);

Parameters
givenValues of missing variables.
rngThe pseudo-random number generator.
Returns
HybridValues

Definition at line 262 of file HybridBayesNet.cpp.

◆ sample() [2/4]

HybridValues gtsam::HybridBayesNet::sample ( std::mt19937_64 *  rng) const

Sample using ancestral sampling.

Example: std::mt19937_64 rng(42); auto sample = bn.sample(&rng);

Parameters
rngThe pseudo-random number generator.
Returns
HybridValues

Definition at line 281 of file HybridBayesNet.cpp.

◆ sample() [3/4]

HybridValues gtsam::HybridBayesNet::sample ( const HybridValues given) const

Sample from an incomplete BayesNet, use default rng.

Parameters
givenValues of missing variables.
Returns
HybridValues

Definition at line 287 of file HybridBayesNet.cpp.

◆ sample() [4/4]

HybridValues gtsam::HybridBayesNet::sample ( ) const

Sample using ancestral sampling, use default rng.

Returns
HybridValues

Definition at line 292 of file HybridBayesNet.cpp.

◆ toFactorGraph()

HybridGaussianFactorGraph gtsam::HybridBayesNet::toFactorGraph ( const VectorValues measurements) const

Convert a hybrid Bayes net to a hybrid Gaussian factor graph by converting all conditionals with instantiated measurements into likelihood factors.

Definition at line 341 of file HybridBayesNet.cpp.

◆ updateDiscreteConditionals()

void gtsam::HybridBayesNet::updateDiscreteConditionals ( const DecisionTreeFactor prunedDecisionTree)
private

Update the discrete conditionals with the pruned versions.

Parameters
prunedDecisionTree

Definition at line 146 of file HybridBayesNet.cpp.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:20