24 #include <Eigen/Sparse> 72 size_t keyValueForIndex(
Key target_key,
uint64_t index)
const;
80 return DiscreteKey(keys_[i], cardinalities_.at(keys_[i]));
97 using Binary = std::function<double(const double, const double)>;
102 static inline double zero() {
return 0.0; }
103 static inline double one() {
return 1.0; }
104 static inline double add(
const double&
a,
const double&
b) {
return a +
b; }
105 static inline double max(
const double&
a,
const double&
b) {
108 static inline double mul(
const double&
a,
const double&
b) {
return a *
b; }
109 static inline double div(
const double&
a,
const double&
b) {
110 return (a == 0 || b == 0) ? 0 : (a /
b);
112 static inline double id(
const double&
x) {
return x; }
137 template <
class SOURCE>
154 const std::string&
s =
"TableFactor:\n",
181 static double safe_div(
const double&
a,
const double&
b);
187 return apply(f, safe_div);
198 shared_ptr
sum(
size_t nrFrontals)
const {
208 shared_ptr
max(
size_t nrFrontals)
const {
243 std::unordered_map<uint64_t, AssignValList> createMap(
264 shared_ptr combine(
size_t nrFrontals,
Binary op)
const;
275 std::vector<std::pair<DiscreteValues, double>> enumerate()
const;
void print(const Matrix &A, const string &s, ostream &stream)
const gtsam::Symbol key('X', 0)
static double mul(const double &a, const double &b)
shared_ptr max(size_t nrFrontals) const
Create new factor by maximizing over all values with the same separator.
std::map< Key, size_t > denominators_
Map of Keys and their denominators used in keyValueForIndex.
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
static int mul(const int &a, const int &b)
shared_ptr max(const Ordering &keys) const
Create new factor by maximizing over all values with the same separator.
DecisionTree< L, Y > apply(const DecisionTree< L, Y > &f, const typename DecisionTree< L, Y >::Unary &op)
Apply unary operator op to DecisionTree f.
static const T & choose(int layout, const T &col, const T &row)
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Eigen::SparseVector< double >::InnerIterator SparseIt
TableFactor(const DiscreteKeys &keys, const std::string &table)
static double max(const double &a, const double &b)
double evaluate(const DiscreteValues &values) const
std::shared_ptr< TableFactor > shared_ptr
Point2 operator*(double s, const Point2 &p)
multiply with scalar
static const KeyFormatter DefaultKeyFormatter
DiscreteKeys sorted_dkeys_
Sorted DiscreteKeys to use internally.
shared_ptr sum(const Ordering &keys) const
Create new factor by summing all values with the same separator values.
const KeyFormatter & formatter
DiscreteFactor Base
Typedef to base class.
std::map< Key, size_t > cardinalities_
Map of Keys and their cardinalities.
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
TableFactor(const DiscreteKeys &keys, const std::vector< double > &table)
size_t cardinality(Key j) const
TableFactor operator/(const TableFactor &f) const
divide by factor f (safely)
TableFactor(const DiscreteKey &key, const std::vector< double > &row)
Single-key specialization, with vector of doubles.
Eigen::SparseVector< double > sparse_table_
SparseVector of nonzero probabilities.
static double id(const double &x)
unsigned __int64 uint64_t
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static double div(const double &a, const double &b)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::function< double(const double, const double)> Binary
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
DiscreteValues::Names Names
Translation table from values to strings.
TableFactor(const DiscreteKey &key, SOURCE table)
Single-key specialization.
specialized key for discrete variables
static int add(const int &a, const int &b)
std::vector< std::pair< DiscreteValues, double > > AssignValList
TableFactor operator*(const TableFactor &f) const
multiply two TableFactors
static double add(const double &a, const double &b)
std::pair< Key, size_t > DiscreteKey
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
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
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::uint64_t Key
Integer nonlinear key type.
DiscreteKey discreteKey(size_t i) const
Return ith key in keys_ as a DiscreteKey.
DiscreteKeys is a set of keys that can be assembled using the & operator.