35 class DiscreteFactorGraph;
36 class DiscreteConditional;
37 class DiscreteBayesNet;
38 class DiscreteEliminationTree;
39 class DiscreteBayesTree;
40 class DiscreteJunctionTree;
63 static std::pair<std::shared_ptr<ConditionalType>,
65 std::shared_ptr<FactorType> >
71 const FactorGraphType&
graph,
72 std::optional<std::reference_wrapper<const VariableIndex>> variableIndex) {
101 template <
typename ITERATOR>
103 :
Base(firstFactor, lastFactor) {}
106 template <
class CONTAINER>
111 template <
class DERIVEDFACTOR>
122 template <
typename... Args>
124 emplace_shared<DecisionTreeFactor>(std::forward<Args>(
args)...);
144 const std::string&
s =
"DiscreteFactorGraph",
154 OptionalOrderingType orderingType = {})
const;
171 OptionalOrderingType orderingType = {})
const;
188 OptionalOrderingType orderingType = {})
const;
230 std::pair<DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr>
void print(const Matrix &A, const string &s, ostream &stream)
DiscreteFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
DiscreteEliminationTree EliminationTreeType
Type of elimination tree.
Variable elimination algorithms for factor graphs.
A Bayes tree representing a Discrete distribution.
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
const GaussianFactorGraph factors
DiscreteFactor FactorType
Type of factors in factor graph.
DiscreteJunctionTree JunctionTreeType
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
static enum @1107 ordering
void add(Args &&... args)
const KeyFormatter & formatter
static Ordering Colamd(const FACTOR_GRAPH &graph)
DiscreteBayesNet BayesNetType
Type of Bayes net from sequential elimination.
std::shared_ptr< This > shared_ptr
shared_ptr to This
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
DiscreteFactorGraph FactorGraphType
Type of the factor graph (e.g. DiscreteFactorGraph)
static std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< FactorType > > DefaultEliminate(const FactorGraphType &factors, const Ordering &keys)
The default dense elimination function.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
static Ordering DefaultOrderingFunc(const FactorGraphType &graph, std::optional< std::reference_wrapper< const VariableIndex >> variableIndex)
The default ordering generation function.
DiscreteFactorGraph()
map from keys to values
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
DiscreteFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph)
DiscreteValues::Names Names
Translation table from values to strings.
std::shared_ptr< DecisionTreeFactor > shared_ptr
DiscreteConditional ConditionalType
Type of conditionals from elimination.
Elimination tree for discrete factors.
DiscreteFactorGraph(const CONTAINER &factors)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateForMPE(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
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
A thin wrapper around std::set that uses boost's fast_pool_allocator.
void product(const MatrixType &m)
DiscreteBayesTree BayesTreeType
Type of Bayes tree.
DiscreteKeys is a set of keys that can be assembled using the & operator.