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>
Classes | |
struct | ConstructorHelper |
Public Types | |
using | Base = HybridFactor |
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< 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 | |
Constructors | |
HybridGaussianFactor ()=default | |
Default constructor, mainly for serialization. More... | |
HybridGaussianFactor (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 DiscreteKey &discreteKey, const std::vector< GaussianFactorValuePair > &factorPairs) | |
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 DiscreteKeys &discreteKeys, const FactorValuePairs &factorPairs) | |
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... | |
Standard API | |
GaussianFactorValuePair | operator() (const DiscreteValues &assignment) const |
Get factor at a given discrete assignment. More... | |
AlgebraicDecisionTree< Key > | errorTree (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 FactorValuePairs & | factors () const |
Getter for GaussianFactor decision tree. More... | |
virtual HybridGaussianProductFactor | asProductFactor () const |
Helper function to return factors and functional to create a DecisionTree of Gaussian Factor Graphs. 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 Member Functions | |
HybridGaussianFactor (const ConstructorHelper &helper) | |
Static Private Member Functions | |
static FactorValuePairs | augment (const FactorValuePairs &factors) |
Helper function to augment the [A|b] matrices in the factor components with the additional scalar values. This is done by storing the value in the b vector as an additional row. More... | |
Private Attributes | |
FactorValuePairs | factors_ |
Decision tree of Gaussian factors indexed by discrete keys. 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... | |
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 60 of file HybridGaussianFactor.h.
Definition at line 62 of file HybridGaussianFactor.h.
typedef for Decision Tree of Gaussian factors and arbitrary value.
Definition at line 69 of file HybridGaussianFactor.h.
using gtsam::HybridGaussianFactor::shared_ptr = std::shared_ptr<This> |
Definition at line 64 of file HybridGaussianFactor.h.
using gtsam::HybridGaussianFactor::sharedFactor = std::shared_ptr<GaussianFactor> |
Definition at line 66 of file HybridGaussianFactor.h.
Definition at line 63 of file HybridGaussianFactor.h.
|
default |
Default constructor, mainly for serialization.
gtsam::HybridGaussianFactor::HybridGaussianFactor | ( | 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).
discreteKey | The discrete key for the "mode", indexing components. |
factors | Vector of gaussian factors, one for each mode. |
Definition at line 100 of file HybridGaussianFactor.cpp.
gtsam::HybridGaussianFactor::HybridGaussianFactor | ( | const DiscreteKey & | discreteKey, |
const std::vector< GaussianFactorValuePair > & | factorPairs | ||
) |
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.
discreteKey | The discrete key for the "mode", indexing components. |
factorPairs | Vector of gaussian factor-scalar pairs, one per mode. |
Definition at line 105 of file HybridGaussianFactor.cpp.
gtsam::HybridGaussianFactor::HybridGaussianFactor | ( | const DiscreteKeys & | discreteKeys, |
const FactorValuePairs & | factorPairs | ||
) |
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.
discreteKeys | Discrete variables and their cardinalities. |
factorPairs | The decision tree of Gaussian factor/scalar pairs. |
Definition at line 110 of file HybridGaussianFactor.cpp.
|
private |
Definition at line 96 of file HybridGaussianFactor.cpp.
|
virtual |
Helper function to return factors and functional to create a DecisionTree of Gaussian Factor Graphs.
Definition at line 166 of file HybridGaussianFactor.cpp.
|
staticprivate |
Helper function to augment the [A|b] matrices in the factor components with the additional scalar values. This is done by storing the value in the b
vector as an additional row.
factors | DecisionTree of GaussianFactors and arbitrary scalars. |
|
overridevirtual |
equals
Reimplemented from gtsam::HybridFactor.
Definition at line 115 of file HybridGaussianFactor.cpp.
|
overridevirtual |
Compute the log-likelihood, including the log-normalizing constant.
Reimplemented from gtsam::Factor.
Definition at line 196 of file HybridGaussianFactor.cpp.
|
overridevirtual |
Compute error of the HybridGaussianFactor as a tree.
continuousValues | The continuous VectorValues. |
Implements gtsam::HybridFactor.
Definition at line 186 of file HybridGaussianFactor.cpp.
|
inline |
Getter for GaussianFactor decision tree.
Definition at line 150 of file HybridGaussianFactor.h.
GaussianFactorValuePair gtsam::HybridGaussianFactor::operator() | ( | const DiscreteValues & | assignment | ) | const |
Get factor at a given discrete assignment.
Definition at line 160 of file HybridGaussianFactor.cpp.
|
overridevirtual |
Reimplemented from gtsam::HybridFactor.
Definition at line 134 of file HybridGaussianFactor.cpp.
|
private |
Decision tree of Gaussian factors indexed by discrete keys.
Definition at line 73 of file HybridGaussianFactor.h.