Autoware.Auto
autoware::localization::ndt::NDTGrid< VoxelT > Class Template Reference

A voxel grid implementation for normal distribution transform. More...

#include <ndt_grid.hpp>

Public Types

using Grid = std::unordered_map< uint64_t, VoxelT >
 
using Point = Eigen::Vector3d
 
using Config = autoware::perception::filters::voxel_grid::Config
 
using VoxelViewVector = std::vector< VoxelView< VoxelT > >
 
using ConfigPoint = std::decay_t< decltype(std::declval< Config >().get_min_point())>
 

Public Member Functions

 NDTGrid (const Config &voxel_grid_config)
 
 NDTGrid (const NDTGrid &)=delete
 
NDTGridoperator= (const NDTGrid &)=delete
 
 NDTGrid (NDTGrid &&)=default
 
NDTGridoperator= (NDTGrid &&)=default
 
const VoxelViewVectorcell (float32_t x, float32_t y, float32_t z) const
 
const VoxelViewVectorcell (const Point &pt) const
 
std::size_t size () const noexcept
 
const ConfigPointcell_size () const noexcept
 
Grid::const_iterator begin () const noexcept
 Returns an const iterator to the first element of the map. More...
 
Grid::iterator begin () noexcept
 Returns an iterator to the first element of the map. More...
 
Grid::const_iterator cbegin () const noexcept
 Returns a const iterator to the first element of the map. More...
 
Grid::const_iterator end () const noexcept
 Returns a const iterator to one past the last element of the map. More...
 
Grid::iterator end () noexcept
 Returns an iterator to one past the last element of the map. More...
 
Grid::const_iterator cend () const noexcept
 Returns a const iterator to one past the last element of the map. More...
 
void clear () noexcept
 Clear all voxels in the map. More...
 
auto index (const Point &pt) const
 
template<typename ... Args>
auto emplace_voxel (Args &&... args)
 Emplace a new voxel into the grid. More...
 
void add_observation (const Point &pt)
 Add a point to its corresponding voxel in the grid. More...
 
void set_config (const Config &config)
 Set the configuration. More...
 
const Configconfig () const
 Get the underlying voxel grid configuration. More...
 

Detailed Description

template<typename VoxelT>
class autoware::localization::ndt::NDTGrid< VoxelT >

A voxel grid implementation for normal distribution transform.

Template Parameters
VoxelTVoxel type

Member Typedef Documentation

◆ Config

◆ ConfigPoint

template<typename VoxelT >
using autoware::localization::ndt::NDTGrid< VoxelT >::ConfigPoint = std::decay_t<decltype(std::declval<Config>().get_min_point())>

◆ Grid

template<typename VoxelT >
using autoware::localization::ndt::NDTGrid< VoxelT >::Grid = std::unordered_map<uint64_t, VoxelT>

◆ Point

template<typename VoxelT >
using autoware::localization::ndt::NDTGrid< VoxelT >::Point = Eigen::Vector3d

◆ VoxelViewVector

template<typename VoxelT >
using autoware::localization::ndt::NDTGrid< VoxelT >::VoxelViewVector = std::vector<VoxelView<VoxelT> >

Constructor & Destructor Documentation

◆ NDTGrid() [1/3]

template<typename VoxelT >
autoware::localization::ndt::NDTGrid< VoxelT >::NDTGrid ( const Config voxel_grid_config)
inlineexplicit

Constructor

Parameters
voxel_grid_configVoxel grid config to configure the underlying voxel grid.

◆ NDTGrid() [2/3]

template<typename VoxelT >
autoware::localization::ndt::NDTGrid< VoxelT >::NDTGrid ( const NDTGrid< VoxelT > &  )
delete

◆ NDTGrid() [3/3]

template<typename VoxelT >
autoware::localization::ndt::NDTGrid< VoxelT >::NDTGrid ( NDTGrid< VoxelT > &&  )
default

Member Function Documentation

◆ add_observation()

template<typename VoxelT >
void autoware::localization::ndt::NDTGrid< VoxelT >::add_observation ( const Point pt)
inline

Add a point to its corresponding voxel in the grid.

Parameters
ptPoint to be added

◆ begin() [1/2]

template<typename VoxelT >
Grid::const_iterator autoware::localization::ndt::NDTGrid< VoxelT >::begin ( ) const
inlinenoexcept

Returns an const iterator to the first element of the map.

Returns
Iterator

◆ begin() [2/2]

template<typename VoxelT >
Grid::iterator autoware::localization::ndt::NDTGrid< VoxelT >::begin ( )
inlinenoexcept

Returns an iterator to the first element of the map.

Returns
Iterator

◆ cbegin()

template<typename VoxelT >
Grid::const_iterator autoware::localization::ndt::NDTGrid< VoxelT >::cbegin ( ) const
inlinenoexcept

Returns a const iterator to the first element of the map.

Returns
Iterator

◆ cell() [1/2]

template<typename VoxelT >
const VoxelViewVector& autoware::localization::ndt::NDTGrid< VoxelT >::cell ( const Point pt) const
inline

Lookup the cell at location.

Parameters
ptpoint to lookup
Returns
A vector containing the cell at given coordinates. A vector is used to support near-neighbour cell queries in the future.

◆ cell() [2/2]

template<typename VoxelT >
const VoxelViewVector& autoware::localization::ndt::NDTGrid< VoxelT >::cell ( float32_t  x,
float32_t  y,
float32_t  z 
) const
inline

Lookup the cell at location.

Parameters
xx coordinate
yy coordinate
zz coordinate
Returns
A vector containing the cell at given coordinates. A vector is used to support near-neighbour cell queries in the future.

◆ cell_size()

template<typename VoxelT >
const ConfigPoint& autoware::localization::ndt::NDTGrid< VoxelT >::cell_size ( ) const
inlinenoexcept

Get size of the cell.

Returns
A point representing the dimensions of the cell.

◆ cend()

template<typename VoxelT >
Grid::const_iterator autoware::localization::ndt::NDTGrid< VoxelT >::cend ( ) const
inlinenoexcept

Returns a const iterator to one past the last element of the map.

Returns
Iterator

◆ clear()

template<typename VoxelT >
void autoware::localization::ndt::NDTGrid< VoxelT >::clear ( )
inlinenoexcept

Clear all voxels in the map.

◆ config()

template<typename VoxelT >
const Config& autoware::localization::ndt::NDTGrid< VoxelT >::config ( ) const
inline

Get the underlying voxel grid configuration.

Returns
Voxel grid configuration

◆ emplace_voxel()

template<typename VoxelT >
template<typename ... Args>
auto autoware::localization::ndt::NDTGrid< VoxelT >::emplace_voxel ( Args &&...  args)
inline

Emplace a new voxel into the grid.

Parameters
argsArguments. An index and a voxel is expected
Returns
See the return type of unordered_map::emplace().

◆ end() [1/2]

template<typename VoxelT >
Grid::const_iterator autoware::localization::ndt::NDTGrid< VoxelT >::end ( ) const
inlinenoexcept

Returns a const iterator to one past the last element of the map.

Returns
Iterator

◆ end() [2/2]

template<typename VoxelT >
Grid::iterator autoware::localization::ndt::NDTGrid< VoxelT >::end ( )
inlinenoexcept

Returns an iterator to one past the last element of the map.

Returns
Iterator

◆ index()

template<typename VoxelT >
auto autoware::localization::ndt::NDTGrid< VoxelT >::index ( const Point pt) const
inline

Get voxel index given a point.

Parameters
ptpoint
Returns
voxel index

◆ operator=() [1/2]

template<typename VoxelT >
NDTGrid& autoware::localization::ndt::NDTGrid< VoxelT >::operator= ( const NDTGrid< VoxelT > &  )
delete

◆ operator=() [2/2]

template<typename VoxelT >
NDTGrid& autoware::localization::ndt::NDTGrid< VoxelT >::operator= ( NDTGrid< VoxelT > &&  )
default

◆ set_config()

template<typename VoxelT >
void autoware::localization::ndt::NDTGrid< VoxelT >::set_config ( const Config config)
inline

Set the configuration.

Parameters
configConfig object to be set.

◆ size()

template<typename VoxelT >
std::size_t autoware::localization::ndt::NDTGrid< VoxelT >::size ( ) const
inlinenoexcept

Get size of the map

Returns
Number of voxels in the map. This number includes the voxels that do not have enough numbers to be used yet.

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