dcsam
Factored inference for discrete-continuous smoothing and mapping
dcsam::DCFactor Class Referenceabstract

Abstract class implementing a discrete-continuous factor. More...

#include <DCFactor.h>

Inheritance diagram for dcsam::DCFactor:
Collaboration diagram for dcsam::DCFactor:

Public Types

using Base = gtsam::Factor
 

Public Member Functions

 DCFactor ()=default
 
 DCFactor (const gtsam::KeyVector &continuousKeys, const gtsam::DiscreteKeys &discreteKeys)
 
 DCFactor (const gtsam::DiscreteKeys &discreteKeys)
 
DCFactoroperator= (const DCFactor &rhs)
 
virtual ~DCFactor ()=default
 
virtual double error (const gtsam::Values &continuousVals, const gtsam::DiscreteFactor::Values &discreteVals) const =0
 
virtual boost::shared_ptr< gtsam::GaussianFactor > linearize (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const =0
 
virtual bool equals (const DCFactor &other, double tol=1e-9) const =0
 
virtual size_t dim () const =0
 
gtsam::DiscreteKeys discreteKeys () const
 
virtual gtsam::DecisionTreeFactor toDecisionTreeFactor (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) 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
 

Protected Attributes

gtsam::DiscreteKeys discreteKeys_
 

Detailed Description

Abstract class implementing a discrete-continuous factor.

keys_ member variable stores keys for continuous variables. discreteKeys_ contains the keys (plus cardinalities) for discrete variables.

Member Typedef Documentation

◆ Base

using dcsam::DCFactor::Base = gtsam::Factor

Constructor & Destructor Documentation

◆ DCFactor() [1/3]

dcsam::DCFactor::DCFactor ( )
default

◆ DCFactor() [2/3]

dcsam::DCFactor::DCFactor ( const gtsam::KeyVector &  continuousKeys,
const gtsam::DiscreteKeys &  discreteKeys 
)
inline

Base constructor for a DCFactor from a set of discrete keys and continuous keys

Parameters
continuousKeys- the keys for continuous variables
discreteKeys- the keys for discrete variables

◆ DCFactor() [3/3]

dcsam::DCFactor::DCFactor ( const gtsam::DiscreteKeys &  discreteKeys)
inlineexplicit

◆ ~DCFactor()

virtual dcsam::DCFactor::~DCFactor ( )
virtualdefault

Member Function Documentation

◆ conditionalTimes()

gtsam::DecisionTreeFactor dcsam::DCFactor::conditionalTimes ( const gtsam::DecisionTreeFactor &  f,
const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inline

Take the product of this DCFactor (as a gtsam::DecisionTreeFactor) conditioned on an assignment to the continous variables, continuousVals with another gtsam::DecisionTreeFactor f. Used internally by GTSAM to solve discrete factor graphs.

Parameters
f- the gtsam::DecisionTreeFactor to be multiplied by this DCFactor
continuousVals- an assignment to the continuous variables (specified by keys_).
Returns
a gtsam::DecisionTreeFactor representing the product of this factor with f.

◆ dim()

virtual size_t dcsam::DCFactor::dim ( ) const
pure virtual

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

Implemented in dcsam::SemanticBearingRangeFactor< PoseType, PointType, BearingType, RangeType >, dcsam::DCMixtureFactor< NonlinearFactorType >, dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.

◆ discreteKeys()

gtsam::DiscreteKeys dcsam::DCFactor::discreteKeys ( ) const
inline

◆ equals()

virtual bool dcsam::DCFactor::equals ( const DCFactor other,
double  tol = 1e-9 
) const
pure virtual

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.

Implemented in dcsam::SemanticBearingRangeFactor< PoseType, PointType, BearingType, RangeType >, dcsam::DCMixtureFactor< NonlinearFactorType >, dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.

◆ error()

virtual double dcsam::DCFactor::error ( const gtsam::Values &  continuousVals,
const gtsam::DiscreteFactor::Values &  discreteVals 
) const
pure virtual

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.

Implemented in dcsam::SemanticBearingRangeFactor< PoseType, PointType, BearingType, RangeType >, dcsam::DCMixtureFactor< NonlinearFactorType >, dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.

◆ evalProbs()

std::vector<double> dcsam::DCFactor::evalProbs ( const gtsam::DiscreteKey &  dk,
const gtsam::Values &  continuousVals 
) const
inline

Obtain the likelihood function for a single discrete variable conditioned on continuous values. Since the error function typically represents the negative log-likelihood, we compute exp(-error).

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.

For this, we assume that the error function can be called with only a single discrete value set, though this may be dependent on the particular implementation behavior desired. At present, this is only used internally to specify the default behavior for toDecisionTreeFactor.

Parameters
dk- the discrete key to evaluate the likelihood for
continuousVals- an assignment to the continuous valued variables
Returns
a vector of length == cardinality of dk specifying the probability of each possible assignment to dk.

◆ linearize()

virtual boost::shared_ptr<gtsam::GaussianFactor> dcsam::DCFactor::linearize ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
pure virtual

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__.

Implemented in dcsam::SemanticBearingRangeFactor< PoseType, PointType, BearingType, RangeType >, dcsam::DCMixtureFactor< NonlinearFactorType >, dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.

◆ logNormalizingConstant()

virtual double dcsam::DCFactor::logNormalizingConstant ( const gtsam::Values &  values) const
inlinevirtual

Calculate a normalizing constant for this DCFactor. Most implementations will be able to use the helper function nonlinearFactorLogNormalizingConstant provided below for most of the calculation. TODO(Kurran) is this the cleanest way to do this? Seems necessary for the DCMaxMixtureFactor implementations etc...

Reimplemented in dcsam::SemanticBearingRangeFactor< PoseType, PointType, BearingType, RangeType >.

◆ nonlinearFactorLogNormalizingConstant()

template<typename NonlinearFactorType >
double dcsam::DCFactor::nonlinearFactorLogNormalizingConstant ( const NonlinearFactorType &  factor,
const gtsam::Values &  values 
) const
inline

Default for computing the negative normalizing constant for the measurement likelihood (since we are minimizing the negative log-likelihood), to be used as a utility for computing the DCFactorLogNormalizingConstant.

◆ operator=()

DCFactor& dcsam::DCFactor::operator= ( const DCFactor rhs)
inline

◆ toDecisionTreeFactor()

virtual gtsam::DecisionTreeFactor dcsam::DCFactor::toDecisionTreeFactor ( const gtsam::Values &  continuousVals,
const DiscreteValues discreteVals 
) const
inlinevirtual

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 in dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.

Member Data Documentation

◆ discreteKeys_

gtsam::DiscreteKeys dcsam::DCFactor::discreteKeys_
protected

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