|
Autoware.Auto
|
|
#include <ndt_voxel.hpp>
Public Types | |
| using | Point = Eigen::Vector3d |
| using | Cov = Eigen::Matrix3d |
Public Member Functions | |
| StaticNDTVoxel () | |
| Initialize an empty voxel. More... | |
| StaticNDTVoxel (const Point ¢roid, const Cov &inv_covariance) | |
| Cov | covariance () const |
| const Point & | centroid () const |
| const Cov & | inverse_covariance () const |
| bool8_t | usable () const noexcept |
Static Voxel implementation for the NDT map. A static voxel is used to represent a pre-computed ndt cell, hence it doesn't contain any logic for updating its states.
| using autoware::localization::ndt::StaticNDTVoxel::Cov = Eigen::Matrix3d |
| using autoware::localization::ndt::StaticNDTVoxel::Point = Eigen::Vector3d |
| autoware::localization::ndt::StaticNDTVoxel::StaticNDTVoxel | ( | ) |
Initialize an empty voxel.
| autoware::localization::ndt::StaticNDTVoxel::StaticNDTVoxel | ( | const Point & | centroid, |
| const Cov & | inv_covariance | ||
| ) |
Initialize a voxel given the centroid and the covariance.
| centroid | Centroid of the voxel. |
| inv_covariance | Covariance of the voxel. |
| const Eigen::Vector3d & autoware::localization::ndt::StaticNDTVoxel::centroid | ( | ) | const |
Returns the mean of the points in the cell. Throw if voxel is empty.
| Eigen::Matrix3d autoware::localization::ndt::StaticNDTVoxel::covariance | ( | ) | const |
Calculates and returns the covariance of the points in the voxel. Throw if voxel is empty.
| const Eigen::Matrix3d & autoware::localization::ndt::StaticNDTVoxel::inverse_covariance | ( | ) | const |
Returns the inverse covariance of the points in the voxel. Throw if voxel is empty.
|
noexcept |
Check if the cell is occupied and can be used in ndt matching