Public Types | Private Member Functions | Private Attributes | List of all members
gtsam::GaussianMixtureFactor Class Reference

Implementation of a discrete conditional mixture factor. Implements a joint discrete-continuous factor where the discrete variable serves to "select" a mixture component corresponding to a GaussianFactor type of measurement. More...

#include <GaussianMixtureFactor.h>

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

Public Types

using Base = HybridFactor
 
using Factors = DecisionTree< Key, sharedFactor >
 typedef for Decision Tree of Gaussian factors and log-constant. More...
 
using shared_ptr = std::shared_ptr< This >
 
using sharedFactor = std::shared_ptr< GaussianFactor >
 
using This = GaussianMixtureFactor
 
- Public Types inherited from gtsam::HybridFactor
typedef Factor Base
 Our base class. More...
 
typedef std::shared_ptr< HybridFactorshared_ptr
 shared_ptr to this class More...
 
typedef HybridFactor This
 This class. More...
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys. More...
 
typedef KeyVector::iterator iterator
 Iterator over keys. More...
 

Public Member Functions

Constructors
 GaussianMixtureFactor ()=default
 Default constructor, mainly for serialization. More...
 
 GaussianMixtureFactor (const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const Factors &factors)
 Construct a new Gaussian mixture factor. More...
 
 GaussianMixtureFactor (const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const std::vector< sharedFactor > &factors)
 Construct a new GaussianMixtureFactor object using a vector of GaussianFactor shared pointers. More...
 
Testable
bool equals (const HybridFactor &lf, double tol=1e-9) const override
 equals More...
 
void print (const std::string &s="GaussianMixtureFactor\, const KeyFormatter &formatter=DefaultKeyFormatter) const override
 print More...
 
- Public Member Functions inherited from gtsam::HybridFactor
 HybridFactor ()=default
 
 HybridFactor (const KeyVector &keys)
 Construct hybrid factor from continuous keys. More...
 
 HybridFactor (const DiscreteKeys &discreteKeys)
 Construct hybrid factor from discrete keys. More...
 
 HybridFactor (const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys)
 Construct a new Hybrid Factor object. More...
 
void print (const std::string &s="HybridFactor\, const KeyFormatter &formatter=DefaultKeyFormatter) const override
 print More...
 
bool isDiscrete () const
 True if this is a factor of discrete variables only. More...
 
bool isContinuous () const
 True if this is a factor of continuous variables only. More...
 
bool isHybrid () const
 True is this is a Discrete-Continuous factor. More...
 
size_t nrContinuous () const
 Return the number of continuous variables in this factor. More...
 
const DiscreteKeysdiscreteKeys () const
 Return the discrete keys for this factor. More...
 
const KeyVectorcontinuousKeys () const
 Return only the continuous keys for this factor. More...
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
bool empty () const
 Whether the factor is empty (involves zero variables). More...
 
Key front () const
 First key. More...
 
Key back () const
 Last key. More...
 
const_iterator find (Key key) const
 find More...
 
const KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Private Member Functions

GaussianFactorGraphTree asGaussianFactorGraphTree () const
 Helper function to return factors and functional to create a DecisionTree of Gaussian Factor Graphs. More...
 

Private Attributes

Factors factors_
 Decision tree of Gaussian factors indexed by discrete keys. More...
 

Standard API

sharedFactor operator() (const DiscreteValues &assignment) const
 Get factor at a given discrete assignment. More...
 
GaussianFactorGraphTree add (const GaussianFactorGraphTree &sum) const
 Combine the Gaussian Factor Graphs in sum and this while maintaining the original tree structure. More...
 
AlgebraicDecisionTree< Keyerror (const VectorValues &continuousValues) const
 Compute error of the GaussianMixtureFactor as a tree. More...
 
double error (const HybridValues &values) const override
 Compute the log-likelihood, including the log-normalizing constant. More...
 
const Factorsfactors () const
 Getter for GaussianFactor decision tree. More...
 
GaussianFactorGraphTreeoperator+= (GaussianFactorGraphTree &sum, const GaussianMixtureFactor &factor)
 Add MixtureFactor to a Sum, syntactic sugar. More...
 

Additional Inherited Members

- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 
- Protected Attributes inherited from gtsam::HybridFactor
KeyVector continuousKeys_
 Record continuous keys for book-keeping. More...
 
DiscreteKeys discreteKeys_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

Implementation of a discrete conditional mixture factor. Implements a joint discrete-continuous factor where the discrete variable serves to "select" a mixture component corresponding to a GaussianFactor type of measurement.

Represents the underlying Gaussian mixture as a Decision Tree, where the set of discrete variables indexes to the continuous gaussian distribution.

Definition at line 47 of file GaussianMixtureFactor.h.

Member Typedef Documentation

◆ Base

Definition at line 49 of file GaussianMixtureFactor.h.

◆ Factors

typedef for Decision Tree of Gaussian factors and log-constant.

Definition at line 56 of file GaussianMixtureFactor.h.

◆ shared_ptr

Definition at line 51 of file GaussianMixtureFactor.h.

◆ sharedFactor

Definition at line 53 of file GaussianMixtureFactor.h.

◆ This

Definition at line 50 of file GaussianMixtureFactor.h.

Constructor & Destructor Documentation

◆ GaussianMixtureFactor() [1/3]

gtsam::GaussianMixtureFactor::GaussianMixtureFactor ( )
default

Default constructor, mainly for serialization.

◆ GaussianMixtureFactor() [2/3]

gtsam::GaussianMixtureFactor::GaussianMixtureFactor ( const KeyVector continuousKeys,
const DiscreteKeys discreteKeys,
const Factors factors 
)

Construct a new Gaussian mixture factor.

Parameters
continuousKeysA vector of keys representing continuous variables.
discreteKeysA vector of keys representing discrete variables and their cardinalities.
factorsThe decision tree of Gaussian factors stored as the mixture density.

Definition at line 32 of file GaussianMixtureFactor.cpp.

◆ GaussianMixtureFactor() [3/3]

gtsam::GaussianMixtureFactor::GaussianMixtureFactor ( const KeyVector continuousKeys,
const DiscreteKeys discreteKeys,
const std::vector< sharedFactor > &  factors 
)
inline

Construct a new GaussianMixtureFactor object using a vector of GaussianFactor shared pointers.

Parameters
continuousKeysVector of keys for continuous factors.
discreteKeysVector of discrete keys.
factorsVector of gaussian factor shared pointers.

Definition at line 98 of file GaussianMixtureFactor.h.

Member Function Documentation

◆ add()

GaussianFactorGraphTree gtsam::GaussianMixtureFactor::add ( const GaussianFactorGraphTree sum) const

Combine the Gaussian Factor Graphs in sum and this while maintaining the original tree structure.

Parameters
sumDecision Tree of Gaussian Factor Graphs indexed by the variables.
Returns
Sum

Definition at line 85 of file GaussianMixtureFactor.cpp.

◆ asGaussianFactorGraphTree()

GaussianFactorGraphTree gtsam::GaussianMixtureFactor::asGaussianFactorGraphTree ( ) const
private

Helper function to return factors and functional to create a DecisionTree of Gaussian Factor Graphs.

Returns
GaussianFactorGraphTree

Definition at line 98 of file GaussianMixtureFactor.cpp.

◆ equals()

bool gtsam::GaussianMixtureFactor::equals ( const HybridFactor lf,
double  tol = 1e-9 
) const
overridevirtual

equals

Reimplemented from gtsam::HybridFactor.

Definition at line 38 of file GaussianMixtureFactor.cpp.

◆ error() [1/2]

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

Compute error of the GaussianMixtureFactor as a tree.

Parameters
continuousValuesThe continuous VectorValues.
Returns
AlgebraicDecisionTree<Key> A decision tree with the same keys as the factors involved, and leaf values as the error.

Definition at line 105 of file GaussianMixtureFactor.cpp.

◆ error() [2/2]

double gtsam::GaussianMixtureFactor::error ( const HybridValues values) const
overridevirtual

Compute the log-likelihood, including the log-normalizing constant.

Returns
double

Reimplemented from gtsam::Factor.

Definition at line 116 of file GaussianMixtureFactor.cpp.

◆ factors()

const Factors& gtsam::GaussianMixtureFactor::factors ( ) const
inline

Getter for GaussianFactor decision tree.

Definition at line 147 of file GaussianMixtureFactor.h.

◆ operator()()

GaussianMixtureFactor::sharedFactor gtsam::GaussianMixtureFactor::operator() ( const DiscreteValues assignment) const

Get factor at a given discrete assignment.

Definition at line 79 of file GaussianMixtureFactor.cpp.

◆ print()

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

print

Reimplemented from gtsam::Factor.

Definition at line 55 of file GaussianMixtureFactor.cpp.

Friends And Related Function Documentation

◆ operator+=

GaussianFactorGraphTree& operator+= ( GaussianFactorGraphTree sum,
const GaussianMixtureFactor factor 
)
friend

Add MixtureFactor to a Sum, syntactic sugar.

Definition at line 150 of file GaussianMixtureFactor.h.

Member Data Documentation

◆ factors_

Factors gtsam::GaussianMixtureFactor::factors_
private

Decision tree of Gaussian factors indexed by discrete keys.

Definition at line 60 of file GaussianMixtureFactor.h.


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


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