Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
DataAssociationModel Class Referenceabstract

Data Association Method class, used to match observations to landmarks in the map. More...

#include <data_association.hpp>

Inheritance diagram for DataAssociationModel:
Inheritance graph
Collaboration diagram for DataAssociationModel:
Collaboration graph

Public Member Functions

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
 
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.
 

Protected Member Functions

float get_max_landmark_distance () const
 

Protected Attributes

DataAssociationParameters _params_
 

Private Attributes

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.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ DataAssociationModel() [1/3]

DataAssociationModel::DataAssociationModel ( float  max_landmark_distance)
explicit

Definition at line 10 of file data_association.cpp.

◆ ~DataAssociationModel() [1/2]

virtual DataAssociationModel::~DataAssociationModel ( )
virtualdefault

◆ DataAssociationModel() [2/3]

DataAssociationModel::DataAssociationModel ( )
default

◆ DataAssociationModel() [3/3]

DataAssociationModel::DataAssociationModel ( DataAssociationParameters  params)
inline

Definition at line 17 of file base_data_association.hpp.

◆ ~DataAssociationModel() [2/2]

virtual DataAssociationModel::~DataAssociationModel ( )
virtualdefault

Member Function Documentation

◆ 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
landmarksLandmarks in the form of [x1, y1, x2, y2, ...] in the global frame
observationsObservations in the form of [x1, y1, x2, y2, ...] in the global frame
covarianceCovariance matrix of the landmark vector
observation_confidencesConfidence 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_mapThe observed landmarks
_x_vector_The state vector
_p_matrix_The covariance matrix
matched_idsVector in which the ids of the matched landmarks will be placed
matched_cone_positionsVector in which the positions of the matched landmarks will be placed
new_featuresVector in which the positions of the new landmarks (unmatched landmarks) will be placed
observation_modelThe observation model
Returns
int Always 0

Implemented in MaxLikelihood.

◆ get_max_landmark_distance()

float DataAssociationModel::get_max_landmark_distance ( ) const
protected

Definition at line 14 of file data_association.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ _params_

DataAssociationParameters DataAssociationModel::_params_
protected

Definition at line 13 of file base_data_association.hpp.

◆ 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
deltaThe distance between the observed landmark and the expected
distance_to_vehicleThe 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: