#include <DiscreteFactorGraph.h>
Public Types | |
typedef FactorGraph< DiscreteFactor > | Base |
Typedef to base factor graph type. More... | |
typedef EliminateableFactorGraph< This > | BaseEliminateable |
Typedef to base elimination class. More... | |
typedef KeyVector | Indices |
typedef boost::shared_ptr< This > | shared_ptr |
shared_ptr to this class More... | |
typedef boost::shared_ptr< Values > | sharedValues |
typedef DiscreteFactorGraph | This |
Typedef to this class. More... | |
typedef Assignment< Key > | Values |
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 boost::shared_ptr< DiscreteFactor > | sharedFactor |
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 boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> | Eliminate |
The function type that does a single dense elimination step on a subgraph. More... | |
typedef std::pair< boost::shared_ptr< ConditionalType >, boost::shared_ptr< _FactorType > > | EliminationResult |
typedef EliminationTraits< FactorGraphType > | EliminationTraitsType |
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 boost::optional< Ordering::OrderingType > | OptionalOrderingType |
Typedef for an optional ordering type. More... | |
typedef boost::optional< const VariableIndex & > | OptionalVariableIndex |
Typedef for an optional variable index as an argument to elimination functions. More... | |
Public Member Functions | |
template<class SOURCE > | |
void | add (const DiscreteKey &j, SOURCE table) |
template<class SOURCE > | |
void | add (const DiscreteKey &j1, const DiscreteKey &j2, SOURCE table) |
template<class SOURCE > | |
void | add (const DiscreteKeys &keys, SOURCE table) |
DiscreteFactorGraph () | |
template<typename ITERATOR > | |
DiscreteFactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
template<class CONTAINER > | |
DiscreteFactorGraph (const CONTAINER &factors) | |
template<class DERIVEDFACTOR > | |
DiscreteFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph) | |
KeySet | keys () const |
double | operator() (const DiscreteFactor::Values &values) const |
DiscreteFactor::sharedValues | optimize () const |
void | print (const std::string &s="DiscreteFactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const override |
print More... | |
DecisionTreeFactor | product () const |
virtual | ~DiscreteFactorGraph () |
Destructor. More... | |
Testable | |
bool | equals (const This &fg, double tol=1e-9) const |
Public Member Functions inherited from gtsam::FactorGraph< DiscreteFactor > | |
virtual | ~FactorGraph ()=default |
Default destructor. More... | |
void | reserve (size_t size) |
IsDerived< DERIVEDFACTOR > | push_back (boost::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 (boost::shared_ptr< DERIVEDFACTOR > factor) |
add is a synonym for push_back. More... | |
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, boost::assign::list_inserter< RefCallPushBack< This > > >::type | operator+= (boost::shared_ptr< DERIVEDFACTOR > factor) |
+= works well with boost::assign list inserter. 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) |
boost::assign::list_inserter< CRefCallPushBack< This > > | operator+= (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 |
size_t | size () const |
bool | empty () const |
const sharedFactor | at (size_t i) const |
sharedFactor & | at (size_t i) |
const sharedFactor | operator[] (size_t i) const |
sharedFactor & | operator[] (size_t i) |
const_iterator | begin () const |
const_iterator | end () const |
sharedFactor | front () const |
sharedFactor | back () const |
iterator | begin () |
iterator | end () |
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) |
size_t | nrFactors () const |
KeySet | keys () const |
KeyVector | keyVector () const |
bool | exists (size_t idx) const |
Public Member Functions inherited from gtsam::EliminateableFactorGraph< DiscreteFactorGraph > | |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (const Ordering &ordering, const Eliminate &function, OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const |
boost::shared_ptr< BayesTreeType > | eliminateMultifrontal (const Eliminate &function, OptionalVariableIndex variableIndex=boost::none, OptionalOrderingType orderingType=boost::none) const |
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialMultifrontal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > | eliminatePartialSequential (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (const Ordering &ordering, const Eliminate &function, OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const |
boost::shared_ptr< BayesNetType > | eliminateSequential (const Eliminate &function, OptionalVariableIndex variableIndex=boost::none, OptionalOrderingType orderingType=boost::none) const |
boost::shared_ptr< FactorGraphType > | marginal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | marginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | marginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesNetType > | marginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | marginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | marginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
boost::shared_ptr< BayesTreeType > | marginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const |
Additional Inherited Members | |
Protected Member Functions inherited from gtsam::FactorGraph< DiscreteFactor > | |
FactorGraph () | |
FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor) | |
FactorGraph (const CONTAINER &factors) | |
Protected Attributes inherited from gtsam::FactorGraph< DiscreteFactor > | |
FastVector< sharedFactor > | factors_ |
A Discrete Factor Graph is a factor graph where all factors are Discrete, i.e. Factor == DiscreteFactor
Definition at line 65 of file DiscreteFactorGraph.h.
Typedef to base factor graph type.
Definition at line 70 of file DiscreteFactorGraph.h.
Typedef to base elimination class.
Definition at line 71 of file DiscreteFactorGraph.h.
A map from keys to values
Definition at line 75 of file DiscreteFactorGraph.h.
typedef boost::shared_ptr<This> gtsam::DiscreteFactorGraph::shared_ptr |
shared_ptr to this class
Definition at line 72 of file DiscreteFactorGraph.h.
typedef boost::shared_ptr<Values> gtsam::DiscreteFactorGraph::sharedValues |
Definition at line 77 of file DiscreteFactorGraph.h.
Typedef to this class.
Definition at line 69 of file DiscreteFactorGraph.h.
Definition at line 76 of file DiscreteFactorGraph.h.
|
inline |
Default constructor
Definition at line 80 of file DiscreteFactorGraph.h.
|
inline |
Construct from iterator over factors
Definition at line 84 of file DiscreteFactorGraph.h.
|
inlineexplicit |
Construct from container of factors (shared_ptr or plain objects)
Definition at line 88 of file DiscreteFactorGraph.h.
|
inline |
Implicit copy/downcast constructor to override explicit template container constructor
Definition at line 92 of file DiscreteFactorGraph.h.
|
inlinevirtual |
Destructor.
Definition at line 95 of file DiscreteFactorGraph.h.
|
inline |
Definition at line 105 of file DiscreteFactorGraph.h.
|
inline |
Definition at line 112 of file DiscreteFactorGraph.h.
|
inline |
add shared discreteFactor immediately from arguments
Definition at line 121 of file DiscreteFactorGraph.h.
bool gtsam::DiscreteFactorGraph::equals | ( | const This & | fg, |
double | tol = 1e-9 |
||
) | const |
Definition at line 36 of file DiscreteFactorGraph.cpp.
KeySet gtsam::DiscreteFactorGraph::keys | ( | ) | const |
Return the set of variables involved in the factors (set union)
Definition at line 42 of file DiscreteFactorGraph.cpp.
double gtsam::DiscreteFactorGraph::operator() | ( | const DiscreteFactor::Values & | values | ) | const |
Evaluates the factor graph given values, returns the joint probability of the factor graph given specific instantiation of values
Definition at line 58 of file DiscreteFactorGraph.cpp.
DiscreteFactor::sharedValues gtsam::DiscreteFactorGraph::optimize | ( | ) | const |
Solve the factor graph by performing variable elimination in COLAMD order using the dense elimination function specified in function
, followed by back-substitution resulting from elimination. Is equivalent to calling graph.eliminateSequential()->optimize().
Definition at line 97 of file DiscreteFactorGraph.cpp.
|
overridevirtual |
Reimplemented from gtsam::FactorGraph< DiscreteFactor >.
Reimplemented in gtsam::Scheduler.
Definition at line 67 of file DiscreteFactorGraph.cpp.
DecisionTreeFactor gtsam::DiscreteFactorGraph::product | ( | ) | const |
return product of all factors as a single factor
Definition at line 50 of file DiscreteFactorGraph.cpp.