Public Types | Public Member Functions | List of all members
gtsam::DiscreteFactorGraph Class Reference

#include <DiscreteFactorGraph.h>

Inheritance diagram for gtsam::DiscreteFactorGraph:
Inheritance graph
[legend]

Public Types

using Base = FactorGraph< DiscreteFactor >
 base factor graph type More...
 
using BaseEliminateable = EliminateableFactorGraph< This >
 for elimination More...
 
using Indices = KeyVector
 
using shared_ptr = std::shared_ptr< This >
 shared_ptr to This More...
 
using This = DiscreteFactorGraph
 this class More...
 
using Values = DiscreteValues
 backwards compatibility More...
 
- Public Types inherited from gtsam::FactorGraph< DiscreteFactor >
typedef FastVector< sharedFactor >::const_iterator const_iterator
 
typedef DiscreteFactor FactorType
 factor type More...
 
typedef FastVector< sharedFactor >::iterator iterator
 
typedef std::shared_ptr< DiscreteFactorsharedFactor
 Shared pointer to a factor. More...
 
typedef sharedFactor value_type
 
- Public Types inherited from gtsam::EliminateableFactorGraph< DiscreteFactorGraph >
typedef EliminationTraitsType::BayesNetType BayesNetType
 Bayes net type produced by sequential elimination. More...
 
typedef EliminationTraitsType::BayesTreeType BayesTreeType
 Bayes tree type produced by multifrontal elimination. More...
 
typedef EliminationTraitsType::ConditionalType ConditionalType
 Conditional type stored in the Bayes net produced by elimination. More...
 
typedef std::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
 The function type that does a single dense elimination step on a subgraph. More...
 
typedef std::pair< std::shared_ptr< ConditionalType >, std::shared_ptr< _FactorType > > EliminationResult
 
typedef EliminationTraits< FactorGraphTypeEliminationTraitsType
 Typedef to the specific EliminationTraits for this graph. More...
 
typedef EliminationTraitsType::EliminationTreeType EliminationTreeType
 Elimination tree type that can do sequential elimination of this graph. More...
 
typedef EliminationTraitsType::JunctionTreeType JunctionTreeType
 Junction tree type that can do multifrontal elimination of this graph. More...
 
typedef std::optional< Ordering::OrderingTypeOptionalOrderingType
 Typedef for an optional ordering type. More...
 
typedef std::optional< std::reference_wrapper< const VariableIndex > > OptionalVariableIndex
 

Public Member Functions

template<typename... Args>
void add (Args &&... args)
 
 DiscreteFactorGraph ()
 

map from keys to values

More...
 
template<typename ITERATOR >
 DiscreteFactorGraph (ITERATOR firstFactor, ITERATOR lastFactor)
 
template<class CONTAINER >
 DiscreteFactorGraph (const CONTAINER &factors)
 
template<class DERIVEDFACTOR >
 DiscreteFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph)
 
DiscreteKeys discreteKeys () const
 Return the DiscreteKeys in this factor graph. More...
 
KeySet keys () const
 
DiscreteLookupDAG maxProduct (OptionalOrderingType orderingType={}) const
 Implement the max-product algorithm. More...
 
DiscreteLookupDAG maxProduct (const Ordering &ordering) const
 Implement the max-product algorithm. More...
 
double operator() (const DiscreteValues &values) const
 
DiscreteValues optimize (OptionalOrderingType orderingType={}) const
 Find the maximum probable explanation (MPE) by doing max-product. More...
 
DiscreteValues optimize (const Ordering &ordering) const
 Find the maximum probable explanation (MPE) by doing max-product. More...
 
void print (const std::string &s="DiscreteFactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 print More...
 
DecisionTreeFactor product () const
 
DiscreteBayesNet sumProduct (OptionalOrderingType orderingType={}) const
 Implement the sum-product algorithm. More...
 
DiscreteBayesNet sumProduct (const Ordering &ordering) const
 Implement the sum-product algorithm. More...
 
Testable
bool equals (const This &fg, double tol=1e-9) const
 
Wrapper support
std::string markdown (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DiscreteFactor::Names &names={}) const
 Render as markdown tables. More...
 
std::string html (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DiscreteFactor::Names &names={}) const
 Render as html tables. More...
 
- Public Member Functions inherited from gtsam::FactorGraph< DiscreteFactor >
 FactorGraph (std::initializer_list< std::shared_ptr< DERIVEDFACTOR >> sharedFactors)
 
virtual ~FactorGraph ()=default
 
void reserve (size_t size)
 
IsDerived< DERIVEDFACTOR > push_back (std::shared_ptr< DERIVEDFACTOR > factor)
 Add a factor directly using a shared_ptr. More...
 
IsDerived< DERIVEDFACTOR > push_back (const DERIVEDFACTOR &factor)
 
IsDerived< DERIVEDFACTOR > emplace_shared (Args &&... args)
 Emplace a shared pointer to factor of given type. More...
 
IsDerived< DERIVEDFACTOR > add (std::shared_ptr< DERIVEDFACTOR > factor)
 add is a synonym for push_back. More...
 
HasDerivedElementType< ITERATOR > push_back (ITERATOR firstFactor, ITERATOR lastFactor)
 
HasDerivedValueType< ITERATOR > push_back (ITERATOR firstFactor, ITERATOR lastFactor)
 Push back many factors with an iterator (factors are copied) More...
 
HasDerivedElementType< CONTAINER > push_back (const CONTAINER &container)
 
HasDerivedValueType< CONTAINER > push_back (const CONTAINER &container)
 Push back non-pointer objects in a container (factors are copied). More...
 
void add (const FACTOR_OR_CONTAINER &factorOrContainer)
 
std::enable_if< std::is_base_of< This, typename CLIQUE::FactorGraphType >::value >::type push_back (const BayesTree< CLIQUE > &bayesTree)
 
FactorIndices add_factors (const CONTAINER &factors, bool useEmptySlots=false)
 
bool equals (const This &fg, double tol=1e-9) const
 Check equality up to tolerance. More...
 
size_t size () const
 
bool empty () const
 
const sharedFactor at (size_t i) const
 
sharedFactorat (size_t i)
 
const sharedFactor operator[] (size_t i) const
 
sharedFactoroperator[] (size_t i)
 
const_iterator begin () const
 
const_iterator end () const
 
sharedFactor front () const
 
sharedFactor back () const
 
double error (const HybridValues &values) const
 
iterator begin ()
 
iterator end ()
 
virtual void resize (size_t size)
 
void remove (size_t i)
 
void replace (size_t index, sharedFactor factor)
 
iterator erase (iterator item)
 
iterator erase (iterator first, iterator last)
 
void dot (std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 Output to graphviz format, stream version. More...
 
std::string dot (const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 Output to graphviz format string. More...
 
void saveGraph (const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const DotWriter &writer=DotWriter()) const
 output to file with graphviz format. More...
 
size_t nrFactors () const
 
KeySet keys () const
 
KeyVector keyVector () const
 
bool exists (size_t idx) const
 
- Public Member Functions inherited from gtsam::EliminateableFactorGraph< DiscreteFactorGraph >
std::shared_ptr< BayesTreeTypeeliminateMultifrontal (OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesTreeTypeeliminateMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::pair< std::shared_ptr< BayesNetType >, std::shared_ptr< FactorGraphType > > eliminatePartialSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::pair< std::shared_ptr< BayesNetType >, std::shared_ptr< FactorGraphType > > eliminatePartialSequential (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesNetTypeeliminateSequential (OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesNetTypeeliminateSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< FactorGraphTypemarginal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (const Ordering &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (const Ordering &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (const KeyVector &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (const Ordering &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (const Ordering &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 
std::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (const KeyVector &variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
 

Additional Inherited Members

- Protected Member Functions inherited from gtsam::FactorGraph< DiscreteFactor >
bool isEqual (const FactorGraph &other) const
 Check exact equality of the factor pointers. Useful for derived ==. More...
 
 FactorGraph ()
 
 FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor)
 
 FactorGraph (const CONTAINER &factors)
 
- Protected Attributes inherited from gtsam::FactorGraph< DiscreteFactor >
FastVector< sharedFactorfactors_
 

Detailed Description

A Discrete Factor Graph is a factor graph where all factors are Discrete, i.e. Factor == DiscreteFactor

Definition at line 83 of file DiscreteFactorGraph.h.

Member Typedef Documentation

◆ Base

base factor graph type

Definition at line 88 of file DiscreteFactorGraph.h.

◆ BaseEliminateable

for elimination

Definition at line 90 of file DiscreteFactorGraph.h.

◆ Indices

Definition at line 95 of file DiscreteFactorGraph.h.

◆ shared_ptr

using gtsam::DiscreteFactorGraph::shared_ptr = std::shared_ptr<This>

shared_ptr to This

Definition at line 91 of file DiscreteFactorGraph.h.

◆ This

this class

Definition at line 87 of file DiscreteFactorGraph.h.

◆ Values

backwards compatibility

Definition at line 93 of file DiscreteFactorGraph.h.

Constructor & Destructor Documentation

◆ DiscreteFactorGraph() [1/4]

gtsam::DiscreteFactorGraph::DiscreteFactorGraph ( )
inline

map from keys to values

Default constructor

Definition at line 98 of file DiscreteFactorGraph.h.

◆ DiscreteFactorGraph() [2/4]

template<typename ITERATOR >
gtsam::DiscreteFactorGraph::DiscreteFactorGraph ( ITERATOR  firstFactor,
ITERATOR  lastFactor 
)
inline

Construct from iterator over factors

Definition at line 102 of file DiscreteFactorGraph.h.

◆ DiscreteFactorGraph() [3/4]

template<class CONTAINER >
gtsam::DiscreteFactorGraph::DiscreteFactorGraph ( const CONTAINER &  factors)
inlineexplicit

Construct from container of factors (shared_ptr or plain objects)

Definition at line 107 of file DiscreteFactorGraph.h.

◆ DiscreteFactorGraph() [4/4]

template<class DERIVEDFACTOR >
gtsam::DiscreteFactorGraph::DiscreteFactorGraph ( const FactorGraph< DERIVEDFACTOR > &  graph)
inline

Implicit copy/downcast constructor to override explicit template container constructor

Definition at line 112 of file DiscreteFactorGraph.h.

Member Function Documentation

◆ add()

template<typename... Args>
void gtsam::DiscreteFactorGraph::add ( Args &&...  args)
inline

Add a decision-tree factor

Definition at line 123 of file DiscreteFactorGraph.h.

◆ discreteKeys()

DiscreteKeys gtsam::DiscreteFactorGraph::discreteKeys ( ) const

Return the DiscreteKeys in this factor graph.

Definition at line 54 of file DiscreteFactorGraph.cpp.

◆ equals()

bool gtsam::DiscreteFactorGraph::equals ( const This fg,
double  tol = 1e-9 
) const

Definition at line 39 of file DiscreteFactorGraph.cpp.

◆ html()

string gtsam::DiscreteFactorGraph::html ( const KeyFormatter keyFormatter = DefaultKeyFormatter,
const DiscreteFactor::Names names = {} 
) const

Render as html tables.

Parameters
keyFormatterGTSAM-style Key formatter.
namesoptional, a map from Key to category names.
Returns
std::string a (potentially long) html string.

Definition at line 255 of file DiscreteFactorGraph.cpp.

◆ keys()

KeySet gtsam::DiscreteFactorGraph::keys ( ) const

Return the set of variables involved in the factors (set union)

Definition at line 45 of file DiscreteFactorGraph.cpp.

◆ markdown()

string gtsam::DiscreteFactorGraph::markdown ( const KeyFormatter keyFormatter = DefaultKeyFormatter,
const DiscreteFactor::Names names = {} 
) const

Render as markdown tables.

Parameters
keyFormatterGTSAM-style Key formatter.
namesoptional, a map from Key to category names.
Returns
std::string a (potentially long) markdown string.

Definition at line 241 of file DiscreteFactorGraph.cpp.

◆ maxProduct() [1/2]

DiscreteLookupDAG gtsam::DiscreteFactorGraph::maxProduct ( OptionalOrderingType  orderingType = {}) const

Implement the max-product algorithm.

Parameters
orderingType: one of COLAMD, METIS, NATURAL, CUSTOM
Returns
DiscreteLookupDAG DAG with lookup tables

Definition at line 174 of file DiscreteFactorGraph.cpp.

◆ maxProduct() [2/2]

DiscreteLookupDAG gtsam::DiscreteFactorGraph::maxProduct ( const Ordering ordering) const

Implement the max-product algorithm.

Parameters
ordering
Returns
DiscreteLookupDAG `DAG with lookup tables

Definition at line 181 of file DiscreteFactorGraph.cpp.

◆ operator()()

double gtsam::DiscreteFactorGraph::operator() ( const DiscreteValues values) const

Evaluates the factor graph given values, returns the joint probability of the factor graph given specific instantiation of values

Definition at line 75 of file DiscreteFactorGraph.cpp.

◆ optimize() [1/2]

DiscreteValues gtsam::DiscreteFactorGraph::optimize ( OptionalOrderingType  orderingType = {}) const

Find the maximum probable explanation (MPE) by doing max-product.

Parameters
orderingType
Returns
DiscreteValues : MPE

Definition at line 189 of file DiscreteFactorGraph.cpp.

◆ optimize() [2/2]

DiscreteValues gtsam::DiscreteFactorGraph::optimize ( const Ordering ordering) const

Find the maximum probable explanation (MPE) by doing max-product.

Parameters
ordering
Returns
DiscreteValues : MPE

Definition at line 196 of file DiscreteFactorGraph.cpp.

◆ print()

void gtsam::DiscreteFactorGraph::print ( const std::string &  s = "DiscreteFactorGraph",
const KeyFormatter formatter = DefaultKeyFormatter 
) const
overridevirtual

print

Reimplemented from gtsam::FactorGraph< DiscreteFactor >.

Reimplemented in gtsam::Scheduler.

Definition at line 84 of file DiscreteFactorGraph.cpp.

◆ product()

DecisionTreeFactor gtsam::DiscreteFactorGraph::product ( ) const

return product of all factors as a single factor

Definition at line 67 of file DiscreteFactorGraph.cpp.

◆ sumProduct() [1/2]

DiscreteBayesNet gtsam::DiscreteFactorGraph::sumProduct ( OptionalOrderingType  orderingType = {}) const

Implement the sum-product algorithm.

Parameters
orderingType: one of COLAMD, METIS, NATURAL, CUSTOM
Returns
DiscreteBayesNet encoding posterior P(X|Z)

Definition at line 154 of file DiscreteFactorGraph.cpp.

◆ sumProduct() [2/2]

DiscreteBayesNet gtsam::DiscreteFactorGraph::sumProduct ( const Ordering ordering) const

Implement the sum-product algorithm.

Parameters
ordering
Returns
DiscreteBayesNet encoding posterior P(X|Z)

Definition at line 161 of file DiscreteFactorGraph.cpp.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:17