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

Implementation of a discrete-conditioned hybrid factor. Implements a joint discrete-continuous factor where the discrete variable serves to "select" a component corresponding to a GaussianFactor. More...

#include <HybridGaussianFactor.h>

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

Public Types

using Base = HybridFactor
 
using Factors = DecisionTree< Key, sharedFactor >
 typedef for Decision Tree of Gaussian factors. More...
 
using FactorValuePairs = DecisionTree< Key, GaussianFactorValuePair >
 typedef for Decision Tree of Gaussian factors and arbitrary value. More...
 
using shared_ptr = std::shared_ptr< This >
 
using sharedFactor = std::shared_ptr< GaussianFactor >
 
using This = HybridGaussianFactor
 
- Public Types inherited from gtsam::HybridFactor
typedef Factor Base
 Our base class. More...
 
enum  Category { Category::None, Category::Discrete, Category::Continuous, Category::Hybrid }
 Enum to help with categorizing hybrid factors. 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
 HybridGaussianFactor ()=default
 Default constructor, mainly for serialization. More...
 
 HybridGaussianFactor (const KeyVector &continuousKeys, const DiscreteKey &discreteKey, const std::vector< GaussianFactor::shared_ptr > &factors)
 Construct a new HybridGaussianFactor on a single discrete key, providing the factors for each mode m as a vector of factors ϕ_m(x). The value ϕ(x,m) for the factor is simply ϕ_m(x). More...
 
 HybridGaussianFactor (const KeyVector &continuousKeys, const DiscreteKey &discreteKey, const std::vector< GaussianFactorValuePair > &factors)
 Construct a new HybridGaussianFactor on a single discrete key, including a scalar error value for each mode m. The factors and scalars are provided as a vector of pairs (ϕ_m(x), E_m). The value ϕ(x,m) for the factor is now ϕ_m(x) + E_m. More...
 
 HybridGaussianFactor (const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const FactorValuePairs &factors)
 Construct a new HybridGaussianFactor on a several discrete keys M, including a scalar error value for each assignment m. The factors and scalars are provided as a DecisionTree<Key> of pairs (ϕ_M(x), E_M). The value ϕ(x,M) for the factor is again ϕ_m(x) + E_m. More...
 
Testable
bool equals (const HybridFactor &lf, double tol=1e-9) const override
 equals More...
 
void print (const std::string &s="", 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...
 
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...
 
double potentiallyPrunedComponentError (const sharedFactor &gf, const VectorValues &continuousValues) const
 Helper method to compute the error of a component. 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< KeyerrorTree (const VectorValues &continuousValues) const override
 Compute error of the HybridGaussianFactor 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 HybridGaussianFactor &factor)
 Add HybridNonlinearFactor 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-conditioned hybrid factor. Implements a joint discrete-continuous factor where the discrete variable serves to "select" a component corresponding to a GaussianFactor.

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

In factor graphs the error function typically returns 0.5*|A*x - b|^2, i.e., the negative log-likelihood for a Gaussian noise model. In hybrid factor graphs we allow adding an arbitrary scalar dependent on the discrete assignment. For example, adding a 70/30 mode probability is supported by providing the scalars $-log(.7)$ and $-log(.3)$. Note that adding a common constant will not make any difference in the optimization, so $-log(70)$ and $-log(30)$ work just as well.

Definition at line 59 of file HybridGaussianFactor.h.

Member Typedef Documentation

◆ Base

Definition at line 61 of file HybridGaussianFactor.h.

◆ Factors

typedef for Decision Tree of Gaussian factors.

Definition at line 70 of file HybridGaussianFactor.h.

◆ FactorValuePairs

typedef for Decision Tree of Gaussian factors and arbitrary value.

Definition at line 68 of file HybridGaussianFactor.h.

◆ shared_ptr

Definition at line 63 of file HybridGaussianFactor.h.

◆ sharedFactor

Definition at line 65 of file HybridGaussianFactor.h.

◆ This

Definition at line 62 of file HybridGaussianFactor.h.

Constructor & Destructor Documentation

◆ HybridGaussianFactor() [1/4]

gtsam::HybridGaussianFactor::HybridGaussianFactor ( )
default

Default constructor, mainly for serialization.

◆ HybridGaussianFactor() [2/4]

gtsam::HybridGaussianFactor::HybridGaussianFactor ( const KeyVector continuousKeys,
const DiscreteKey discreteKey,
const std::vector< GaussianFactor::shared_ptr > &  factors 
)
inline

Construct a new HybridGaussianFactor on a single discrete key, providing the factors for each mode m as a vector of factors ϕ_m(x). The value ϕ(x,m) for the factor is simply ϕ_m(x).

Parameters
continuousKeysVector of keys for continuous factors.
discreteKeyThe discrete key for the "mode", indexing components.
factorsVector of gaussian factors, one for each mode.

Definition at line 100 of file HybridGaussianFactor.h.

◆ HybridGaussianFactor() [3/4]

gtsam::HybridGaussianFactor::HybridGaussianFactor ( const KeyVector continuousKeys,
const DiscreteKey discreteKey,
const std::vector< GaussianFactorValuePair > &  factors 
)
inline

Construct a new HybridGaussianFactor on a single discrete key, including a scalar error value for each mode m. The factors and scalars are provided as a vector of pairs (ϕ_m(x), E_m). The value ϕ(x,m) for the factor is now ϕ_m(x) + E_m.

Parameters
continuousKeysVector of keys for continuous factors.
discreteKeyThe discrete key for the "mode", indexing components.
factorsVector of gaussian factor-scalar pairs, one per mode.

Definition at line 115 of file HybridGaussianFactor.h.

◆ HybridGaussianFactor() [4/4]

gtsam::HybridGaussianFactor::HybridGaussianFactor ( const KeyVector continuousKeys,
const DiscreteKeys discreteKeys,
const FactorValuePairs factors 
)

Construct a new HybridGaussianFactor on a several discrete keys M, including a scalar error value for each assignment m. The factors and scalars are provided as a DecisionTree<Key> of pairs (ϕ_M(x), E_M). The value ϕ(x,M) for the factor is again ϕ_m(x) + E_m.

Parameters
continuousKeysA vector of keys representing continuous variables.
discreteKeysDiscrete variables and their cardinalities.
factorsThe decision tree of Gaussian factor/scalar pairs.

Definition at line 80 of file HybridGaussianFactor.cpp.

Member Function Documentation

◆ add()

GaussianFactorGraphTree gtsam::HybridGaussianFactor::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 135 of file HybridGaussianFactor.cpp.

◆ asGaussianFactorGraphTree()

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

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

Returns
GaussianFactorGraphTree

Definition at line 148 of file HybridGaussianFactor.cpp.

◆ equals()

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

equals

Reimplemented from gtsam::HybridFactor.

Definition at line 86 of file HybridGaussianFactor.cpp.

◆ error()

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

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

Returns
double

Reimplemented from gtsam::Factor.

Definition at line 180 of file HybridGaussianFactor.cpp.

◆ errorTree()

AlgebraicDecisionTree< Key > gtsam::HybridGaussianFactor::errorTree ( const VectorValues continuousValues) const
overridevirtual

Compute error of the HybridGaussianFactor 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.

Implements gtsam::HybridFactor.

Definition at line 169 of file HybridGaussianFactor.cpp.

◆ factors()

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

Getter for GaussianFactor decision tree.

Definition at line 178 of file HybridGaussianFactor.h.

◆ operator()()

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

Get factor at a given discrete assignment.

Definition at line 129 of file HybridGaussianFactor.cpp.

◆ potentiallyPrunedComponentError()

double gtsam::HybridGaussianFactor::potentiallyPrunedComponentError ( const sharedFactor gf,
const VectorValues continuousValues 
) const
private

Helper method to compute the error of a component.

Definition at line 155 of file HybridGaussianFactor.cpp.

◆ print()

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

print

Reimplemented from gtsam::HybridFactor.

Definition at line 103 of file HybridGaussianFactor.cpp.

Friends And Related Function Documentation

◆ operator+=

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

Add HybridNonlinearFactor to a Sum, syntactic sugar.

Definition at line 181 of file HybridGaussianFactor.h.

Member Data Documentation

◆ factors_

Factors gtsam::HybridGaussianFactor::factors_
private

Decision tree of Gaussian factors indexed by discrete keys.

Definition at line 74 of file HybridGaussianFactor.h.


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


gtsam
Author(s):
autogenerated on Wed Sep 25 2024 03:21:31