Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
data_association.hpp File Reference
#include <gtest/gtest_prod.h>
#include <Eigen/Dense>
#include <functional>
#include <map>
#include <memory>
#include "common_lib/structures/cone.hpp"
#include "kalman_filter/observation_models.hpp"
Include dependency graph for data_association.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  DataAssociationModel
 Data Association Method class, used to match observations to landmarks in the map. More...
 
class  MaxLikelihood
 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...
 

Variables

const std::map< std::string, std::function< std::shared_ptr< DataAssociationModel >(float max_landmark_distance)>, std::less<> > data_association_model_constructors
 

Variable Documentation

◆ data_association_model_constructors

const std::map<std::string, std::function<std::shared_ptr<DataAssociationModel>(float max_landmark_distance)>, std::less<> > data_association_model_constructors
Initial value:
= {
{"max_likelihood",
[](float max_landmark_distance) -> std::shared_ptr<DataAssociationModel> {
return std::make_shared<MaxLikelihood>(max_landmark_distance);
}}}

Definition at line 114 of file data_association.hpp.