|
Formula Student Autonomous Systems
The code for the main driverless system
|
Data association implementation that uses the Malhanobis Distance only as criterion to make observation matches. More...
#include <nearest_neighbor.hpp>


Public Member Functions | |
| NearestNeighbor (const DataAssociationParameters ¶ms) | |
| ~NearestNeighbor ()=default | |
| Eigen::VectorXi | associate (const Eigen::VectorXd &landmarks, const Eigen::VectorXd &observations, const Eigen::MatrixXd &covariance, const Eigen::VectorXd &observation_confidences) const override |
| This function associates the landmarks with the observations. | |
Public Member Functions inherited from DataAssociationModel | |
| virtual 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 =0 |
| Associate the observed landmarks to the expected landmarks and update the state vector and the covariance matrix. | |
| DataAssociationModel (float max_landmark_distance) | |
| virtual | ~DataAssociationModel ()=default |
| DataAssociationModel ()=default | |
| DataAssociationModel (DataAssociationParameters params) | |
| virtual | ~DataAssociationModel ()=default |
Additional Inherited Members | |
Protected Member Functions inherited from DataAssociationModel | |
| float | get_max_landmark_distance () const |
Protected Attributes inherited from DataAssociationModel | |
| DataAssociationParameters | _params_ |
Data association implementation that uses the Malhanobis Distance only as criterion to make observation matches.
Definition at line 13 of file nearest_neighbor.hpp.
| NearestNeighbor::NearestNeighbor | ( | const DataAssociationParameters & | params | ) |
Definition at line 6 of file nearest_neighbor.cpp.
|
default |
|
overridevirtual |
This function associates the landmarks with the observations.
| 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 |
Implements DataAssociationModel.
Definition at line 16 of file nearest_neighbor.cpp.
