Loading [MathJax]/extensions/tex2jax.js
Autoware.Auto
autoware::localization::ndt::StaticNDTVoxel Class Reference

#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 &centroid, const Cov &inv_covariance)
 
Cov covariance () const
 
const Pointcentroid () const
 
const Covinverse_covariance () const
 
bool8_t usable () const noexcept
 

Detailed Description

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.

Member Typedef Documentation

◆ Cov

◆ Point

Constructor & Destructor Documentation

◆ StaticNDTVoxel() [1/2]

autoware::localization::ndt::StaticNDTVoxel::StaticNDTVoxel ( )

Initialize an empty voxel.

◆ StaticNDTVoxel() [2/2]

autoware::localization::ndt::StaticNDTVoxel::StaticNDTVoxel ( const Point centroid,
const Cov inv_covariance 
)

Initialize a voxel given the centroid and the covariance.

Parameters
centroidCentroid of the voxel.
inv_covarianceCovariance of the voxel.

Member Function Documentation

◆ centroid()

const Eigen::Vector3d & autoware::localization::ndt::StaticNDTVoxel::centroid ( ) const

Returns the mean of the points in the cell. Throw if voxel is empty.

Returns
centroid of the cell

◆ covariance()

Eigen::Matrix3d autoware::localization::ndt::StaticNDTVoxel::covariance ( ) const

Calculates and returns the covariance of the points in the voxel. Throw if voxel is empty.

Returns
covariance of the cell

◆ inverse_covariance()

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.

Returns
inverse covariance of the cell

◆ usable()

bool8_t autoware::localization::ndt::StaticNDTVoxel::usable ( ) const
noexcept

Check if the cell is occupied and can be used in ndt matching

Returns
True if cell is occupied

The documentation for this class was generated from the following files: