Data association implementation that uses the Malhanobis Distance only as criterion to make observation matches.
More...
#include <maximum_likelihood_md.hpp>
Data association implementation that uses the Malhanobis Distance only as criterion to make observation matches.
Definition at line 13 of file maximum_likelihood_md.hpp.
◆ MaximumLikelihoodMD()
◆ ~MaximumLikelihoodMD()
| MaximumLikelihoodMD::~MaximumLikelihoodMD |
( |
| ) |
|
|
default |
◆ associate()
| Eigen::VectorXi MaximumLikelihoodMD::associate |
( |
const Eigen::VectorXd & |
landmarks, |
|
|
const Eigen::VectorXd & |
observations, |
|
|
const Eigen::MatrixXd & |
covariance, |
|
|
const Eigen::VectorXd & |
observation_confidences |
|
) |
| const |
|
overridevirtual |
This function associates the landmarks with the observations.
- Parameters
-
| landmarks | Landmarks in the form of [x1, y1, x2, y2, ...] in the global frame |
| observations | Observations in the form of [x1, y1, x2, y2, ...] in the global frame |
| covariance | Covariance matrix of the landmark vector |
| observation_confidences | Confidence in the observations in the same order as the observations |
- Returns
- Eigen::VectorXi Each entry corresponds to an observation and contains the index of the landmark that the observation is associated with in the landmark vector (x coordinate). If the observation is considered new, the entry is -1. If the observation is considered an outlier, the entry is -2.
Implements DataAssociationModel.
Definition at line 9 of file maximum_likelihood_md.cpp.
◆ observation_noise_covariance_matrix_
| Eigen::Matrix2d MaximumLikelihoodMD::observation_noise_covariance_matrix_ |
|
private |
The documentation for this class was generated from the following files: