|
dcsam
Factored inference for discrete-continuous smoothing and mapping
|
Abstract class implementing a discrete-continuous factor. More...
#include <DCFactor.h>


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) | |
| DCFactor & | operator= (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_ |
Abstract class implementing a discrete-continuous factor.
keys_ member variable stores keys for continuous variables. discreteKeys_ contains the keys (plus cardinalities) for discrete variables.
| using dcsam::DCFactor::Base = gtsam::Factor |
|
default |
|
inline |
Base constructor for a DCFactor from a set of discrete keys and continuous keys
| continuousKeys | - the keys for continuous variables |
| discreteKeys | - the keys for discrete variables |
|
inlineexplicit |
|
virtualdefault |
|
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.
| f | - the gtsam::DecisionTreeFactor to be multiplied by this DCFactor |
| continuousVals | - an assignment to the continuous variables (specified by keys_). |
f.
|
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
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 >.
|
inline |
|
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.
| 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 >.
|
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.
| 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_ |
Implemented in dcsam::SemanticBearingRangeFactor< PoseType, PointType, BearingType, RangeType >, dcsam::DCMixtureFactor< NonlinearFactorType >, dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.
|
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.
| dk | - the discrete key to evaluate the likelihood for |
| continuousVals | - an assignment to the continuous valued variables |
|
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.
| 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 >.
|
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 >.
|
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.
|
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
| continuousVals | - an assignment to the continuous variables |
| discreteVals | - |
Reimplemented in dcsam::DCMaxMixtureFactor< DCFactorType >, and dcsam::DCEMFactor< DCFactorType >.
|
protected |