|
Autoware.Auto
|
|
Functions | |
| template<std::int32_t kNumOfStates> | |
| bool | passes_mahalanobis_gate (const Eigen::Matrix< common::types::float32_t, kNumOfStates, 1 > &sample, const Eigen::Matrix< common::types::float32_t, kNumOfStates, 1 > &mean, const Eigen::Matrix< common::types::float32_t, kNumOfStates, kNumOfStates > &covariance_factor, const common::types::float32_t mahalanobis_threshold) |
| bool autoware::prediction::detail::passes_mahalanobis_gate | ( | const Eigen::Matrix< common::types::float32_t, kNumOfStates, 1 > & | sample, |
| const Eigen::Matrix< common::types::float32_t, kNumOfStates, 1 > & | mean, | ||
| const Eigen::Matrix< common::types::float32_t, kNumOfStates, kNumOfStates > & | covariance_factor, | ||
| const common::types::float32_t | mahalanobis_threshold | ||
| ) |
Check if the sample passes the Mahalanobis gate.
| [in] | sample | The input sample |
| [in] | mean | The mean to be compared against |
| [in] | covariance_factor | Covariance around the given mean |
| [in] | mahalanobis_threshold | The mahalanobis threshold factor |
| kNumOfStates | Number of states in the state vector. |