#include <TableFactor.h>
Public Types | |
typedef std::vector< std::pair< DiscreteValues, double > > | AssignValList |
typedef DiscreteFactor | Base |
Typedef to base class. More... | |
typedef std::shared_ptr< TableFactor > | shared_ptr |
typedef Eigen::SparseVector< double >::InnerIterator | SparseIt |
typedef TableFactor | This |
Public Types inherited from gtsam::DiscreteFactor | |
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... | |
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 Member Functions | |
Standard Constructors | |
TableFactor () | |
TableFactor (const DiscreteKeys &keys, const TableFactor &potentials) | |
TableFactor (const DiscreteKeys &keys, const Eigen::SparseVector< double > &table) | |
TableFactor (const DiscreteKeys &keys, const std::vector< double > &table) | |
TableFactor (const DiscreteKeys &keys, const std::string &table) | |
template<class SOURCE > | |
TableFactor (const DiscreteKey &key, SOURCE table) | |
Single-key specialization. More... | |
TableFactor (const DiscreteKey &key, const std::vector< double > &row) | |
Single-key specialization, with vector of doubles. More... | |
TableFactor (const DiscreteKeys &keys, const DecisionTreeFactor &dtf) | |
Constructor from DecisionTreeFactor. More... | |
TableFactor (const DecisionTreeFactor &dtf) | |
TableFactor (const DiscreteKeys &keys, const DecisionTree< Key, double > &dtree) | |
Constructor from DecisionTree<Key, double>/AlgebraicDecisionTree. More... | |
TableFactor (const DiscreteConditional &c) | |
Advanced Interface | |
TableFactor | apply (Unary op) const |
TableFactor | apply (UnaryAssignment op) const |
TableFactor | apply (const TableFactor &f, Binary op) const |
DiscreteKeys | contractDkeys (const TableFactor &f) const |
DiscreteKeys | freeDkeys (const TableFactor &f) const |
Return keys in free mode which are the dimensions not involved in the contraction operation. More... | |
DiscreteKeys | unionDkeys (const TableFactor &f) const |
Return union of DiscreteKeys in two factors. More... | |
uint64_t | unionRep (const DiscreteKeys &keys, const DiscreteValues &assign, const uint64_t idx) const |
Create unique representation of union modes. More... | |
std::unordered_map< uint64_t, AssignValList > | createMap (const DiscreteKeys &contract, const DiscreteKeys &free) const |
uint64_t | uniqueRep (const DiscreteKeys &keys, const uint64_t idx) const |
Create unique representation. More... | |
uint64_t | uniqueRep (const DiscreteValues &assignments) const |
Create unique representation with DiscreteValues. More... | |
DiscreteValues | findAssignments (const uint64_t idx) const |
Find DiscreteValues for corresponding index. More... | |
double | findValue (const DiscreteValues &values) const |
Find value for corresponding DiscreteValues. More... | |
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... | |
TableFactor | prune (size_t maxNrAssignments) const |
Prune the decision tree of discrete variables. More... | |
uint64_t | nrValues () const override |
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 | error (const HybridValues &values) const override |
Public Member Functions inherited from gtsam::DiscreteFactor | |
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... | |
virtual AlgebraicDecisionTree< Key > | errorTree () const |
Compute error for each assignment and return as a tree. More... | |
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 () |
Protected Attributes | |
Eigen::SparseVector< double > | sparse_table_ |
SparseVector of nonzero probabilities. More... | |
Protected Attributes inherited from gtsam::DiscreteFactor | |
std::map< Key, size_t > | cardinalities_ |
Map of Keys and their cardinalities. More... | |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Private Member Functions | |
DiscreteKey | discreteKey (size_t i) const |
Return ith key in keys_ as a DiscreteKey. More... | |
size_t | keyValueForIndex (Key target_key, uint64_t index) const |
Uses lazy cartesian product to find nth entry in the cartesian product of arrays in O(1) Example) v0 | v1 | val 0 | 0 | 10 0 | 1 | 21 1 | 0 | 32 1 | 1 | 43 keyValueForIndex(v1, 2) = 0. More... | |
Static Private Member Functions | |
static Eigen::SparseVector< double > | Convert (const DiscreteKeys &keys, const std::string &table) |
Convert probability table given as string to SparseVector. More... | |
static Eigen::SparseVector< double > | Convert (const DiscreteKeys &keys, const std::vector< double > &table) |
Private Attributes | |
std::map< Key, size_t > | denominators_ |
Map of Keys and their denominators used in keyValueForIndex. More... | |
DiscreteKeys | sorted_dkeys_ |
Sorted DiscreteKeys to use internally. More... | |
Testable | |
bool | equals (const DiscreteFactor &other, double tol=1e-9) const override |
equality More... | |
void | print (const std::string &s="TableFactor:\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print More... | |
Eigen::SparseVector< double > | sparseTable () const |
Getter for the underlying sparse vector. More... | |
double | evaluate (const Assignment< Key > &values) const override |
Evaluate probability distribution, is just look up in TableFactor. More... | |
double | error (const DiscreteValues &values) const override |
Calculate error for DiscreteValues x , is -log(probability). More... | |
TableFactor | operator* (const TableFactor &f) const |
multiply two TableFactors More... | |
DecisionTreeFactor | operator* (const DecisionTreeFactor &f) const override |
multiply with DecisionTreeFactor More... | |
virtual DiscreteFactor::shared_ptr | multiply (const DiscreteFactor::shared_ptr &f) const override |
Multiply factors, DiscreteFactor::shared_ptr edition. More... | |
TableFactor | operator/ (const TableFactor &f) const |
divide by factor f (safely) More... | |
DiscreteFactor::shared_ptr | operator/ (const DiscreteFactor::shared_ptr &f) const override |
divide by DiscreteFactor::shared_ptr f (safely) More... | |
DecisionTreeFactor | toDecisionTreeFactor () const override |
Convert into a decisiontree. More... | |
TableFactor | choose (const DiscreteValues assignments, DiscreteKeys parent_keys) const |
Create a TableFactor that is a subset of this TableFactor. 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... | |
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... | |
static double | safe_div (const double &a, const double &b) |
Additional Inherited Members | |
Protected Member Functions inherited from gtsam::Factor | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
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) |
A discrete probabilistic factor optimized for sparsity. Uses sparse_table_ to store only the nonzero probabilities. Computes the assigned value for the key using the ordering which the nonzero probabilties are stored in. (lazy cartesian product)
Definition at line 54 of file TableFactor.h.
typedef std::vector<std::pair<DiscreteValues, double> > gtsam::TableFactor::AssignValList |
Definition at line 107 of file TableFactor.h.
Typedef to base class.
Definition at line 104 of file TableFactor.h.
typedef std::shared_ptr<TableFactor> gtsam::TableFactor::shared_ptr |
Definition at line 105 of file TableFactor.h.
typedef Eigen::SparseVector<double>::InnerIterator gtsam::TableFactor::SparseIt |
Definition at line 106 of file TableFactor.h.
typedef TableFactor gtsam::TableFactor::This |
Definition at line 103 of file TableFactor.h.
gtsam::TableFactor::TableFactor | ( | ) |
Default constructor for I/O
Definition at line 32 of file TableFactor.cpp.
gtsam::TableFactor::TableFactor | ( | const DiscreteKeys & | keys, |
const TableFactor & | potentials | ||
) |
Constructor from DiscreteKeys and TableFactor
Definition at line 35 of file TableFactor.cpp.
gtsam::TableFactor::TableFactor | ( | const DiscreteKeys & | keys, |
const Eigen::SparseVector< double > & | table | ||
) |
Constructor from sparse_table
Definition at line 45 of file TableFactor.cpp.
|
inline |
Constructor from doubles
Definition at line 123 of file TableFactor.h.
|
inline |
Constructor from string
Definition at line 127 of file TableFactor.h.
|
inline |
Single-key specialization.
Definition at line 132 of file TableFactor.h.
|
inline |
Single-key specialization, with vector of doubles.
Definition at line 136 of file TableFactor.h.
gtsam::TableFactor::TableFactor | ( | const DiscreteKeys & | keys, |
const DecisionTreeFactor & | dtf | ||
) |
Constructor from DecisionTreeFactor.
Definition at line 156 of file TableFactor.cpp.
gtsam::TableFactor::TableFactor | ( | const DecisionTreeFactor & | dtf | ) |
Definition at line 161 of file TableFactor.cpp.
gtsam::TableFactor::TableFactor | ( | const DiscreteKeys & | keys, |
const DecisionTree< Key, double > & | dtree | ||
) |
Constructor from DecisionTree<Key, double>/AlgebraicDecisionTree.
Definition at line 60 of file TableFactor.cpp.
|
explicit |
Construct from a DiscreteConditional type
Definition at line 165 of file TableFactor.cpp.
TableFactor gtsam::TableFactor::apply | ( | const TableFactor & | f, |
Binary | op | ||
) | const |
Apply binary operator (*this) "op" f
f | the second argument for op |
op | a binary operator that operates on TableFactor |
Definition at line 432 of file TableFactor.cpp.
TableFactor gtsam::TableFactor::apply | ( | Unary | op | ) | const |
Apply unary operator op(*this)
where op
accepts the discrete value.
op | a unary operator that operates on TableFactor |
Definition at line 393 of file TableFactor.cpp.
TableFactor gtsam::TableFactor::apply | ( | UnaryAssignment | op | ) | const |
Apply unary operator op(*this)
where op
accepts the discrete assignment and the value at that assignment.
op | a unary operator that operates on TableFactor |
Definition at line 412 of file TableFactor.cpp.
TableFactor gtsam::TableFactor::choose | ( | const DiscreteValues | assignments, |
DiscreteKeys | parent_keys | ||
) | const |
Create a TableFactor that is a subset of this TableFactor.
Definition at line 322 of file TableFactor.cpp.
TableFactor::shared_ptr gtsam::TableFactor::combine | ( | const Ordering & | keys, |
Binary | op | ||
) | const |
Combine frontal variables in an Ordering using binary operator "op"
nrFrontals | nr. of frontal to combine variables in this factor |
op | a binary operator that operates on TableFactor |
Definition at line 597 of file TableFactor.cpp.
TableFactor::shared_ptr gtsam::TableFactor::combine | ( | size_t | nrFrontals, |
Binary | op | ||
) | const |
Combine frontal variables using binary operator "op"
nrFrontals | nr. of frontal to combine variables in this factor |
op | a binary operator that operates on TableFactor |
Definition at line 566 of file TableFactor.cpp.
DiscreteKeys gtsam::TableFactor::contractDkeys | ( | const TableFactor & | f | ) | const |
Return keys in contract mode.
Modes are each of the dimensions of a sparse tensor, and the contract modes represent which dimensions will be involved in contraction (aka tensor multiplication).
Definition at line 466 of file TableFactor.cpp.
|
staticprivate |
Convert probability table given as string to SparseVector.
Definition at line 195 of file TableFactor.cpp.
|
staticprivate |
Convert probability table given as doubles to SparseVector. Example: {0, 1, 1, 0, 0, 1, 0} -> values: {1, 1, 1}, indices: {1, 2, 5}
Definition at line 169 of file TableFactor.cpp.
unordered_map< uint64_t, TableFactor::AssignValList > gtsam::TableFactor::createMap | ( | const DiscreteKeys & | contract, |
const DiscreteKeys & | free | ||
) | const |
Create a hash map of input factor with assignment of contract modes as keys and vector of hashed assignment of free modes and value as values.
Definition at line 511 of file TableFactor.cpp.
|
inlineprivate |
Return ith key in keys_ as a DiscreteKey.
i | ith key in keys_ |
Definition at line 86 of file TableFactor.h.
std::vector< std::pair< DiscreteValues, double > > gtsam::TableFactor::enumerate | ( | ) | const |
Enumerate all values into a map from values to double.
Definition at line 638 of file TableFactor.cpp.
|
overridevirtual |
|
overridevirtual |
Calculate error for DiscreteValues x
, is -log(probability).
Reimplemented from gtsam::DiscreteFactor.
Definition at line 243 of file TableFactor.cpp.
|
overridevirtual |
Calculate error for HybridValues x
, is -log(probability) Simply dispatches to DiscreteValues version.
Reimplemented from gtsam::DiscreteFactor.
Definition at line 248 of file TableFactor.cpp.
|
overridevirtual |
Evaluate probability distribution, is just look up in TableFactor.
Implements gtsam::DiscreteFactor.
Definition at line 217 of file TableFactor.cpp.
DiscreteValues gtsam::TableFactor::findAssignments | ( | const uint64_t | idx | ) | const |
Find DiscreteValues for corresponding index.
Definition at line 557 of file TableFactor.cpp.
double gtsam::TableFactor::findValue | ( | const DiscreteValues & | values | ) | const |
Find value for corresponding DiscreteValues.
Definition at line 230 of file TableFactor.cpp.
DiscreteKeys gtsam::TableFactor::freeDkeys | ( | const TableFactor & | f | ) | const |
Return keys in free mode which are the dimensions not involved in the contraction operation.
Definition at line 476 of file TableFactor.cpp.
|
overridevirtual |
Render as html table.
keyFormatter | GTSAM-style Key formatter. |
names | optional, category names corresponding to choices. |
Implements gtsam::DiscreteFactor.
Definition at line 684 of file TableFactor.cpp.
Uses lazy cartesian product to find nth entry in the cartesian product of arrays in O(1) Example) v0 | v1 | val 0 | 0 | 10 0 | 1 | 21 1 | 0 | 32 1 | 1 | 43 keyValueForIndex(v1, 2) = 0.
target_key | nth entry's key to find out its assigned value |
index | nth entry in the sparse vector |
Definition at line 632 of file TableFactor.cpp.
|
overridevirtual |
Render as markdown table.
keyFormatter | GTSAM-style Key formatter. |
names | optional, category names corresponding to choices. |
Implements gtsam::DiscreteFactor.
Definition at line 654 of file TableFactor.cpp.
|
inlineoverridevirtual |
Create new factor by maximizing over all values with the same separator.
Implements gtsam::DiscreteFactor.
Definition at line 233 of file TableFactor.h.
|
inlineoverridevirtual |
Create new factor by maximizing over all values with the same separator.
Implements gtsam::DiscreteFactor.
Definition at line 228 of file TableFactor.h.
|
overridevirtual |
Multiply factors, DiscreteFactor::shared_ptr edition.
This method accepts DiscreteFactor::shared_ptr
and uses dynamic dispatch and specializations to perform the most efficient multiplication.
While converting a DecisionTreeFactor to a TableFactor is efficient, the reverse is not. Hence we specialize the code to return a TableFactor always.
f | The factor to multiply with. |
Implements gtsam::DiscreteFactor.
Definition at line 258 of file TableFactor.cpp.
|
inlineoverridevirtual |
Get the number of non-zero values contained in this factor. It could be much smaller than prod_{key}(cardinality(key))
.
Implements gtsam::DiscreteFactor.
Definition at line 342 of file TableFactor.h.
|
overridevirtual |
multiply with DecisionTreeFactor
Implements gtsam::DiscreteFactor.
Definition at line 253 of file TableFactor.cpp.
|
inline |
multiply two TableFactors
Definition at line 175 of file TableFactor.h.
|
overridevirtual |
divide by DiscreteFactor::shared_ptr f (safely)
Implements gtsam::DiscreteFactor.
Definition at line 284 of file TableFactor.cpp.
|
inline |
divide by factor f (safely)
Definition at line 202 of file TableFactor.h.
|
overridevirtual |
TableFactor gtsam::TableFactor::prune | ( | size_t | maxNrAssignments | ) | const |
Prune the decision tree of discrete variables.
Pruning will set the values to be "pruned" to 0 indicating a 0 probability. An assignment is pruned if it is not in the top maxNrAssignments
values.
A violation can occur if there are more duplicate values than maxNrAssignments
. A violation here is the need to un-prune the decision tree (e.g. all assignment values are 1.0). We could have another case where some subset of duplicates exist (e.g. for a tree with 8 assignments we have 1, 1, 1, 1, 0.8, 0.7, 0.6, 0.5), but this is not a violation since the for maxNrAssignments=5
the top values are (1, 0.8).
maxNrAssignments | The maximum number of assignments to keep. |
Definition at line 717 of file TableFactor.cpp.
|
static |
Definition at line 367 of file TableFactor.cpp.
|
inline |
Getter for the underlying sparse vector.
Definition at line 166 of file TableFactor.h.
|
inlineoverridevirtual |
Create new factor by summing all values with the same separator values.
Implements gtsam::DiscreteFactor.
Definition at line 223 of file TableFactor.h.
|
inlineoverridevirtual |
Create new factor by summing all values with the same separator values.
Implements gtsam::DiscreteFactor.
Definition at line 218 of file TableFactor.h.
|
overridevirtual |
Convert into a decisiontree.
Implements gtsam::DiscreteFactor.
Definition at line 298 of file TableFactor.cpp.
DiscreteKeys gtsam::TableFactor::unionDkeys | ( | const TableFactor & | f | ) | const |
Return union of DiscreteKeys in two factors.
Definition at line 486 of file TableFactor.cpp.
uint64_t gtsam::TableFactor::unionRep | ( | const DiscreteKeys & | keys, |
const DiscreteValues & | assign, | ||
const uint64_t | idx | ||
) | const |
Create unique representation of union modes.
Definition at line 495 of file TableFactor.cpp.
uint64_t gtsam::TableFactor::uniqueRep | ( | const DiscreteKeys & | keys, |
const uint64_t | idx | ||
) | const |
Create unique representation.
Definition at line 534 of file TableFactor.cpp.
uint64_t gtsam::TableFactor::uniqueRep | ( | const DiscreteValues & | assignments | ) | const |
Create unique representation with DiscreteValues.
Definition at line 546 of file TableFactor.cpp.
Map of Keys and their denominators used in keyValueForIndex.
Definition at line 61 of file TableFactor.h.
|
private |
Sorted DiscreteKeys to use internally.
Definition at line 63 of file TableFactor.h.
|
protected |
SparseVector of nonzero probabilities.
Definition at line 57 of file TableFactor.h.