|
Formula Student Autonomous Systems
The code for the main driverless system
|
Maximum Likelihood Method class, used to match observations to landmarks in the map with maximum likelihood method It uses the Mahalanobis distance to determine the best match It also uses a gate to determine if the match is valid The Mahalanobis distance is calculated as the square root of the innovation covariance The gate is a threshold that the Mahalanobis distance must be below to be considered a valid match The gate is defined as the normalized innovation squared (NIS) gate Normalized Distance. More...
#include <data_association.hpp>


Public Member Functions | |
| int | 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 override |
| normalized distance gate (closest unmatched landmark) | |
| MaxLikelihood (float max_landmark_distance) | |
| Construct a new Max Likelihood object. | |
Public Member Functions inherited from DataAssociationModel | |
| DataAssociationModel (float max_landmark_distance) | |
| virtual | ~DataAssociationModel ()=default |
| DataAssociationModel ()=default | |
| DataAssociationModel (DataAssociationParameters params) | |
| virtual | ~DataAssociationModel ()=default |
| virtual Eigen::VectorXi | associate (const Eigen::VectorXd &landmarks, const Eigen::VectorXd &observations, const Eigen::MatrixXd &covariance, const Eigen::VectorXd &observation_confidences) const =0 |
| This function associates the landmarks with the observations. | |
Static Public Attributes | |
| static float | association_gate_ = 4.991f |
| static float | new_landmark_gate_ = 20.0f |
| normalized innovation squared gate | |
Additional Inherited Members | |
Protected Member Functions inherited from DataAssociationModel | |
| float | get_max_landmark_distance () const |
Protected Attributes inherited from DataAssociationModel | |
| DataAssociationParameters | _params_ |
Maximum Likelihood Method class, used to match observations to landmarks in the map with maximum likelihood method It uses the Mahalanobis distance to determine the best match It also uses a gate to determine if the match is valid The Mahalanobis distance is calculated as the square root of the innovation covariance The gate is a threshold that the Mahalanobis distance must be below to be considered a valid match The gate is defined as the normalized innovation squared (NIS) gate Normalized Distance.
Definition at line 71 of file data_association.hpp.
|
explicit |
Construct a new Max Likelihood object.
| max_landmark_distance | Maximum distance from the car to an observed landmark for it to be considered in the state estimation |
Definition at line 20 of file data_association.cpp.
|
overridevirtual |
normalized distance gate (closest unmatched landmark)
Associate the observed landmarks to the expected landmarks and update the state vector and the covariance matrix
| 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 |
Implements DataAssociationModel.
Definition at line 27 of file data_association.cpp.


|
static |
Definition at line 75 of file data_association.hpp.
|
static |
normalized innovation squared gate
Definition at line 76 of file data_association.hpp.