#include <DiscreteConditional.h>
Public Types | |
typedef Conditional< BaseFactor, This > | BaseConditional |
Typedef to our conditional base class. More... | |
typedef DecisionTreeFactor | BaseFactor |
Typedef to our factor base class. More... | |
typedef std::shared_ptr< This > | shared_ptr |
shared_ptr to this class More... | |
typedef DiscreteConditional | This |
Typedef to this class. More... | |
using | Values = DiscreteValues |
backwards compatibility More... | |
Public Types inherited from gtsam::DecisionTreeFactor | |
typedef AlgebraicDecisionTree< Key > | ADT |
typedef DiscreteFactor | Base |
Typedef to base class. More... | |
typedef std::shared_ptr< DecisionTreeFactor > | shared_ptr |
typedef DecisionTreeFactor | This |
Public Types inherited from gtsam::DiscreteFactor | |
typedef Factor | Base |
Our base class. More... | |
typedef std::shared_ptr< DiscreteFactor > | shared_ptr |
shared_ptr to this class More... | |
typedef DiscreteFactor | This |
This class. More... | |
using | Values = DiscreteValues |
backwards compatibility More... | |
using | Names = DiscreteValues::Names |
Translation table from values to strings. 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::AlgebraicDecisionTree< Key > | |
using | Base = DecisionTree< Key, double > |
Public Types inherited from gtsam::DecisionTree< Key, double > | |
using | Binary = std::function< double(const double &, const double &)> |
using | CompareFunc = std::function< bool(const double &, const double &)> |
using | LabelC = std::pair< Key, size_t > |
using | LabelFormatter = std::function< std::string(Key)> |
using | NodePtr = typename Node::Ptr |
using | Unary = std::function< double(const double &)> |
using | UnaryAssignment = std::function< double(const Assignment< Key > &, const double &)> |
using | ValueFormatter = std::function< std::string(double)> |
Public Types inherited from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional > | |
typedef std::pair< typename DecisionTreeFactor ::const_iterator, typename DecisionTreeFactor ::const_iterator > | ConstFactorRange |
typedef ConstFactorRangeIterator | Frontals |
typedef ConstFactorRangeIterator | Parents |
Public Member Functions | |
Standard Constructors | |
DiscreteConditional () | |
Default constructor needed for serialization. More... | |
DiscreteConditional (size_t nFrontals, const DecisionTreeFactor &f) | |
Construct from factor, taking the first nFrontals keys as frontals. More... | |
DiscreteConditional (size_t nFrontals, const DiscreteKeys &keys, const ADT &potentials) | |
DiscreteConditional (const Signature &signature) | |
DiscreteConditional (const DiscreteKey &key, const DiscreteKeys &parents, const Signature::Table &table) | |
DiscreteConditional (const DiscreteKey &key, const DiscreteKeys &parents, const std::string &spec) | |
DiscreteConditional (const DiscreteKey &key, const std::string &spec) | |
No-parent specialization; can also use DiscreteDistribution. More... | |
DiscreteConditional (const DecisionTreeFactor &joint, const DecisionTreeFactor &marginal) | |
construct P(X|Y) = f(X,Y)/f(Y) from f(X,Y) and f(Y) Assumes but does not check that f(Y)=sum_X f(X,Y). More... | |
DiscreteConditional (const DecisionTreeFactor &joint, const DecisionTreeFactor &marginal, const Ordering &orderedKeys) | |
construct P(X|Y) = f(X,Y)/f(Y) from f(X,Y) and f(Y) Assumes but does not check that f(Y)=sum_X f(X,Y). Makes sure the keys are ordered as given. Does not check orderedKeys. More... | |
DiscreteConditional | operator* (const DiscreteConditional &other) const |
Combine two conditionals, yielding a new conditional with the union of the frontal keys, ordered by gtsam::Key. More... | |
DiscreteConditional | marginal (Key key) const |
Testable | |
void | print (const std::string &s="Discrete Conditional: ", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
GTSAM-style print. More... | |
bool | equals (const DiscreteFactor &other, double tol=1e-9) const override |
GTSAM-style equals. More... | |
Standard Interface | |
double | logProbability (const DiscreteValues &x) const |
Log-probability is just -error(x). More... | |
void | printSignature (const std::string &s="Discrete Conditional: ", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print index signature only More... | |
double | evaluate (const DiscreteValues &values) const |
Evaluate, just look up in AlgebraicDecisonTree. More... | |
shared_ptr | choose (const DiscreteValues &given) const |
< DiscreteValues version More... | |
DecisionTreeFactor::shared_ptr | likelihood (const DiscreteValues &frontalValues) const |
DecisionTreeFactor::shared_ptr | likelihood (size_t frontal) const |
size_t | sample (const DiscreteValues &parentsValues) const |
size_t | sample (size_t parent_value) const |
Single parent version. More... | |
size_t | sample () const |
Zero parent version. More... | |
size_t | argmax () const |
Return assignment that maximizes distribution. More... | |
Advanced Interface | |
void | sampleInPlace (DiscreteValues *parentsValues) const |
sample in place, stores result in partial solution More... | |
std::vector< DiscreteValues > | frontalAssignments () const |
Return all assignments for frontal variables. More... | |
std::vector< DiscreteValues > | allAssignments () const |
Return all assignments for frontal and parent variables. More... | |
Wrapper support | |
std::string | markdown (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override |
Render as markdown table. More... | |
std::string | html (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const Names &names={}) const override |
Render as html table. More... | |
HybridValues methods. | |
double | evaluate (const HybridValues &x) const override |
double | logProbability (const HybridValues &x) const override |
< HybridValues version More... | |
double | logNormalizationConstant () const override |
Public Member Functions inherited from gtsam::DecisionTreeFactor | |
DecisionTreeFactor () | |
DecisionTreeFactor (const DiscreteKeys &keys, const ADT &potentials) | |
DecisionTreeFactor (const DiscreteKeys &keys, const std::vector< double > &table) | |
DecisionTreeFactor (const DiscreteKeys &keys, const std::string &table) | |
template<class SOURCE > | |
DecisionTreeFactor (const DiscreteKey &key, SOURCE table) | |
Single-key specialization. More... | |
DecisionTreeFactor (const DiscreteKey &key, const std::vector< double > &row) | |
Single-key specialization, with vector of doubles. More... | |
DecisionTreeFactor (const DiscreteConditional &c) | |
DecisionTreeFactor | apply (const DecisionTreeFactor &f, ADT::Binary op) const |
shared_ptr | combine (size_t nrFrontals, ADT::Binary op) const |
shared_ptr | combine (const Ordering &keys, ADT::Binary op) const |
std::vector< std::pair< DiscreteValues, double > > | enumerate () const |
Enumerate all values into a map from values to double. More... | |
DiscreteKeys | discreteKeys () const |
Return all the discrete keys associated with this factor. More... | |
DecisionTreeFactor | prune (size_t maxNrAssignments) const |
Prune the decision tree of discrete variables. More... | |
void | dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, bool showZero=true) const |
void | dot (const std::string &name, const KeyFormatter &keyFormatter=DefaultKeyFormatter, bool showZero=true) const |
std::string | dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter, bool showZero=true) const |
double | error (const HybridValues &values) const override |
double | evaluate (const DiscreteValues &values) const |
double | operator() (const DiscreteValues &values) const override |
Evaluate probability distribution, sugar. More... | |
double | error (const DiscreteValues &values) const |
Calculate error for DiscreteValues x , is -log(probability). More... | |
DecisionTreeFactor | operator* (const DecisionTreeFactor &f) const override |
multiply two factors More... | |
size_t | cardinality (Key j) const |
DecisionTreeFactor | operator/ (const DecisionTreeFactor &f) const |
divide by factor f (safely) More... | |
DecisionTreeFactor | toDecisionTreeFactor () const override |
Convert into a decisiontree. More... | |
shared_ptr | sum (size_t nrFrontals) const |
Create new factor by summing all values with the same separator values. More... | |
shared_ptr | sum (const Ordering &keys) const |
Create new factor by summing all values with the same separator values. More... | |
shared_ptr | max (size_t nrFrontals) const |
Create new factor by maximizing over all values with the same separator. More... | |
shared_ptr | max (const Ordering &keys) const |
Create new factor by maximizing over all values with the same separator. More... | |
Public Member Functions inherited from gtsam::DiscreteFactor | |
DiscreteFactor () | |
template<typename CONTAINER > | |
DiscreteFactor (const CONTAINER &keys) | |
void | print (const std::string &s="DiscreteFactor\, const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print More... | |
double | error (const DiscreteValues &values) const |
Error is just -log(value) More... | |
double | error (const HybridValues &c) const override |
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::AlgebraicDecisionTree< Key > | |
AlgebraicDecisionTree (double leaf=1.0) | |
AlgebraicDecisionTree (const Base &add) | |
AlgebraicDecisionTree (const Key &label, double y1, double y2) | |
AlgebraicDecisionTree (const typename Base::LabelC &labelC, double y1, double y2) | |
AlgebraicDecisionTree (const std::vector< typename Base::LabelC > &labelCs, const std::vector< double > &ys) | |
AlgebraicDecisionTree (const std::vector< typename Base::LabelC > &labelCs, const std::string &table) | |
AlgebraicDecisionTree (Iterator begin, Iterator end, const Key &label) | |
AlgebraicDecisionTree (const AlgebraicDecisionTree< M > &other, const std::map< M, Key > &map) | |
bool | equals (const AlgebraicDecisionTree &other, double tol=1e-9) const |
Equality method customized to value type double . More... | |
AlgebraicDecisionTree | operator* (const AlgebraicDecisionTree &g) const |
AlgebraicDecisionTree | operator+ (const AlgebraicDecisionTree &g) const |
AlgebraicDecisionTree | operator/ (const AlgebraicDecisionTree &g) const |
void | print (const std::string &s="", const typename Base::LabelFormatter &labelFormatter=&DefaultFormatter) const |
print method customized to value type double . More... | |
AlgebraicDecisionTree | sum (const Key &label, size_t cardinality) const |
AlgebraicDecisionTree | sum (const typename Base::LabelC &labelC) const |
Public Member Functions inherited from gtsam::DecisionTree< Key, double > | |
DecisionTree () | |
DecisionTree (const double &y) | |
DecisionTree (const Key &label, const double &y1, const double &y2) | |
Create tree with 2 assignments y1 , y2 , splitting on variable label More... | |
DecisionTree (const LabelC &label, const double &y1, const double &y2) | |
DecisionTree (const std::vector< LabelC > &labelCs, const std::vector< double > &ys) | |
DecisionTree (const std::vector< LabelC > &labelCs, const std::string &table) | |
DecisionTree (Iterator begin, Iterator end, const Key &label) | |
DecisionTree (const Key &label, const DecisionTree &f0, const DecisionTree &f1) | |
DecisionTree (const DecisionTree< Key, X > &other, Func Y_of_X) | |
Convert from a different value type. More... | |
DecisionTree (const DecisionTree< M, X > &other, const std::map< M, Key > &map, Func Y_of_X) | |
Convert from a different value type X to value type Y, also transate labels via map from type M to L. More... | |
DecisionTree (const NodePtr &root) | |
NodePtr | compose (Iterator begin, Iterator end, const Key &label) const |
void | print (const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const |
GTSAM-style print. More... | |
bool | equals (const DecisionTree &other, const CompareFunc &compare=&DefaultCompare) const |
virtual | ~DecisionTree ()=default |
Make virtual. More... | |
bool | empty () const |
Check if tree is empty. More... | |
bool | operator== (const DecisionTree &q) const |
const double & | operator() (const Assignment< Key > &x) const |
void | visit (Func f) const |
Visit all leaves in depth-first fashion. More... | |
void | visitLeaf (Func f) const |
Visit all leaves in depth-first fashion. More... | |
void | visitWith (Func f) const |
Visit all leaves in depth-first fashion. More... | |
size_t | nrLeaves () const |
Return the number of leaves in the tree. More... | |
X | fold (Func f, X x0) const |
Fold a binary function over the tree, returning accumulator. More... | |
std::set< Key > | labels () const |
DecisionTree | apply (const Unary &op) const |
DecisionTree | apply (const UnaryAssignment &op) const |
Apply Unary operation "op" to f while also providing the corresponding assignment. More... | |
DecisionTree | apply (const DecisionTree &g, const Binary &op) const |
DecisionTree | choose (const Key &label, size_t index) const |
DecisionTree | combine (const Key &label, size_t cardinality, const Binary &op) const |
DecisionTree | combine (const LabelC &labelC, const Binary &op) const |
void | dot (std::ostream &os, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero=true) const |
void | dot (const std::string &name, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero=true) const |
std::string | dot (const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter, bool showZero=true) const |
Public Member Functions inherited from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional > | |
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 () |
DecisionTreeFactor ::const_iterator | beginFrontals () const |
DecisionTreeFactor ::iterator | beginFrontals () |
DecisionTreeFactor ::const_iterator | endFrontals () const |
DecisionTreeFactor ::iterator | endFrontals () |
DecisionTreeFactor ::const_iterator | beginParents () const |
DecisionTreeFactor ::iterator | beginParents () |
DecisionTreeFactor ::const_iterator | endParents () const |
DecisionTreeFactor ::iterator | endParents () |
Protected Member Functions | |
DiscreteConditional::ADT | choose (const DiscreteValues &given, bool forceComplete) const |
Internal version of choose. More... | |
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::DecisionTree< Key, double > | |
NodePtr | convertFrom (const typename DecisionTree< M, X >::NodePtr &f, std::function< Key(const M &)> L_of_M, std::function< double(const X &)> Y_of_X) const |
Convert from a DecisionTree<M, X> to DecisionTree<L, Y>. More... | |
NodePtr | create (It begin, It end, ValueIt beginY, ValueIt endY) const |
Protected Member Functions inherited from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional > | |
Conditional () | |
Conditional (size_t nrFrontals) | |
Additional Inherited Members | |
Static Public Member Functions inherited from gtsam::DecisionTreeFactor | |
static double | safe_div (const double &a, const double &b) |
Static Public Member Functions inherited from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional > | |
static bool | CheckInvariants (const DiscreteConditional &conditional, const VALUES &x) |
Public Attributes inherited from gtsam::DecisionTree< Key, double > | |
NodePtr | root_ |
A DecisionTree just contains the root. TODO(dellaert): make protected. More... | |
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) |
Static Protected Member Functions inherited from gtsam::DecisionTree< Key, double > | |
static bool | DefaultCompare (const double &a, const double &b) |
Default method for comparison of two objects of type Y. More... | |
Protected Attributes inherited from gtsam::DecisionTreeFactor | |
std::map< Key, size_t > | cardinalities_ |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Protected Attributes inherited from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional > | |
size_t | nrFrontals_ |
Discrete Conditional Density Derives from DecisionTreeFactor
represent a discrete conditional distribution over discrete variables.
Definition at line 37 of file DiscreteConditional.h.
Typedef to our conditional base class.
Definition at line 46 of file DiscreteConditional.h.
Typedef to our factor base class.
Definition at line 44 of file DiscreteConditional.h.
typedef std::shared_ptr<This> gtsam::DiscreteConditional::shared_ptr |
shared_ptr to this class
Definition at line 43 of file DiscreteConditional.h.
Typedef to this class.
Definition at line 42 of file DiscreteConditional.h.
backwards compatibility
Definition at line 48 of file DiscreteConditional.h.
|
inline |
Default constructor needed for serialization.
Definition at line 54 of file DiscreteConditional.h.
gtsam::DiscreteConditional::DiscreteConditional | ( | size_t | nFrontals, |
const DecisionTreeFactor & | f | ||
) |
Construct from factor, taking the first nFrontals
keys as frontals.
Definition at line 44 of file DiscreteConditional.cpp.
gtsam::DiscreteConditional::DiscreteConditional | ( | size_t | nFrontals, |
const DiscreteKeys & | keys, | ||
const ADT & | potentials | ||
) |
Construct from DiscreteKeys and AlgebraicDecisionTree, taking the first nFrontals
keys as frontals, in the order given.
Definition at line 49 of file DiscreteConditional.cpp.
|
explicit |
Construct from signature
Definition at line 70 of file DiscreteConditional.cpp.
|
inline |
Construct from key, parents, and a Signature::Table specifying the conditional probability table (CPT) in 00 01 10 11 order. For three-valued, it would be 00 01 02 10 11 12 20 21 22, etc....
Example: DiscreteConditional P(D, {B,E}, table);
Definition at line 76 of file DiscreteConditional.h.
|
inline |
Construct from key, parents, and a string specifying the conditional probability table (CPT) in 00 01 10 11 order. For three-valued, it would be 00 01 02 10 11 12 20 21 22, etc....
The string is parsed into a Signature::Table.
Example: DiscreteConditional P(D, {B,E}, "9/1 2/8 3/7 1/9");
Definition at line 89 of file DiscreteConditional.h.
|
inline |
No-parent specialization; can also use DiscreteDistribution.
Definition at line 94 of file DiscreteConditional.h.
gtsam::DiscreteConditional::DiscreteConditional | ( | const DecisionTreeFactor & | joint, |
const DecisionTreeFactor & | marginal | ||
) |
construct P(X|Y) = f(X,Y)/f(Y) from f(X,Y) and f(Y) Assumes but does not check that f(Y)=sum_X f(X,Y).
Definition at line 55 of file DiscreteConditional.cpp.
gtsam::DiscreteConditional::DiscreteConditional | ( | const DecisionTreeFactor & | joint, |
const DecisionTreeFactor & | marginal, | ||
const Ordering & | orderedKeys | ||
) |
construct P(X|Y) = f(X,Y)/f(Y) from f(X,Y) and f(Y) Assumes but does not check that f(Y)=sum_X f(X,Y). Makes sure the keys are ordered as given. Does not check orderedKeys.
Definition at line 61 of file DiscreteConditional.cpp.
vector< DiscreteValues > gtsam::DiscreteConditional::allAssignments | ( | ) | const |
Return all assignments for frontal and parent variables.
Definition at line 322 of file DiscreteConditional.cpp.
size_t gtsam::DiscreteConditional::argmax | ( | ) | const |
Return assignment that maximizes distribution.
Definition at line 238 of file DiscreteConditional.cpp.
DiscreteConditional::shared_ptr gtsam::DiscreteConditional::choose | ( | const DiscreteValues & | given | ) | const |
< DiscreteValues version
restrict to given parent values.
Note: does not need be complete set. Examples:
P(C|D,E) + . -> P(C|D,E) P(C|D,E) + E -> P(C|D) P(C|D,E) + D -> P(C|E) P(C|D,E) + D,E -> P(C) P(C|D,E) + C -> error!
Definition at line 182 of file DiscreteConditional.cpp.
|
protected |
Internal version of choose.
Definition at line 160 of file DiscreteConditional.cpp.
|
overridevirtual |
GTSAM-style equals.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 149 of file DiscreteConditional.cpp.
|
inline |
Evaluate, just look up in AlgebraicDecisonTree.
Definition at line 162 of file DiscreteConditional.h.
|
overridevirtual |
Calculate probability for HybridValues x
. Dispatches to DiscreteValues version.
Reimplemented from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional >.
Definition at line 462 of file DiscreteConditional.cpp.
vector< DiscreteValues > gtsam::DiscreteConditional::frontalAssignments | ( | ) | const |
Return all assignments for frontal variables.
Definition at line 314 of file DiscreteConditional.cpp.
|
overridevirtual |
Render as html table.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 407 of file DiscreteConditional.cpp.
DecisionTreeFactor::shared_ptr gtsam::DiscreteConditional::likelihood | ( | const DiscreteValues & | frontalValues | ) | const |
Convert to a likelihood factor by providing value before bar.
Definition at line 201 of file DiscreteConditional.cpp.
DecisionTreeFactor::shared_ptr gtsam::DiscreteConditional::likelihood | ( | size_t | frontal | ) | const |
Single variable version of likelihood.
Definition at line 226 of file DiscreteConditional.cpp.
|
inlineoverridevirtual |
logNormalizationConstant K is just zero, such that logProbability(x) = log(evaluate(x)) = - error(x) and hence error(x) = - log(evaluate(x)) > 0 for all x.
Reimplemented from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional >.
Definition at line 261 of file DiscreteConditional.h.
|
inline |
Log-probability is just -error(x).
Definition at line 150 of file DiscreteConditional.h.
|
inlineoverridevirtual |
< HybridValues version
Calculate log-probability log(evaluate(x)) for HybridValues x
. This is actually just -error(x).
Reimplemented from gtsam::Conditional< DecisionTreeFactor, DiscreteConditional >.
Definition at line 252 of file DiscreteConditional.h.
DiscreteConditional gtsam::DiscreteConditional::marginal | ( | Key | key | ) | const |
Calculate marginal on given key, no parent case.
Definition at line 112 of file DiscreteConditional.cpp.
|
overridevirtual |
Render as markdown table.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 355 of file DiscreteConditional.cpp.
DiscreteConditional gtsam::DiscreteConditional::operator* | ( | const DiscreteConditional & | other | ) | const |
Combine two conditionals, yielding a new conditional with the union of the frontal keys, ordered by gtsam::Key.
The two conditionals must make a valid Bayes net fragment, i.e., the frontal variables cannot overlap, and must be acyclic: Example of correct use: P(A,B) = P(A|B) * P(B) P(A,B|C) = P(A|B) * P(B|C) P(A,B,C) = P(A,B|C) * P(C) Example of incorrect use: P(A|B) * P(A|C) = ? P(A|B) * P(B|A) = ? We check for overlapping frontals, but do not check for cyclic.
Definition at line 75 of file DiscreteConditional.cpp.
|
overridevirtual |
GTSAM-style print.
Reimplemented from gtsam::DecisionTreeFactor.
Reimplemented in gtsam::DiscreteDistribution, and gtsam::DiscreteLookupTable.
Definition at line 131 of file DiscreteConditional.cpp.
|
inline |
print index signature only
Definition at line 155 of file DiscreteConditional.h.
size_t gtsam::DiscreteConditional::sample | ( | const DiscreteValues & | parentsValues | ) | const |
sample
parentsValues | Known values of the parents |
Definition at line 266 of file DiscreteConditional.cpp.
Single parent version.
Definition at line 294 of file DiscreteConditional.cpp.
size_t gtsam::DiscreteConditional::sample | ( | ) | const |
Zero parent version.
Definition at line 305 of file DiscreteConditional.cpp.
void gtsam::DiscreteConditional::sampleInPlace | ( | DiscreteValues * | parentsValues | ) | const |
sample in place, stores result in partial solution
Definition at line 258 of file DiscreteConditional.cpp.