#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 | |
Construct empty Bayes net. More... | |
HybridBayesNet (std::initializer_list< HybridConditional::shared_ptr > conditionals) | |
Constructor that takes an initializer list of shared pointers. More... | |
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... | |
void | push_back (HybridConditional &&conditional) |
template<class CONDITIONAL > | |
void | push_back (const std::shared_ptr< CONDITIONAL > &conditional) |
Add a conditional to the Bayes net. Implicitly convert to a HybridConditional. More... | |
template<class CONDITIONAL , class... Args> | |
void | emplace_shared (Args &&...args) |
DiscreteBayesNet | discreteMarginal () const |
Get the discrete Bayes Net P(M). As the hybrid Bayes net defines P(X,M) = P(X|M) P(M), this method returns the marginal distribution on the discrete variables. More... | |
GaussianBayesNet | choose (const DiscreteValues &assignment) const |
Get the Gaussian Bayes net P(X|M=m) corresponding to a specific assignment m for the discrete variables M. As the hybrid Bayes net defines P(X,M) = P(X|M) P(M), this method returns the posterior p(X|M=m). 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... | |
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) const |
Prune the Bayes Net such that we have at most maxNrLeaves leaves. More... | |
AlgebraicDecisionTree< Key > | errorTree (const VectorValues &continuousValues) const |
Compute the negative log posterior log P'(M|x) of all assignments up to a constant, returning the result as an algebraic decision tree. More... | |
AlgebraicDecisionTree< Key > | discretePosterior (const VectorValues &continuousValues) const |
Compute normalized posterior P(M|X=x) and return as a tree. More... | |
HybridGaussianFactorGraph | toFactorGraph (const VectorValues &measurements) const |
double | logProbability (const HybridValues &x) 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... | |
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, This >::type & | operator+= (std::shared_ptr< DERIVEDFACTOR > factor) |
Append factor to factor graph. More... | |
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, This >::type & | operator, (std::shared_ptr< DERIVEDFACTOR > factor) |
Overload comma operator to allow for append chaining. 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) |
This & | operator+= (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) |
std::shared_ptr< F > | at (size_t i) |
const std::shared_ptr< F > | at (size_t i) const |
Const version of templated at method. More... | |
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 |
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, hybrid Gaussian conditionals, or pure Gaussian conditionals.
Definition at line 37 of file HybridBayesNet.h.
Definition at line 39 of file HybridBayesNet.h.
Definition at line 41 of file HybridBayesNet.h.
using gtsam::HybridBayesNet::shared_ptr = std::shared_ptr<HybridBayesNet> |
Definition at line 42 of file HybridBayesNet.h.
using gtsam::HybridBayesNet::sharedConditional = std::shared_ptr<ConditionalType> |
Definition at line 43 of file HybridBayesNet.h.
Definition at line 40 of file HybridBayesNet.h.
|
default |
Construct empty Bayes net.
|
inline |
Constructor that takes an initializer list of shared pointers.
Definition at line 52 of file HybridBayesNet.h.
GaussianBayesNet gtsam::HybridBayesNet::choose | ( | const DiscreteValues & | assignment | ) | const |
Get the Gaussian Bayes net P(X|M=m) corresponding to a specific assignment m for the discrete variables M. As the hybrid Bayes net defines P(X,M) = P(X|M) P(M), this method returns the posterior p(X|M=m).
assignment | The discrete value assignment for the discrete keys. |
Definition at line 103 of file HybridBayesNet.cpp.
DiscreteBayesNet gtsam::HybridBayesNet::discreteMarginal | ( | ) | const |
Get the discrete Bayes Net P(M). As the hybrid Bayes net defines P(X,M) = P(X|M) P(M), this method returns the marginal distribution on the discrete variables.
Definition at line 92 of file HybridBayesNet.cpp.
AlgebraicDecisionTree< Key > gtsam::HybridBayesNet::discretePosterior | ( | const VectorValues & | continuousValues | ) | const |
Compute normalized posterior P(M|X=x) and return as a tree.
continuousValues | Continuous values x to condition P(M|X=x) on. |
Definition at line 201 of file HybridBayesNet.cpp.
|
inline |
Preferred: Emplace a conditional directly using arguments.
Examples: hbn.emplace_shared<HybridGaussianConditional>(...))); hbn.emplace_shared<GaussianConditional>(...))); hbn.emplace_shared<DiscreteConditional>(...)));
Definition at line 116 of file HybridBayesNet.h.
GTSAM-style equals.
Definition at line 39 of file HybridBayesNet.cpp.
AlgebraicDecisionTree< Key > gtsam::HybridBayesNet::errorTree | ( | const VectorValues & | continuousValues | ) | const |
Compute the negative log posterior log P'(M|x) of all assignments up to a constant, returning the result as an algebraic decision tree.
continuousValues | Continuous values x at which to compute log P'(M|x) |
Definition at line 188 of file HybridBayesNet.cpp.
double gtsam::HybridBayesNet::evaluate | ( | const HybridValues & | values | ) | const |
Evaluate hybrid probability density for given HybridValues.
Definition at line 210 of file HybridBayesNet.cpp.
double gtsam::BayesNet< CONDITIONAL >::logProbability |
Definition at line 94 of file BayesNet-inst.h.
|
inline |
Evaluate hybrid probability density for given HybridValues, sugar.
Definition at line 145 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 123 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 141 of file HybridBayesNet.cpp.
|
overridevirtual |
GTSAM-style printing.
Reimplemented from gtsam::FactorGraph< HybridConditional >.
Definition at line 33 of file HybridBayesNet.cpp.
HybridBayesNet gtsam::HybridBayesNet::prune | ( | size_t | maxNrLeaves | ) | const |
Prune the Bayes Net such that we have at most maxNrLeaves leaves.
maxNrLeaves | Continuous values at which to compute the error. |
Definition at line 48 of file HybridBayesNet.cpp.
|
inline |
Add a conditional to the Bayes net. Implicitly convert to a HybridConditional.
E.g. hbn.push_back(std::make_shared<DiscreteConditional>(m, "1/1"));
CONDITIONAL | Type of conditional. This is shared_ptr version. |
conditional | The conditional as a shared pointer. |
Definition at line 103 of file HybridBayesNet.h.
|
inline |
Move a HybridConditional into a shared pointer and add.
Example: HybridGaussianConditional conditional(...); hbn.push_back(conditional); // loses the original conditional
Definition at line 87 of file HybridBayesNet.h.
|
inline |
Add a hybrid conditional using a shared_ptr.
This is the "native" push back, as this class stores hybrid conditionals.
Definition at line 76 of file HybridBayesNet.h.
HybridValues gtsam::HybridBayesNet::sample | ( | ) | const |
Sample using ancestral sampling, use default rng.
Definition at line 183 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 178 of file HybridBayesNet.cpp.
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 153 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 172 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 215 of file HybridBayesNet.cpp.