Go to the documentation of this file.
24 #include <Eigen/Sparse>
35 class DiscreteConditional;
71 size_t keyValueForIndex(
Key target_key,
uint64_t index)
const;
96 using Unary = std::function<double(
const double&)>;
99 using Binary = std::function<double(
const double,
const double)>;
104 static inline double zero() {
return 0.0; }
105 static inline double one() {
return 1.0; }
106 static inline double add(
const double&
a,
const double&
b) {
return a +
b; }
107 static inline double max(
const double&
a,
const double&
b) {
110 static inline double mul(
const double&
a,
const double&
b) {
return a *
b; }
111 static inline double div(
const double&
a,
const double&
b) {
112 return (
a == 0 ||
b == 0) ? 0 : (
a /
b);
114 static inline double id(
const double&
x) {
return x; }
139 template <
class SOURCE>
148 TableFactor(
const DiscreteKeys&
keys,
const DecisionTreeFactor& dtf);
151 TableFactor(
const DiscreteKeys&
keys,
const DecisionTree<Key, double>& dtree);
154 explicit TableFactor(
const DiscreteConditional&
c);
165 const std::string&
s =
"TableFactor:\n",
192 static double safe_div(
const double&
a,
const double&
b);
196 return apply(
f, safe_div);
273 std::unordered_map<uint64_t, AssignValList> createMap(
294 shared_ptr combine(
size_t nrFrontals, Binary op)
const;
302 shared_ptr combine(
const Ordering&
keys, Binary op)
const;
305 std::vector<std::pair<DiscreteValues, double>> enumerate()
const;
339 const Names&
names = {})
const override;
349 const Names&
names = {})
const override;
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
shared_ptr max(size_t nrFrontals) const
Create new factor by maximizing over all values with the same separator.
static double max(const double &a, const double &b)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TableFactor operator/(const TableFactor &f) const
divide by factor f (safely)
Eigen::SparseVector< double > sparse_table_
SparseVector of nonzero probabilities.
TableFactor(const DiscreteKeys &keys, const std::vector< double > &table)
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
const KeyFormatter & formatter
Variable ordering for the elimination algorithm.
DiscreteKeys is a set of keys that can be assembled using the & operator.
DiscreteFactor Base
Typedef to base class.
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Point2 operator*(double s, const Point2 &p)
multiply with scalar
TableFactor(const DiscreteKeys &keys, const std::string &table)
static double id(const double &x)
void print(const Matrix &A, const string &s, ostream &stream)
DiscreteKeys sorted_dkeys_
Sorted DiscreteKeys to use internally.
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
TableFactor(const DiscreteKey &key, SOURCE table)
Single-key specialization.
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
std::vector< std::pair< DiscreteValues, double > > AssignValList
static int add(const int &a, const int &b)
static double div(const double &a, const double &b)
shared_ptr max(const Ordering &keys) const
Create new factor by maximizing over all values with the same separator.
TableFactor(const DiscreteKey &key, const std::vector< double > &row)
Single-key specialization, with vector of doubles.
shared_ptr sum(const Ordering &keys) const
Create new factor by summing all values with the same separator values.
specialized key for discrete variables
const gtsam::Symbol key('X', 0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
std::function< double(const double, const double)> Binary
std::function< double(const double &)> Unary
std::function< double(const Assignment< Key > &, const double &)> UnaryAssignment
TableFactor operator*(const TableFactor &f) const
multiply two TableFactors
std::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
std::pair< Key, size_t > DiscreteKey
std::map< Key, size_t > denominators_
Map of Keys and their denominators used in keyValueForIndex.
double evaluate(const DiscreteValues &values) const
DecisionTree< L, Y > apply(const DecisionTree< L, Y > &f, const typename DecisionTree< L, Y >::Unary &op)
Apply unary operator op to DecisionTree f.
Eigen::SparseVector< double >::InnerIterator SparseIt
DiscreteKey discreteKey(size_t i) const
Return ith key in keys_ as a DiscreteKey.
unsigned __int64 uint64_t
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
static double mul(const double &a, const double &b)
std::uint64_t Key
Integer nonlinear key type.
static const T & choose(int layout, const T &col, const T &row)
static double add(const double &a, const double &b)
std::shared_ptr< TableFactor > shared_ptr
static int mul(const int &a, const int &b)
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:36:55