Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
maximum_likelihood_nll.cpp
Go to the documentation of this file.
2
3#include <cmath>
4#include <limits>
5#include <vector>
6
8 const Eigen::VectorXd& landmarks, const Eigen::VectorXd& observations,
9 const Eigen::MatrixXd& covariance, const Eigen::VectorXd& observation_confidences) const {
10 const int num_observations = observations.size() / 2;
11 const int num_landmarks = landmarks.size() / 2;
12 Eigen::VectorXi associations =
13 Eigen::VectorXi::Constant(num_observations, -2); // Default: not associated (-2)
14
15 for (int i = 0; i < num_observations; i++) {
16 Eigen::Vector2d obs;
17 obs << observations(2 * i), observations(2 * i + 1);
18
19 double best_cost = std::numeric_limits<double>::max();
20 int best_landmark_index = -1;
21
22 for (int j = 0; j < num_landmarks; j++) {
23 // Innovation: difference between observations and landmarks
24 Eigen::Vector2d innovation = obs - landmarks.segment(2 * j, 2);
25
26 Eigen::Matrix2d innovation_covariance =
27 covariance.block(2 * j, 2 * j, 2, 2) + this->observation_noise_covariance_matrix_;
28
29 // Guard against non-invertible innovation_covariance
30 double det = innovation_covariance.determinant();
31 if (det == 0) {
32 RCLCPP_WARN(rclcpp::get_logger("data_association"),
33 "Non-invertible innovation covariance matrix for landmark at: [%f, %f]",
34 landmarks(2 * j), landmarks(2 * j + 1));
35 continue;
36 }
37 if (det < 1e-9) det = 1e-9;
38
39 double normalized_innovation_squared =
40 innovation.transpose() * innovation_covariance.inverse() * innovation;
41 double cost = normalized_innovation_squared + std::log(det);
42 // Check if this landmark is a good candidate for association
43 if (normalized_innovation_squared < this->_params_.association_gate && cost < best_cost) {
44 best_cost = cost;
45 best_landmark_index = 2 * j;
46 }
47 }
48
49 if (best_landmark_index != -1) {
50 associations(i) = best_landmark_index;
51 } else if (observation_confidences[i] > this->_params_.new_landmark_confidence_gate) {
52 associations(i) = -1; // New landmark
53 }
54 }
55
56 return associations;
57}
DataAssociationParameters _params_
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_