#include <HybridBayesNet.h>
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< HybridConditional > | sharedConditional |
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< HybridConditional > | sharedFactor |
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< Key > | logProbability (const VectorValues &continuousValues) const |
Compute conditional error for each discrete assignment, and return as a tree. More... | |
AlgebraicDecisionTree< Key > | 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. 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 |
sharedFactor & | at (size_t i) |
const sharedFactor | operator[] (size_t i) const |
sharedFactor & | operator[] (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< sharedFactor > | factors_ |
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.
Definition at line 37 of file HybridBayesNet.h.
Definition at line 39 of file HybridBayesNet.h.
using gtsam::HybridBayesNet::shared_ptr = std::shared_ptr<HybridBayesNet> |
Definition at line 40 of file HybridBayesNet.h.
using gtsam::HybridBayesNet::sharedConditional = std::shared_ptr<ConditionalType> |
Definition at line 41 of file HybridBayesNet.h.
Definition at line 38 of file HybridBayesNet.h.
|
default |
Construct empty Bayes net
GaussianBayesNet gtsam::HybridBayesNet::choose | ( | const DiscreteValues & | assignment | ) | const |
Get the Gaussian Bayes Net which corresponds to a specific discrete value assignment.
assignment | The discrete value assignment for the discrete keys. |
Definition at line 213 of file HybridBayesNet.cpp.
DecisionTreeFactor::shared_ptr gtsam::HybridBayesNet::discreteConditionals | ( | ) | const |
Get all the discrete conditionals as a decision tree factor.
Definition at line 41 of file HybridBayesNet.cpp.
|
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.
bool gtsam::HybridBayesNet::equals | ( | const This & | fg, |
double | tol = 1e-9 |
||
) | const |
GTSAM-style equals.
Definition at line 36 of file HybridBayesNet.cpp.
double gtsam::HybridBayesNet::evaluate | ( | const HybridValues & | values | ) | const |
Evaluate hybrid probability density for given HybridValues.
Definition at line 336 of file HybridBayesNet.cpp.
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.
continuousValues | Continuous values at which to compute the probability. |
Definition at line 329 of file HybridBayesNet.cpp.
AlgebraicDecisionTree< Key > gtsam::HybridBayesNet::logProbability | ( | const VectorValues & | continuousValues | ) | const |
Compute conditional error for each discrete assignment, and return as a tree.
continuousValues | Continuous values at which to compute the error. |
Definition at line 297 of file HybridBayesNet.cpp.
|
inline |
Evaluate hybrid probability density for given HybridValues, sugar.
Definition at line 117 of file HybridBayesNet.h.
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.
Definition at line 233 of file HybridBayesNet.cpp.
VectorValues gtsam::HybridBayesNet::optimize | ( | const DiscreteValues & | assignment | ) | const |
Given the discrete assignment, return the optimized estimate for the selected Gaussian BayesNet.
assignment | An assignment of discrete values. |
Definition at line 250 of file HybridBayesNet.cpp.
|
overridevirtual |
GTSAM-style printing.
Reimplemented from gtsam::FactorGraph< HybridConditional >.
Definition at line 30 of file HybridBayesNet.cpp.
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.
|
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.
|
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.
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);
given | Values of missing variables. |
rng | The pseudo-random number generator. |
Definition at line 262 of file HybridBayesNet.cpp.
HybridValues gtsam::HybridBayesNet::sample | ( | std::mt19937_64 * | rng | ) | const |
Sample using ancestral sampling.
Example: std::mt19937_64 rng(42); auto sample = bn.sample(&rng);
rng | The pseudo-random number generator. |
Definition at line 281 of file HybridBayesNet.cpp.
HybridValues gtsam::HybridBayesNet::sample | ( | const HybridValues & | given | ) | const |
Sample from an incomplete BayesNet, use default rng.
given | Values of missing variables. |
Definition at line 287 of file HybridBayesNet.cpp.
HybridValues gtsam::HybridBayesNet::sample | ( | ) | const |
Sample using ancestral sampling, use default rng.
Definition at line 292 of file HybridBayesNet.cpp.
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.
|
private |
Update the discrete conditionals with the pruned versions.
prunedDecisionTree |
Definition at line 146 of file HybridBayesNet.cpp.