Autoware.Auto
autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT > Class Template Reference

A voxel grid data structure for downsampling point clouds. More...

#include <voxel_grid.hpp>

Public Types

using point_t = typename VoxelT::point_t
 

Public Member Functions

 VoxelGrid (const Config &cfg)
 Constructor. More...
 
void insert (const point_t &pt)
 Inserts a point into the voxel grid, may result in new voxels being activated. More...
 
template<typename IT >
void insert (const IT begin, const IT end)
 Inserts many points into the voxel grid, dispatches to the core insert method. More...
 
const OutputQueue & new_voxels ()
 Return a list of iterators pointing to newly activated voxels. Voxels will be removed from queue during a subsequent call to this method. More...
 
IT begin () const
 Returns an iterator to the first element of the voxel grid. More...
 
IT cbegin () const
 Returns an iterator to the first element of the voxel grid. More...
 
IT end () const
 Returns an iterator to one past the last element of the voxel grid. More...
 
IT cend () const
 Returns an iterator to one past the last element of the voxel grid. More...
 
void clear ()
 Resets the state of the voxel grid. More...
 
std::size_t size () const
 Returns the current size of the voxel grid. More...
 
std::size_t capacity () const
 Returns the preallocated capacity of the voxel grid. More...
 
bool8_t empty () const
 Whether the voxel grid is empty. More...
 

Detailed Description

template<typename VoxelT>
class autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >

A voxel grid data structure for downsampling point clouds.

Template Parameters
VoxelTThe underlying voxel type, assumed to be a child class of Voxel with the addition of the add_observation(PointT) method

Member Typedef Documentation

◆ point_t

template<typename VoxelT >
using autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::point_t = typename VoxelT::point_t

Constructor & Destructor Documentation

◆ VoxelGrid()

template<typename VoxelT >
autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::VoxelGrid ( const Config cfg)
inlineexplicit

Constructor.

Parameters
[in]cfgThe configuration class

Member Function Documentation

◆ begin()

template<typename VoxelT >
IT autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::begin ( ) const
inline

Returns an iterator to the first element of the voxel grid.

Returns
Iterator

◆ capacity()

template<typename VoxelT >
std::size_t autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::capacity ( ) const
inline

Returns the preallocated capacity of the voxel grid.

Returns
The preallocated capacity

◆ cbegin()

template<typename VoxelT >
IT autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::cbegin ( ) const
inline

Returns an iterator to the first element of the voxel grid.

Returns
Iterator

◆ cend()

template<typename VoxelT >
IT autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::cend ( ) const
inline

Returns an iterator to one past the last element of the voxel grid.

Returns
Iterator

◆ clear()

template<typename VoxelT >
void autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::clear ( )
inline

Resets the state of the voxel grid.

◆ empty()

template<typename VoxelT >
bool8_t autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::empty ( ) const
inline

Whether the voxel grid is empty.

Returns
True or false

◆ end()

template<typename VoxelT >
IT autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::end ( ) const
inline

Returns an iterator to one past the last element of the voxel grid.

Returns
Iterator

◆ insert() [1/2]

template<typename VoxelT >
template<typename IT >
void autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::insert ( const IT  begin,
const IT  end 
)
inline

Inserts many points into the voxel grid, dispatches to the core insert method.

Template Parameters
ITThe iterator type
Parameters
[in]beginThe starting iterator
[in]endAn iterator pointing one past the last element to be inserted.

◆ insert() [2/2]

template<typename VoxelT >
void autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::insert ( const point_t pt)
inline

Inserts a point into the voxel grid, may result in new voxels being activated.

Parameters
[in]ptThe point to insert

◆ new_voxels()

template<typename VoxelT >
const OutputQueue& autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::new_voxels ( )
inline

Return a list of iterators pointing to newly activated voxels. Voxels will be removed from queue during a subsequent call to this method.

Returns
A list of newly activated iterators pointing to index-voxel pairs, from most recently activated to least recently activated voxels.

An example of queueing behavior: insert 0, 1, 2, 3, 4 new_voxels: 4->3->2->1->0 insert 0, 3, 5 new_voxels: 5

◆ size()

template<typename VoxelT >
std::size_t autoware::perception::filters::voxel_grid::VoxelGrid< VoxelT >::size ( ) const
inline

Returns the current size of the voxel grid.


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