Data Association Method class, used to match observations to landmarks in the map.
More...
#include <data_association.hpp>
|
| float | max_landmark_distance_ |
| | Check if the observed landmark is a valid match to the expected landmark It depends on external parameters like the distance to the vehicle.
|
| |
Data Association Method class, used to match observations to landmarks in the map.
Data association models are responsible for associating landmarks with observations given the current state, covariance, and confidences in the observations.
Definition at line 17 of file data_association.hpp.
◆ DataAssociationModel() [1/3]
| DataAssociationModel::DataAssociationModel |
( |
float |
max_landmark_distance | ) |
|
|
explicit |
◆ ~DataAssociationModel() [1/2]
| virtual DataAssociationModel::~DataAssociationModel |
( |
| ) |
|
|
virtualdefault |
◆ DataAssociationModel() [2/3]
| DataAssociationModel::DataAssociationModel |
( |
| ) |
|
|
default |
◆ DataAssociationModel() [3/3]
◆ ~DataAssociationModel() [2/2]
| virtual DataAssociationModel::~DataAssociationModel |
( |
| ) |
|
|
virtualdefault |
◆ associate()
| virtual Eigen::VectorXi DataAssociationModel::associate |
( |
const Eigen::VectorXd & |
landmarks, |
|
|
const Eigen::VectorXd & |
observations, |
|
|
const Eigen::MatrixXd & |
covariance, |
|
|
const Eigen::VectorXd & |
observation_confidences |
|
) |
| const |
|
pure virtual |
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.
Implemented in JCBB, MaximumLikelihoodMD, MaximumLikelihoodNLL, and NearestNeighbor.
◆ associate_n_filter()
| virtual int DataAssociationModel::associate_n_filter |
( |
const std::vector< common_lib::structures::Cone > & |
perception_map, |
|
|
Eigen::VectorXf & |
_x_vector_, |
|
|
Eigen::MatrixXf & |
_p_matrix_, |
|
|
std::vector< int > & |
matched_ids, |
|
|
std::vector< Eigen::Vector2f > & |
matched_cone_positions, |
|
|
std::vector< Eigen::Vector2f > & |
new_features, |
|
|
ObservationModel * |
observation_model |
|
) |
| const |
|
pure virtual |
Associate the observed landmarks to the expected landmarks and update the state vector and the covariance matrix.
- Parameters
-
| perception_map | The observed landmarks |
| _x_vector_ | The state vector |
| _p_matrix_ | The covariance matrix |
| matched_ids | Vector in which the ids of the matched landmarks will be placed |
| matched_cone_positions | Vector in which the positions of the matched landmarks will be placed |
| new_features | Vector in which the positions of the new landmarks (unmatched landmarks) will be placed |
| observation_model | The observation model |
- Returns
- int Always 0
Implemented in MaxLikelihood.
◆ get_max_landmark_distance()
| float DataAssociationModel::get_max_landmark_distance |
( |
| ) |
const |
|
protected |
◆ _params_
◆ max_landmark_distance_
| float DataAssociationModel::max_landmark_distance_ |
|
private |
Check if the observed landmark is a valid match to the expected landmark It depends on external parameters like the distance to the vehicle.
- Parameters
-
| delta | The distance between the observed landmark and the expected |
| distance_to_vehicle | The distance between the vehicle and the observed landmark |
- Returns
- bool True if the observed landmark is a valid match to the expected landmark Maximum distance from the car to a cone for it to be considered in the State Estimation. Cones farther away will be ignored.
Definition at line 31 of file data_association.hpp.
The documentation for this class was generated from the following files: