dcsam
Factored inference for discrete-continuous smoothing and mapping
dcsam::DCMaxMixtureFactor< DCFactorType > Class Template Reference

Implementation of a discrete-continuous max-mixture factor. More...

#include <DCMaxMixtureFactor.h>

Inheritance diagram for dcsam::DCMaxMixtureFactor< DCFactorType >:
Collaboration diagram for dcsam::DCMaxMixtureFactor< DCFactorType >:

Public Types

using Base = DCFactor
 
- Public Types inherited from dcsam::DCFactor
using Base = gtsam::Factor
 

Public Member Functions

 DCMaxMixtureFactor ()=default
 
 DCMaxMixtureFactor (const gtsam::KeyVector &continuousKeys, const gtsam::DiscreteKeys &discreteKeys, const std::vector< DCFactorType > factors, const std::vector< double > weights, const bool normalized)
 
 DCMaxMixtureFactor (const gtsam::KeyVector &continuousKeys, const gtsam::DiscreteKeys &discreteKeys, const std::vector< DCFactorType > factors, const bool normalized)
 
DCMaxMixtureFactoroperator= (const DCMaxMixtureFactor &rhs)
 
virtual ~DCMaxMixtureFactor ()=default
 
double error (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const override
 
size_t getActiveFactorIdx (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const
 
size_t dim () const override
 
bool equals (const DCFactor &other, double tol=1e-9) const override
 
boost::shared_ptr< gtsam::GaussianFactor > linearize (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const override
 
gtsam::DecisionTreeFactor uniformDecisionTreeFactor (const gtsam::DiscreteKey &dk) const
 
gtsam::DecisionTreeFactor toDecisionTreeFactor (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const override
 
gtsam::FastVector< gtsam::Key > getAssociationKeys (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const
 
void updateWeights (const std::vector< double > &weights)
 
- Public Member Functions inherited from dcsam::DCFactor
 DCFactor ()=default
 
 DCFactor (const gtsam::KeyVector &continuousKeys, const gtsam::DiscreteKeys &discreteKeys)
 
 DCFactor (const gtsam::DiscreteKeys &discreteKeys)
 
DCFactoroperator= (const DCFactor &rhs)
 
virtual ~DCFactor ()=default
 
gtsam::DiscreteKeys discreteKeys () const
 
virtual double logNormalizingConstant (const gtsam::Values &values) const
 
template<typename NonlinearFactorType >
double nonlinearFactorLogNormalizingConstant (const NonlinearFactorType &factor, const gtsam::Values &values) const
 
std::vector< double > evalProbs (const gtsam::DiscreteKey &dk, const gtsam::Values &continuousVals) const
 
gtsam::DecisionTreeFactor conditionalTimes (const gtsam::DecisionTreeFactor &f, const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const
 

Additional Inherited Members

- Protected Attributes inherited from dcsam::DCFactor
gtsam::DiscreteKeys discreteKeys_
 

Detailed Description

template<class DCFactorType>
class dcsam::DCMaxMixtureFactor< DCFactorType >

Implementation of a discrete-continuous max-mixture factor.

r(x) = min_i -log(w_i) + r_i(x)

The error returned from this factor is the minimum error + weight over all of the component factors See Olson and Agarwal RSS 2012 for details

Member Typedef Documentation

◆ Base

template<class DCFactorType >
using dcsam::DCMaxMixtureFactor< DCFactorType >::Base = DCFactor

Constructor & Destructor Documentation

◆ DCMaxMixtureFactor() [1/3]

template<class DCFactorType >
dcsam::DCMaxMixtureFactor< DCFactorType >::DCMaxMixtureFactor ( )
default

◆ DCMaxMixtureFactor() [2/3]

template<class DCFactorType >
dcsam::DCMaxMixtureFactor< DCFactorType >::DCMaxMixtureFactor ( const gtsam::KeyVector &  continuousKeys,
const gtsam::DiscreteKeys &  discreteKeys,
const std::vector< DCFactorType >  factors,
const std::vector< double >  weights,
const bool  normalized 
)
inlineexplicit

◆ DCMaxMixtureFactor() [3/3]

template<class DCFactorType >
dcsam::DCMaxMixtureFactor< DCFactorType >::DCMaxMixtureFactor ( const gtsam::KeyVector &  continuousKeys,
const gtsam::DiscreteKeys &  discreteKeys,
const std::vector< DCFactorType >  factors,
const bool  normalized 
)
inlineexplicit

◆ ~DCMaxMixtureFactor()

template<class DCFactorType >
virtual dcsam::DCMaxMixtureFactor< DCFactorType >::~DCMaxMixtureFactor ( )
virtualdefault

Member Function Documentation

◆ dim()

template<class DCFactorType >
size_t dcsam::DCMaxMixtureFactor< DCFactorType >::dim ( ) const
inlineoverridevirtual

Returns the number of rows in the Jacobian with respect to the continuous variables for this factor. Internally this is used in the conversion to a gtsam::NonlinearFactor

TODO(kevin): not sure if needed???

This will be specific to the model being implemented, so it is a pure virtual function and must be overridden

Returns
the dimension (number of rows) in the Jacobian of the error function with respect to continuous variables for

Implements dcsam::DCFactor.

◆ equals()

template<class DCFactorType >
bool dcsam::DCMaxMixtureFactor< DCFactorType >::equals ( const DCFactor other,
double  tol = 1e-9 
) const
inlineoverridevirtual

Returns true when the DCFactor is equal to other

This will be specific to the model being implemented, so it is a pure virtual function and must be overridden.

Parameters
other- the DCFactor for which to test equality.
tol= 1e-9 - numerical tolerance for any floating point comparisons.

Implements dcsam::DCFactor.

◆ error()

template<class DCFactorType >
double dcsam::DCMaxMixtureFactor< DCFactorType >::error ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inlineoverridevirtual

Return the error for the DCFactor given an assignment to the variables referenced by the discrete keys and the continuous keys (keys_).

This will be specific to the model being implemented, so it is a pure virtual function and must be overridden.

NOTE: Depending on the application, it may be important that the error function is normalized, i.e. it corresponds to a proper negative log-likelihood, rather than the negative log-likelihood with normalization constants discarded.

Parameters
continuousVals- the values assigned to the continuous variables, must contain keys in keys_ member variable
discreteVals- likewise, the values assigned to discrete variables, must contain keys in discreteKeys_
Returns
error (usually the negative log-likelihood) for the measurement model as a double.

Implements dcsam::DCFactor.

◆ getActiveFactorIdx()

template<class DCFactorType >
size_t dcsam::DCMaxMixtureFactor< DCFactorType >::getActiveFactorIdx ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inline

◆ getAssociationKeys()

template<class DCFactorType >
gtsam::FastVector<gtsam::Key> dcsam::DCMaxMixtureFactor< DCFactorType >::getAssociationKeys ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inline

◆ linearize()

template<class DCFactorType >
boost::shared_ptr<gtsam::GaussianFactor> dcsam::DCMaxMixtureFactor< DCFactorType >::linearize ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inlineoverridevirtual

Linearize the error function with respect to the continuous variables (given in keys_) at the point specified by continuousVals. Since this Jacobian can be dependent on the assignment to discrete variables as well, they are required as a parameter.

This will be specific to the model being implemented, so it is a pure virtual function and must be overridden.

Parameters
continuousVals- Assignment to the continuous variables in keys_
discreteVals- Likewise, assignment to the discrete variables in discreteKeys__.

Implements dcsam::DCFactor.

◆ operator=()

template<class DCFactorType >
DCMaxMixtureFactor& dcsam::DCMaxMixtureFactor< DCFactorType >::operator= ( const DCMaxMixtureFactor< DCFactorType > &  rhs)
inline

◆ toDecisionTreeFactor()

template<class DCFactorType >
gtsam::DecisionTreeFactor dcsam::DCMaxMixtureFactor< DCFactorType >::toDecisionTreeFactor ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inlineoverridevirtual

Converts the DCFactor to a gtsam::DecisionTreeFactor. Internally, this will be used to generate a gtsam::DiscreteFactor type, which itself requires a conversion function to gtsam::DecisionTreeFactor for inference using GTSAM.

Performing this conversion can be problem specific, so we allow for the option to override, but try to implement a sensible default: we assume the error function can be called setting each discrete key's variable individually, and the overall DCFactor can itself be factored as a product of unary gtsam::DecisionTreeFactors.

Alternative implementations might consider something like the gtsam::AllDiff approach here: https://github.com/borglab/gtsam/blob/43e8f1e5aeaf11890262722c1e5e04a11dbf9d75/gtsam_unstable/discrete/AllDiff.cpp#L43

Parameters
continuousVals- an assignment to the continuous variables
discreteVals-
Returns
a gtsam::DecisionTreeFactor implementing this DCFactor.

Reimplemented from dcsam::DCFactor.

◆ uniformDecisionTreeFactor()

template<class DCFactorType >
gtsam::DecisionTreeFactor dcsam::DCMaxMixtureFactor< DCFactorType >::uniformDecisionTreeFactor ( const gtsam::DiscreteKey &  dk) const
inline

◆ updateWeights()

template<class DCFactorType >
void dcsam::DCMaxMixtureFactor< DCFactorType >::updateWeights ( const std::vector< double > &  weights)
inline

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