Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
maximum_likelihood_nll.hpp
Go to the documentation of this file.
1#pragma once
2#include <memory>
3#include <rclcpp/rclcpp.hpp>
4
7
15
16public:
22
24
25 Eigen::VectorXi associate(const Eigen::VectorXd& landmarks, const Eigen::VectorXd& observations,
26 const Eigen::MatrixXd& covariance,
27 const Eigen::VectorXd& observation_confidences) const override;
28};
Data Association Method class, used to match observations to landmarks in the map.
Data association implementation that uses the Negative Log-Likehood as criterion to make observation ...
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.
Eigen::Matrix2d observation_noise_covariance_matrix_
~MaximumLikelihoodNLL()=default
MaximumLikelihoodNLL(const DataAssociationParameters &params)