Public Types | Protected Types | List of all members
gtsam::HybridGaussianFactorGraph Class Reference

#include <HybridGaussianFactorGraph.h>

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

Public Types

using Base = HybridFactorGraph
 
using BaseEliminateable = EliminateableFactorGraph< This >
 for elimination More...
 
using Indices = KeyVector
 map from keys to values More...
 
using shared_ptr = std::shared_ptr< This >
 shared_ptr to This More...
 
using This = HybridGaussianFactorGraph
 this class More...
 
using Values = gtsam::Values
 backwards compatibility More...
 
- Public Types inherited from gtsam::HybridFactorGraph
using Base = FactorGraph< Factor >
 
using Indices = KeyVector
 
using shared_ptr = std::shared_ptr< This >
 shared_ptr to This More...
 
using This = HybridFactorGraph
 this class More...
 
using Values = gtsam::Values
 backwards compatibility More...
 
- Public Types inherited from gtsam::FactorGraph< Factor >
typedef FastVector< sharedFactor >::const_iterator const_iterator
 
typedef Factor FactorType
 factor type More...
 
typedef FastVector< sharedFactor >::iterator iterator
 
typedef std::shared_ptr< FactorsharedFactor
 Shared pointer to a factor. More...
 
typedef sharedFactor value_type
 
- Public Types inherited from gtsam::EliminateableFactorGraph< HybridGaussianFactorGraph >
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

Constructors
 HybridGaussianFactorGraph ()=default
 Default constructor. More...
 
template<class DERIVEDFACTOR >
 HybridGaussianFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph)
 
Standard Interface
AlgebraicDecisionTree< Keyerror (const VectorValues &continuousValues) const
 Compute error for each discrete assignment, and return as a tree. More...
 
AlgebraicDecisionTree< KeyprobPrime (const VectorValues &continuousValues) const
 Compute unnormalized probability $ P(X | M, Z) $ for each discrete assignment, and return as a tree. More...
 
double probPrime (const HybridValues &values) const
 Compute the unnormalized posterior probability for a continuous vector values given a specific assignment. More...
 
GaussianFactorGraphTree assembleGraphTree () const
 Create a decision tree of factor graphs out of this hybrid factor graph. More...
 
- Public Member Functions inherited from gtsam::HybridFactorGraph
 HybridFactorGraph ()=default
 Default constructor. More...
 
template<class DERIVEDFACTOR >
 HybridFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph)
 
std::set< DiscreteKeydiscreteKeys () const
 Get all the discrete keys in the factor graph. More...
 
KeySet discreteKeySet () const
 Get all the discrete keys in the factor graph, as a set. More...
 
std::unordered_map< Key, DiscreteKeydiscreteKeyMap () const
 Get a map from Key to corresponding DiscreteKey. More...
 
const KeySet continuousKeySet () const
 Get all the continuous keys in the factor graph. More...
 
- Public Member Functions inherited from gtsam::FactorGraph< Factor >
 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)
 
virtual void print (const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
 Print out graph to std::cout, with optional key formatter. More...
 
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< HybridGaussianFactorGraph >
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
 

Protected Types

template<typename FACTOR >
using IsGaussian = typename std::enable_if< std::is_base_of< GaussianFactor, FACTOR >::value >::type
 Check if FACTOR type is derived from GaussianFactor. More...
 

Additional Inherited Members

- Protected Member Functions inherited from gtsam::FactorGraph< Factor >
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< Factor >
FastVector< sharedFactorfactors_
 

Detailed Description

Hybrid Gaussian Factor Graph

This is the linearized version of a hybrid factor graph.

Definition at line 103 of file HybridGaussianFactorGraph.h.

Member Typedef Documentation

◆ Base

Definition at line 113 of file HybridGaussianFactorGraph.h.

◆ BaseEliminateable

for elimination

Definition at line 116 of file HybridGaussianFactorGraph.h.

◆ Indices

map from keys to values

Definition at line 120 of file HybridGaussianFactorGraph.h.

◆ IsGaussian

template<typename FACTOR >
using gtsam::HybridGaussianFactorGraph::IsGaussian = typename std::enable_if< std::is_base_of<GaussianFactor, FACTOR>::value>::type
protected

Check if FACTOR type is derived from GaussianFactor.

Definition at line 110 of file HybridGaussianFactorGraph.h.

◆ shared_ptr

shared_ptr to This

Definition at line 117 of file HybridGaussianFactorGraph.h.

◆ This

this class

Definition at line 114 of file HybridGaussianFactorGraph.h.

◆ Values

backwards compatibility

Definition at line 119 of file HybridGaussianFactorGraph.h.

Constructor & Destructor Documentation

◆ HybridGaussianFactorGraph() [1/2]

gtsam::HybridGaussianFactorGraph::HybridGaussianFactorGraph ( )
default

Default constructor.

◆ HybridGaussianFactorGraph() [2/2]

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

Implicit copy/downcast constructor to override explicit template container constructor. In BayesTree this is used for: cachedSeparatorMarginal_.reset(*separatorMarginal)

Definition at line 134 of file HybridGaussianFactorGraph.h.

Member Function Documentation

◆ assembleGraphTree()

GaussianFactorGraphTree gtsam::HybridGaussianFactorGraph::assembleGraphTree ( ) const

Create a decision tree of factor graphs out of this hybrid factor graph.

For example, if there are two mixture factors, one with a discrete key A and one with a discrete key B, then the decision tree will have two levels, one for A and one for B. The leaves of the tree will be the Gaussian factors that have only continuous keys.

Definition at line 100 of file HybridGaussianFactorGraph.cpp.

◆ error()

AlgebraicDecisionTree< Key > gtsam::HybridGaussianFactorGraph::error ( const VectorValues continuousValues) const

Compute error for each discrete assignment, and return as a tree.

Error $ e = \Vert x - \mu \Vert_{\Sigma} $.

Parameters
continuousValuesContinuous values at which to compute the error.
Returns
AlgebraicDecisionTree<Key>

Definition at line 424 of file HybridGaussianFactorGraph.cpp.

◆ probPrime() [1/2]

AlgebraicDecisionTree< Key > gtsam::HybridGaussianFactorGraph::probPrime ( const VectorValues continuousValues) const

Compute unnormalized probability $ P(X | M, Z) $ for each discrete assignment, and return as a tree.

Parameters
continuousValuesContinuous values at which to compute the probability.
Returns
AlgebraicDecisionTree<Key>

Definition at line 462 of file HybridGaussianFactorGraph.cpp.

◆ probPrime() [2/2]

double gtsam::HybridGaussianFactorGraph::probPrime ( const HybridValues values) const

Compute the unnormalized posterior probability for a continuous vector values given a specific assignment.

Returns
double

Definition at line 455 of file HybridGaussianFactorGraph.cpp.


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


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