A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network. This is the result of the elimination of a continuous variable in a hybrid scheme, such that the remaining variables are discrete+continuous. More...
#include <GaussianMixture.h>
Public Types | |
using | BaseConditional = Conditional< HybridFactor, GaussianMixture > |
using | BaseFactor = HybridFactor |
using | Conditionals = DecisionTree< Key, GaussianConditional::shared_ptr > |
typedef for Decision Tree of Gaussian Conditionals More... | |
using | shared_ptr = std::shared_ptr< GaussianMixture > |
using | This = GaussianMixture |
Public Types inherited from gtsam::HybridFactor | |
typedef Factor | Base |
Our base class. More... | |
typedef std::shared_ptr< HybridFactor > | shared_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 Types inherited from gtsam::Conditional< HybridFactor, GaussianMixture > | |
typedef std::pair< typename HybridFactor ::const_iterator, typename HybridFactor ::const_iterator > | ConstFactorRange |
typedef ConstFactorRangeIterator | Frontals |
typedef ConstFactorRangeIterator | Parents |
Public Member Functions | |
Constructors | |
GaussianMixture ()=default | |
Default constructor, mainly for serialization. More... | |
GaussianMixture (const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, const Conditionals &conditionals) | |
Construct a new GaussianMixture object. More... | |
GaussianMixture (KeyVector &&continuousFrontals, KeyVector &&continuousParents, DiscreteKeys &&discreteParents, std::vector< GaussianConditional::shared_ptr > &&conditionals) | |
Make a Gaussian Mixture from a list of Gaussian conditionals. More... | |
GaussianMixture (const KeyVector &continuousFrontals, const KeyVector &continuousParents, const DiscreteKeys &discreteParents, const std::vector< GaussianConditional::shared_ptr > &conditionals) | |
Make a Gaussian Mixture from a list of Gaussian conditionals. More... | |
Testable | |
bool | equals (const HybridFactor &lf, double tol=1e-9) const override |
Test equality with base HybridFactor. More... | |
void | print (const std::string &s="GaussianMixture\, const KeyFormatter &formatter=DefaultKeyFormatter) const override |
Print utility. More... | |
Standard API | |
GaussianConditional::shared_ptr | operator() (const DiscreteValues &discreteValues) const |
Return the conditional Gaussian for the given discrete assignment. More... | |
size_t | nrComponents () const |
Returns the total number of continuous components. More... | |
KeyVector | continuousParents () const |
Returns the continuous keys among the parents. More... | |
double | logNormalizationConstant () const override |
std::shared_ptr< GaussianMixtureFactor > | likelihood (const VectorValues &given) const |
const Conditionals & | conditionals () const |
Getter for the underlying Conditionals DecisionTree. More... | |
AlgebraicDecisionTree< Key > | logProbability (const VectorValues &continuousValues) const |
Compute logProbability of the GaussianMixture as a tree. More... | |
double | error (const HybridValues &values) const override |
Compute the error of this Gaussian Mixture. More... | |
AlgebraicDecisionTree< Key > | error (const VectorValues &continuousValues) const |
Compute error of the GaussianMixture as a tree. More... | |
double | logProbability (const HybridValues &values) const override |
Compute the logProbability of this Gaussian Mixture. More... | |
double | evaluate (const HybridValues &values) const override |
Calculate probability density for given values . More... | |
double | operator() (const HybridValues &values) const |
Evaluate probability density, sugar. More... | |
void | prune (const DecisionTreeFactor &decisionTree) |
Prune the decision tree of Gaussian factors as per the discrete decisionTree . More... | |
GaussianFactorGraphTree | add (const GaussianFactorGraphTree &sum) const |
Merge the Gaussian Factor Graphs in this and sum while maintaining the decision tree structure. 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 DiscreteKeys & | discreteKeys () const |
Return the discrete keys for this factor. More... | |
const KeyVector & | continuousKeys () 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 KeyVector & | keys () 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... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Public Member Functions inherited from gtsam::Conditional< HybridFactor, GaussianMixture > | |
void | print (const std::string &s="Conditional", const KeyFormatter &formatter=DefaultKeyFormatter) const |
bool | equals (const This &c, double tol=1e-9) const |
virtual | ~Conditional () |
size_t | nrFrontals () const |
size_t | nrParents () const |
Key | firstFrontalKey () const |
Frontals | frontals () const |
Parents | parents () const |
double | operator() (const HybridValues &x) const |
Evaluate probability density, sugar. More... | |
double | normalizationConstant () const |
size_t & | nrFrontals () |
HybridFactor ::const_iterator | beginFrontals () const |
HybridFactor ::iterator | beginFrontals () |
HybridFactor ::const_iterator | endFrontals () const |
HybridFactor ::iterator | endFrontals () |
HybridFactor ::const_iterator | beginParents () const |
HybridFactor ::iterator | beginParents () |
HybridFactor ::const_iterator | endParents () const |
HybridFactor ::iterator | endParents () |
Private Member Functions | |
bool | allFrontalsGiven (const VectorValues &given) const |
Check whether given has values for all frontal keys. More... | |
GaussianFactorGraphTree | asGaussianFactorGraphTree () const |
Convert a DecisionTree of factors into a DT of Gaussian FGs. More... | |
std::function< GaussianConditional::shared_ptr(const Assignment< Key > &, const GaussianConditional::shared_ptr &)> | prunerFunc (const DecisionTreeFactor &decisionTree) |
Helper function to get the pruner functor. More... | |
Private Attributes | |
Conditionals | conditionals_ |
a decision tree of Gaussian conditionals. More... | |
double | logConstant_ |
log of the normalization constant. More... | |
Additional Inherited Members | |
Static Public Member Functions inherited from gtsam::Conditional< HybridFactor, GaussianMixture > | |
static bool | CheckInvariants (const GaussianMixture &conditional, const VALUES &x) |
Protected Member Functions inherited from gtsam::Factor | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
Protected Member Functions inherited from gtsam::Conditional< HybridFactor, GaussianMixture > | |
Conditional () | |
Conditional (size_t nrFrontals) | |
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... | |
Protected Attributes inherited from gtsam::Conditional< HybridFactor, GaussianMixture > | |
size_t | nrFrontals_ |
A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network. This is the result of the elimination of a continuous variable in a hybrid scheme, such that the remaining variables are discrete+continuous.
Represents the conditional density P(X | M, Z) where X is the set of continuous random variables, M is the selection of discrete variables corresponding to a subset of the Gaussian variables and Z is parent of this node .
The probability P(x|y,z,...) is proportional to where i indexes the components and k_i is a component-wise normalization constant.
a density over continuous variables given discrete/continuous parents.
Definition at line 53 of file GaussianMixture.h.
Definition at line 60 of file GaussianMixture.h.
Definition at line 59 of file GaussianMixture.h.
typedef for Decision Tree of Gaussian Conditionals
Definition at line 63 of file GaussianMixture.h.
using gtsam::GaussianMixture::shared_ptr = std::shared_ptr<GaussianMixture> |
Definition at line 58 of file GaussianMixture.h.
Definition at line 57 of file GaussianMixture.h.
|
default |
Default constructor, mainly for serialization.
gtsam::GaussianMixture::GaussianMixture | ( | const KeyVector & | continuousFrontals, |
const KeyVector & | continuousParents, | ||
const DiscreteKeys & | discreteParents, | ||
const Conditionals & | conditionals | ||
) |
Construct a new GaussianMixture object.
continuousFrontals | the continuous frontals. |
continuousParents | the continuous parents. |
discreteParents | the discrete parents. Will be placed last. |
conditionals | a decision tree of GaussianConditionals. The number of conditionals should be C^(number of discrete parents), where C is the cardinality of the DiscreteKeys in discreteParents, since the discreteParents will be used as the labels in the decision tree. |
Definition at line 31 of file GaussianMixture.cpp.
gtsam::GaussianMixture::GaussianMixture | ( | KeyVector && | continuousFrontals, |
KeyVector && | continuousParents, | ||
DiscreteKeys && | discreteParents, | ||
std::vector< GaussianConditional::shared_ptr > && | conditionals | ||
) |
Make a Gaussian Mixture from a list of Gaussian conditionals.
continuousFrontals | The continuous frontal variables |
continuousParents | The continuous parent variables |
discreteParents | Discrete parents variables |
conditionals | List of conditionals |
Definition at line 57 of file GaussianMixture.cpp.
gtsam::GaussianMixture::GaussianMixture | ( | const KeyVector & | continuousFrontals, |
const KeyVector & | continuousParents, | ||
const DiscreteKeys & | discreteParents, | ||
const std::vector< GaussianConditional::shared_ptr > & | conditionals | ||
) |
Make a Gaussian Mixture from a list of Gaussian conditionals.
continuousFrontals | The continuous frontal variables |
continuousParents | The continuous parent variables |
discreteParents | Discrete parents variables |
conditionals | List of conditionals |
Definition at line 65 of file GaussianMixture.cpp.
GaussianFactorGraphTree gtsam::GaussianMixture::add | ( | const GaussianFactorGraphTree & | sum | ) | const |
Merge the Gaussian Factor Graphs in this
and sum
while maintaining the decision tree structure.
sum | Decision Tree of Gaussian Factor Graphs |
Definition at line 75 of file GaussianMixture.cpp.
|
private |
Check whether given
has values for all frontal keys.
Definition at line 178 of file GaussianMixture.cpp.
|
private |
Convert a DecisionTree of factors into a DT of Gaussian FGs.
Definition at line 88 of file GaussianMixture.cpp.
const GaussianMixture::Conditionals & gtsam::GaussianMixture::conditionals | ( | ) | const |
Getter for the underlying Conditionals DecisionTree.
Definition at line 52 of file GaussianMixture.cpp.
KeyVector gtsam::GaussianMixture::continuousParents | ( | ) | const |
Returns the continuous keys among the parents.
Definition at line 162 of file GaussianMixture.cpp.
|
overridevirtual |
Test equality with base HybridFactor.
Reimplemented from gtsam::HybridFactor.
Definition at line 118 of file GaussianMixture.cpp.
|
overridevirtual |
Compute the error of this Gaussian Mixture.
This requires some care, as different mixture components may have different normalization constants. Let's consider p(x|y,m), where m is discrete. We need the error to satisfy the invariant:
error(x;y,m) = K - log(probability(x;y,m))
For all x,y,m. But note that K, the (log) normalization constant defined in Conditional.h, should not depend on x, y, or m, only on the parameters of the density. Hence, we delegate to the underlying Gaussian conditionals, indexed by m, which do satisfy:
log(probability_m(x;y)) = K_m - error_m(x;y)
We resolve by having K == max(K_m) and
error(x;y,m) = error_m(x;y) + K - K_m
which also makes error(x;y,m) >= 0 for all x,y,m.
values | Continuous values and discrete assignment. |
Reimplemented from gtsam::Factor.
Definition at line 329 of file GaussianMixture.cpp.
AlgebraicDecisionTree< Key > gtsam::GaussianMixture::error | ( | const VectorValues & | continuousValues | ) | const |
Compute error of the GaussianMixture as a tree.
continuousValues | The continuous VectorValues. |
Definition at line 318 of file GaussianMixture.cpp.
|
overridevirtual |
Calculate probability density for given values
.
Reimplemented from gtsam::Conditional< HybridFactor, GaussianMixture >.
Definition at line 343 of file GaussianMixture.cpp.
std::shared_ptr< GaussianMixtureFactor > gtsam::GaussianMixture::likelihood | ( | const VectorValues & | given | ) | const |
Create a likelihood factor for a Gaussian mixture, return a Mixture factor on the parents.
Definition at line 188 of file GaussianMixture.cpp.
|
inlineoverridevirtual |
The log normalization constant is max of the the individual log-normalization constants.
Reimplemented from gtsam::Conditional< HybridFactor, GaussianMixture >.
Definition at line 161 of file GaussianMixture.h.
AlgebraicDecisionTree< Key > gtsam::GaussianMixture::logProbability | ( | const VectorValues & | continuousValues | ) | const |
Compute logProbability of the GaussianMixture as a tree.
continuousValues | The continuous VectorValues. |
Definition at line 300 of file GaussianMixture.cpp.
|
overridevirtual |
Compute the logProbability of this Gaussian Mixture.
values | Continuous values and discrete assignment. |
Reimplemented from gtsam::Conditional< HybridFactor, GaussianMixture >.
Definition at line 337 of file GaussianMixture.cpp.
size_t gtsam::GaussianMixture::nrComponents | ( | ) | const |
Returns the total number of continuous components.
Definition at line 96 of file GaussianMixture.cpp.
GaussianConditional::shared_ptr gtsam::GaussianMixture::operator() | ( | const DiscreteValues & | discreteValues | ) | const |
Return the conditional Gaussian for the given discrete assignment.
Definition at line 105 of file GaussianMixture.cpp.
|
inline |
Evaluate probability density, sugar.
Definition at line 231 of file GaussianMixture.h.
|
overridevirtual |
Print utility.
Reimplemented from gtsam::Factor.
Definition at line 136 of file GaussianMixture.cpp.
void gtsam::GaussianMixture::prune | ( | const DecisionTreeFactor & | decisionTree | ) |
Prune the decision tree of Gaussian factors as per the discrete decisionTree
.
decisionTree | A pruned decision tree of discrete keys where the leaves are probabilities. |
Definition at line 288 of file GaussianMixture.cpp.
|
private |
Helper function to get the pruner functor.
Helper function to get the pruner functional.
decisionTree | The pruned discrete probability decision tree. |
decisionTree | The probability decision tree of only discrete keys. |
Definition at line 237 of file GaussianMixture.cpp.
|
private |
a decision tree of Gaussian conditionals.
Definition at line 66 of file GaussianMixture.h.
|
private |
log of the normalization constant.
Definition at line 67 of file GaussianMixture.h.