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 gtsam::NonlinearFactor type of measurement.
More...
#include <DCMixtureFactor.h>
|
| | DCMixtureFactor ()=default |
| |
| | DCMixtureFactor (const gtsam::KeyVector &keys, const gtsam::DiscreteKey &dk, const std::vector< NonlinearFactorType > &factors, bool normalized=false) |
| |
| DCMixtureFactor & | operator= (const DCMixtureFactor &rhs) |
| |
| | ~DCMixtureFactor ()=default |
| |
| double | error (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) const override |
| |
| 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 |
| |
| | DCFactor ()=default |
| |
| | DCFactor (const gtsam::KeyVector &continuousKeys, const gtsam::DiscreteKeys &discreteKeys) |
| |
| | DCFactor (const gtsam::DiscreteKeys &discreteKeys) |
| |
| DCFactor & | operator= (const DCFactor &rhs) |
| |
| virtual | ~DCFactor ()=default |
| |
| 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 |
| |
template<class NonlinearFactorType>
class dcsam::DCMixtureFactor< NonlinearFactorType >
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 gtsam::NonlinearFactor type of measurement.
◆ Base
template<class NonlinearFactorType >
◆ DCMixtureFactor() [1/2]
template<class NonlinearFactorType >
◆ DCMixtureFactor() [2/2]
template<class NonlinearFactorType >
| dcsam::DCMixtureFactor< NonlinearFactorType >::DCMixtureFactor |
( |
const gtsam::KeyVector & |
keys, |
|
|
const gtsam::DiscreteKey & |
dk, |
|
|
const std::vector< NonlinearFactorType > & |
factors, |
|
|
bool |
normalized = false |
|
) |
| |
|
inline |
◆ ~DCMixtureFactor()
template<class NonlinearFactorType >
◆ dim()
template<class NonlinearFactorType >
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 NonlinearFactorType >
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 NonlinearFactorType >
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.
◆ linearize()
template<class NonlinearFactorType >
| boost::shared_ptr<gtsam::GaussianFactor> dcsam::DCMixtureFactor< NonlinearFactorType >::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 NonlinearFactorType >
The documentation for this class was generated from the following file: