#include <TableDistribution.h>
Public Types | |
typedef DiscreteConditional | BaseConditional |
Typedef to our conditional base class. More... | |
typedef std::shared_ptr< This > | shared_ptr |
shared_ptr to this class More... | |
typedef TableDistribution | This |
Typedef to this class. More... | |
using | Values = DiscreteValues |
backwards compatibility More... | |
![]() | |
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... | |
![]() | |
typedef AlgebraicDecisionTree< Key > | ADT |
typedef DiscreteFactor | Base |
Typedef to base class. More... | |
using | Binary = std::function< double(const double, const double)> |
typedef std::shared_ptr< DecisionTreeFactor > | shared_ptr |
typedef DecisionTreeFactor | This |
using | Unary = std::function< double(const double &)> |
using | UnaryAssignment = std::function< double(const Assignment< Key > &, const double &)> |
![]() | |
typedef Factor | Base |
Our base class. More... | |
using | Binary = std::function< double(const double, const double)> |
typedef std::shared_ptr< DiscreteFactor > | shared_ptr |
shared_ptr to this class More... | |
typedef DiscreteFactor | This |
This class. More... | |
using | Unary = std::function< double(const double &)> |
using | UnaryAssignment = std::function< double(const Assignment< Key > &, const double &)> |
using | Values = DiscreteValues |
backwards compatibility More... | |
using | Names = DiscreteValues::Names |
Translation table from values to strings. More... | |
![]() | |
typedef KeyVector::const_iterator | const_iterator |
Const iterator over keys. More... | |
typedef KeyVector::iterator | iterator |
Iterator over keys. More... | |
![]() | |
using | Base = 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)> |
![]() | |
typedef std::pair< typename DecisionTreeFactor ::const_iterator, typename DecisionTreeFactor ::const_iterator > | ConstFactorRange |
typedef ConstFactorRangeIterator | Frontals |
typedef ConstFactorRangeIterator | Parents |
Public Member Functions | |
Standard Constructors | |
TableDistribution () | |
Default constructor needed for serialization. More... | |
TableDistribution (const TableFactor &f) | |
Construct from TableFactor. More... | |
TableDistribution (const DiscreteKeys &keys, const std::vector< double > &potentials) | |
TableDistribution (const DiscreteKey &key, const std::vector< double > &potentials) | |
TableDistribution (const DiscreteKeys &keys, const std::string &potentials) | |
TableDistribution (const DiscreteKey &key, const std::string &potentials) | |
Testable | |
void | print (const std::string &s="Table Distribution: ", 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 | |
TableFactor | table () const |
Return the underlying TableFactor. More... | |
virtual double | evaluate (const Assignment< Key > &values) const override |
Evaluate the conditional given the values. More... | |
DiscreteFactor::shared_ptr | sum (size_t nrFrontals) const override |
Create new factor by summing all values with the same separator values. More... | |
DiscreteFactor::shared_ptr | sum (const Ordering &keys) const override |
Create new factor by summing all values with the same separator values. More... | |
double | max () const override |
Find the maximum value in the factor. More... | |
DiscreteFactor::shared_ptr | max (size_t nrFrontals) const override |
Create new factor by maximizing over all values with the same separator. More... | |
DiscreteFactor::shared_ptr | max (const Ordering &keys) const override |
Create new factor by maximizing over all values with the same separator. More... | |
DiscreteFactor::shared_ptr | operator* (double s) const override |
Multiply by scalar s. More... | |
DiscreteFactor::shared_ptr | operator/ (const DiscreteFactor::shared_ptr &f) const override |
divide by DiscreteFactor::shared_ptr f (safely) More... | |
DiscreteValues | argmax () const |
Return assignment that maximizes value. More... | |
virtual size_t | sample (const DiscreteValues &parentsValues) const override |
virtual double | evaluate (const HybridValues &c) const |
Advanced Interface | |
virtual void | prune (size_t maxNrAssignments) override |
Prune the conditional. More... | |
DecisionTreeFactor | toDecisionTreeFactor () const override |
Get a DecisionTreeFactor representation. More... | |
uint64_t | nrValues () const override |
Get the number of non-zero values. More... | |
![]() | |
DiscreteConditional () | |
Default constructor needed for serialization. More... | |
DiscreteConditional (size_t nFrontals, const DiscreteFactor &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::vector< double > &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 |
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... | |
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 (size_t parent_value) const |
Single parent version. More... | |
size_t | sample () const |
Zero parent version. More... | |
size_t | argmax (const DiscreteValues &parentsValues=DiscreteValues()) const |
Return assignment for single frontal variable that maximizes value. More... | |
double | error (const DiscreteValues &values) const override |
Calculate error for DiscreteValues x , is -log(probability). More... | |
double | error (const HybridValues &values) const override |
virtual double | evaluate (const Assignment< Key > &values) const override |
< DiscreteValues version More... | |
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... | |
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... | |
double | evaluate (const HybridValues &x) const override |
double | logProbability (const HybridValues &x) const override |
< HybridValues version More... | |
double | negLogConstant () const override |
void | removeDiscreteModes (const DiscreteValues &given) |
Remove the discrete modes whose assignments are given to us. Only applies to discrete conditionals. More... | |
![]() | |
DecisionTreeFactor () | |
DecisionTreeFactor (const DiscreteKeys &keys, const ADT &potentials) | |
DecisionTreeFactor (const DiscreteKeys &keys, const std::vector< double > &table) | |
Constructor from doubles. More... | |
DecisionTreeFactor (const DiscreteKeys &keys, const std::string &table) | |
Constructor from string. More... | |
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 (Unary op) const |
DecisionTreeFactor | apply (UnaryAssignment op) const |
DecisionTreeFactor | apply (const DecisionTreeFactor &f, Binary op) const |
shared_ptr | combine (size_t nrFrontals, Binary op) const |
shared_ptr | combine (const Ordering &keys, Binary op) const |
std::vector< std::pair< DiscreteValues, double > > | enumerate () const |
Enumerate all values into a map from values to double. More... | |
std::vector< double > | probabilities () const |
Get all the probabilities in order of assignment values. More... | |
double | computeThreshold (const size_t N) const |
Compute the probability value which is the threshold above which only N leaves are present. 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 | error (const DiscreteValues &values) const override |
Calculate error for DiscreteValues x , is -log(probability). More... | |
virtual DiscreteFactor::shared_ptr | multiply (const DiscreteFactor::shared_ptr &f) const override |
Multiply factors, DiscreteFactor::shared_ptr edition. More... | |
DecisionTreeFactor | operator* (const DecisionTreeFactor &f) const override |
multiply two factors More... | |
DecisionTreeFactor | operator/ (const DecisionTreeFactor &f) const |
Divide by factor f (safely). Division of a factor ![]() ![]() ![]() | |
DiscreteFactor::shared_ptr | restrict (const DiscreteValues &assignment) const override |
Restrict the factor to the given assignment. More... | |
![]() | |
DiscreteFactor () | |
template<typename CONTAINER > | |
DiscreteFactor (const CONTAINER &keys, const std::map< Key, size_t > cardinalities={}) | |
DiscreteKeys | discreteKeys () const |
Return all the discrete keys associated with this factor. More... | |
std::map< Key, size_t > | cardinalities () const |
size_t | cardinality (Key j) const |
double | operator() (const DiscreteValues &values) const |
Find value for given assignment of values to variables. More... | |
double | error (const HybridValues &c) const override |
virtual AlgebraicDecisionTree< Key > | errorTree () const |
Compute error for each assignment and return as a tree. More... | |
DiscreteFactor::shared_ptr | scale () const |
Scale the factor values by the maximum to prevent underflow/overflow. More... | |
![]() | |
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 () |
![]() | |
AlgebraicDecisionTree (const AlgebraicDecisionTree< M > &other, const std::map< M, Key > &map) | |
AlgebraicDecisionTree (const Base &add) | |
AlgebraicDecisionTree (const DecisionTree< Key, X > &other, Func f) | |
Create from an arbitrary DecisionTree<L, X> by operating on it with a functional f . More... | |
AlgebraicDecisionTree (const Key &label, double y1, double y2) | |
AlgebraicDecisionTree (const std::vector< typename Base::LabelC > &labelCs, const std::string &table) | |
Create from keys and string table. More... | |
AlgebraicDecisionTree (const std::vector< typename Base::LabelC > &labelCs, const std::vector< double > &ys) | |
Create from keys with cardinalities and a vector table. More... | |
AlgebraicDecisionTree (const typename Base::LabelC &labelC, double y1, double y2) | |
Create a new leaf function splitting on a variable. More... | |
AlgebraicDecisionTree (const typename Base::NodePtr root) | |
Constructor which accepts root pointer. More... | |
AlgebraicDecisionTree (double leaf=1.0) | |
AlgebraicDecisionTree (Iterator begin, Iterator end, const Key &label) | |
Create a range of decision trees, splitting on a single variable. More... | |
bool | equals (const AlgebraicDecisionTree &other, double tol=1e-9) const |
Equality method customized to value type double . More... | |
double | max () const |
Find the maximum values amongst all leaves. More... | |
double | min () const |
Find the minimum values amongst all leaves. More... | |
AlgebraicDecisionTree | normalize () const |
Helper method to perform normalization such that all leaves in the tree sum to 1. More... | |
AlgebraicDecisionTree | operator* (const AlgebraicDecisionTree &g) const |
AlgebraicDecisionTree | operator+ (const AlgebraicDecisionTree &g) const |
AlgebraicDecisionTree | operator- () 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... | |
double | sum () const |
Compute sum of all values. More... | |
AlgebraicDecisionTree | sum (const Key &label, size_t cardinality) const |
AlgebraicDecisionTree | sum (const typename Base::LabelC &labelC) const |
![]() | |
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 Unary &op, DecisionTree &&other) noexcept | |
Move constructor for DecisionTree. Very efficient as does not allocate anything, just changes in-place. But other is consumed. More... | |
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 translate labels via map from type M to L. More... | |
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 | restrict (const Assignment< Key > &assignment) 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 |
std::pair< DecisionTree< Key, A >, DecisionTree< Key, B > > | split (std::function< std::pair< A, B >(const double &)> AB_of_Y) const |
Convert into two trees with value types A and B. More... | |
DecisionTree (const NodePtr &root) | |
![]() | |
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 () |
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 () |
Private Types | |
typedef Eigen::SparseVector< double >::InnerIterator | SparseIt |
Private Attributes | |
TableFactor | table_ |
Additional Inherited Members | |
![]() | |
static double | safe_div (const double &a, const double &b) |
![]() | |
static NodePtr | compose (Iterator begin, Iterator end, const Key &label) |
![]() | |
static bool | CheckInvariants (const DiscreteConditional &conditional, const VALUES &x) |
![]() | |
NodePtr | root_ |
A DecisionTree just contains the root. TODO(dellaert): make protected. More... | |
![]() | |
DiscreteConditional::ADT | choose (const DiscreteValues &given, bool forceComplete) const |
Internal version of choose. More... | |
![]() | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
![]() | |
Conditional () | |
Conditional (size_t nrFrontals) | |
![]() | |
template<typename CONTAINER > | |
static Factor | FromKeys (const CONTAINER &keys) |
template<typename ITERATOR > | |
static Factor | FromIterators (ITERATOR first, ITERATOR last) |
![]() | |
static NodePtr | build (It begin, It end, ValueIt beginY, ValueIt endY) |
static NodePtr | convertFrom (const typename DecisionTree< Key, X >::NodePtr &f, std::function< double(const X &)> Y_of_X) |
Convert from a DecisionTree<L, X> to DecisionTree<L, Y>. More... | |
static 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) |
Convert from a DecisionTree<M, X> to DecisionTree<L, Y>. More... | |
static NodePtr | create (It begin, It end, ValueIt beginY, ValueIt endY) |
static bool | DefaultCompare (const double &a, const double &b) |
Default method for comparison of two objects of type Y. More... | |
![]() | |
std::map< Key, size_t > | cardinalities_ |
Map of Keys and their cardinalities. More... | |
![]() | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
![]() | |
size_t | nrFrontals_ |
Distribution which uses a SparseVector as the internal representation, similar to the TableFactor.
This is primarily used in the case when we have a clique in the BayesTree which consists of all the discrete variables, e.g. in hybrid elimination.
Definition at line 39 of file TableDistribution.h.
Typedef to our conditional base class.
Definition at line 50 of file TableDistribution.h.
typedef std::shared_ptr<This> gtsam::TableDistribution::shared_ptr |
shared_ptr to this class
Definition at line 48 of file TableDistribution.h.
|
private |
Definition at line 43 of file TableDistribution.h.
Typedef to this class.
Definition at line 47 of file TableDistribution.h.
backwards compatibility
Definition at line 52 of file TableDistribution.h.
|
inline |
Default constructor needed for serialization.
Definition at line 58 of file TableDistribution.h.
gtsam::TableDistribution::TableDistribution | ( | const TableFactor & | f | ) |
Construct from TableFactor.
Definition at line 47 of file TableDistribution.cpp.
gtsam::TableDistribution::TableDistribution | ( | const DiscreteKeys & | keys, |
const std::vector< double > & | potentials | ||
) |
Construct from DiscreteKeys and std::vector.
Definition at line 53 of file TableDistribution.cpp.
|
inline |
Construct from single DiscreteKey and std::vector.
Definition at line 72 of file TableDistribution.h.
gtsam::TableDistribution::TableDistribution | ( | const DiscreteKeys & | keys, |
const std::string & | potentials | ||
) |
Construct from DiscreteKey and std::string.
Definition at line 61 of file TableDistribution.cpp.
|
inline |
Construct from single DiscreteKey and std::string.
Definition at line 84 of file TableDistribution.h.
DiscreteValues gtsam::TableDistribution::argmax | ( | ) | const |
Return assignment that maximizes value.
Definition at line 125 of file TableDistribution.cpp.
|
overridevirtual |
GTSAM-style equals.
Reimplemented from gtsam::DiscreteConditional.
Definition at line 81 of file TableDistribution.cpp.
|
inlineoverridevirtual |
Evaluate the conditional given the values.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 109 of file TableDistribution.h.
double gtsam::Conditional< FACTOR, DERIVEDCONDITIONAL >::evaluate |
All conditional types need to implement an evaluate
function, that yields a true probability. The default implementation just exponentiates logProbability.
Definition at line 55 of file Conditional-inst.h.
|
inlineoverridevirtual |
Find the maximum value in the factor.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 120 of file TableDistribution.h.
|
overridevirtual |
Create new factor by maximizing over all values with the same separator.
Reimplemented from gtsam::DiscreteConditional.
Definition at line 109 of file TableDistribution.cpp.
|
overridevirtual |
Create new factor by maximizing over all values with the same separator.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 104 of file TableDistribution.cpp.
|
inlineoverridevirtual |
Get the number of non-zero values.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 163 of file TableDistribution.h.
|
overridevirtual |
Multiply by scalar s.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 114 of file TableDistribution.cpp.
|
overridevirtual |
divide by DiscreteFactor::shared_ptr f (safely)
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 119 of file TableDistribution.cpp.
|
overridevirtual |
GTSAM-style print.
Reimplemented from gtsam::DiscreteConditional.
Definition at line 69 of file TableDistribution.cpp.
|
overridevirtual |
Prune the conditional.
Reimplemented from gtsam::DiscreteConditional.
Definition at line 142 of file TableDistribution.cpp.
|
overridevirtual |
sample
parentsValues | Known values of the parents |
Reimplemented from gtsam::DiscreteConditional.
Definition at line 147 of file TableDistribution.cpp.
|
overridevirtual |
Create new factor by summing all values with the same separator values.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 99 of file TableDistribution.cpp.
|
overridevirtual |
Create new factor by summing all values with the same separator values.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 94 of file TableDistribution.cpp.
|
inline |
Return the underlying TableFactor.
Definition at line 104 of file TableDistribution.h.
|
inlineoverridevirtual |
Get a DecisionTreeFactor representation.
Reimplemented from gtsam::DecisionTreeFactor.
Definition at line 158 of file TableDistribution.h.
|
private |
Definition at line 41 of file TableDistribution.h.