Implementation of a discrete conditional mixture factor. More...
#include <MixtureFactor.h>
Public Types | |
using | Base = HybridFactor |
using | Factors = DecisionTree< Key, sharedFactor > |
typedef for DecisionTree which has Keys as node labels and NonlinearFactor as leaf nodes. More... | |
using | shared_ptr = std::shared_ptr< MixtureFactor > |
using | sharedFactor = std::shared_ptr< NonlinearFactor > |
using | This = MixtureFactor |
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 Member Functions | |
size_t | dim () const |
Get the dimension of the factor (number of rows on linearization). Returns the dimension of the first component factor. More... | |
AlgebraicDecisionTree< Key > | error (const Values &continuousValues) const |
Compute error of the MixtureFactor as a tree. More... | |
double | error (const Values &continuousValues, const DiscreteValues &discreteValues) const |
Compute error of factor given both continuous and discrete values. More... | |
double | error (const HybridValues &values) const override |
Compute error of factor given hybrid values. More... | |
GaussianFactor::shared_ptr | linearize (const Values &continuousValues, const DiscreteValues &discreteValues) const |
std::shared_ptr< GaussianMixtureFactor > | linearize (const Values &continuousValues) const |
Linearize all the continuous factors to get a GaussianMixtureFactor. More... | |
MixtureFactor ()=default | |
MixtureFactor (const KeyVector &keys, const DiscreteKeys &discreteKeys, const Factors &factors, bool normalized=false) | |
Construct from Decision tree. More... | |
template<typename FACTOR > | |
MixtureFactor (const KeyVector &keys, const DiscreteKeys &discreteKeys, const std::vector< std::shared_ptr< FACTOR >> &factors, bool normalized=false) | |
Convenience constructor that generates the underlying factor decision tree for us. More... | |
double | nonlinearFactorLogNormalizingConstant (const sharedFactor &factor, const Values &values) const |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
print to stdout More... | |
bool | equals (const HybridFactor &other, double tol=1e-9) const override |
Check equality. 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 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 () |
Private Attributes | |
Factors | factors_ |
Decision tree of Gaussian factors indexed by discrete keys. More... | |
bool | normalized_ |
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... | |
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 NonlinearFactor type of measurement.
This class stores all factors as HybridFactors which can then be typecast to one of (NonlinearFactor, GaussianFactor) which can then be checked to perform the correct operation.
Definition at line 47 of file MixtureFactor.h.
Definition at line 49 of file MixtureFactor.h.
typedef for DecisionTree which has Keys as node labels and NonlinearFactor as leaf nodes.
Definition at line 58 of file MixtureFactor.h.
using gtsam::MixtureFactor::shared_ptr = std::shared_ptr<MixtureFactor> |
Definition at line 51 of file MixtureFactor.h.
using gtsam::MixtureFactor::sharedFactor = std::shared_ptr<NonlinearFactor> |
Definition at line 52 of file MixtureFactor.h.
Definition at line 50 of file MixtureFactor.h.
|
default |
|
inline |
Construct from Decision tree.
keys | Vector of keys for continuous factors. |
discreteKeys | Vector of discrete keys. |
factors | Decision tree with of shared factors. |
normalized | Flag indicating if the factor error is already normalized. |
Definition at line 77 of file MixtureFactor.h.
|
inline |
Convenience constructor that generates the underlying factor decision tree for us.
Here it is important that the vector of factors has the correct number of elements based on the number of discrete keys and the cardinality of the keys, so that the decision tree is constructed appropriately.
FACTOR | The type of the factor shared pointers being passed in. Will be typecast to NonlinearFactor shared pointers. |
keys | Vector of keys for continuous factors. |
discreteKeys | Vector of discrete keys. |
factors | Vector of nonlinear factors. |
normalized | Flag indicating if the factor error is already normalized. |
Definition at line 98 of file MixtureFactor.h.
|
inline |
Get the dimension of the factor (number of rows on linearization). Returns the dimension of the first component factor.
Definition at line 176 of file MixtureFactor.h.
|
inlineoverridevirtual |
Check equality.
Reimplemented from gtsam::HybridFactor.
Definition at line 203 of file MixtureFactor.h.
|
inline |
Compute error of the MixtureFactor as a tree.
continuousValues | The continuous values for which to compute the error. |
Definition at line 134 of file MixtureFactor.h.
|
inline |
Compute error of factor given both continuous and discrete values.
Definition at line 150 of file MixtureFactor.h.
|
inlineoverridevirtual |
Compute error of factor given hybrid values.
values | The continuous Values and the discrete assignment. |
Reimplemented from gtsam::Factor.
Definition at line 167 of file MixtureFactor.h.
|
inline |
Linearize specific nonlinear factors based on the assignment in discreteValues.
Definition at line 229 of file MixtureFactor.h.
|
inline |
Linearize all the continuous factors to get a GaussianMixtureFactor.
Definition at line 237 of file MixtureFactor.h.
|
inline |
If the component factors are not already normalized, we want to compute their normalizing constants so that the resulting joint distribution is appropriately computed. Remember, this is the negative normalizing constant for the measurement likelihood (since we are minimizing the negative log-likelihood).
Definition at line 258 of file MixtureFactor.h.
|
inlineoverridevirtual |
print to stdout
Reimplemented from gtsam::HybridFactor.
Definition at line 186 of file MixtureFactor.h.
|
private |
Decision tree of Gaussian factors indexed by discrete keys.
Definition at line 62 of file MixtureFactor.h.
|
private |
Definition at line 63 of file MixtureFactor.h.