Autoware.Auto
autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT > Class Template Reference

An implementation of the spatial hash or integer lattice data structure for efficient (O(1)) near neighbor queries. More...

#include <spatial_hash.hpp>

Classes

class  Output
 Wrapper around an iterator and a distance (from some query point) More...
 

Public Types

using Hash = std::unordered_multimap< Index, PointT >
 
using IT = typename Hash::const_iterator
 
using OutputVector = typename std::vector< Output >
 

Public Member Functions

 SpatialHashBase (const ConfigT &cfg)
 Constructor. More...
 
IT insert (const PointT &pt)
 Inserts point. More...
 
template<typename IteratorT >
void insert (IteratorT begin, IteratorT end)
 Inserts a range of points. More...
 
IT erase (const IT point)
 Removes the specified element from the data structure. More...
 
void clear ()
 Reset the state of the data structure. More...
 
Index size () const
 Get current number of element stored in this data structure. More...
 
Index capacity () const
 Get the maximum capacity of the data structure. More...
 
bool8_t empty () const
 Whether the hash is empty. More...
 
IT begin () const
 Get iterator to beginning of data structure. More...
 
IT end () const
 Get iterator to end of data structure. More...
 
IT cbegin () const
 Get iterator to beginning of data structure. More...
 
IT cend () const
 Get iterator to end of data structure. More...
 
Index bins_hit () const
 Get the number of bins touched during the lifetime of this object, for debugging and size tuning. More...
 
Index neighbors_found () const
 Get number of near neighbors found during the lifetime of this object, for debugging and size tuning. More...
 

Protected Member Functions

const OutputVectornear_impl (const float32_t x, const float32_t y, const float32_t z, const float32_t radius)
 Finds all points within a fixed radius of a reference point. More...
 

Detailed Description

template<typename PointT, typename ConfigT>
class autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >

An implementation of the spatial hash or integer lattice data structure for efficient (O(1)) near neighbor queries.

Template Parameters
PointTThe point type stored in this data structure. Must have float members x, y, and z

This implementation can support both 2D and 3D queries (though only one type per data structure), and can support queries of varying radius. This data structure cannot do near neighbor lookups for euclidean distance in arbitrary dimensions.

Member Typedef Documentation

◆ Hash

template<typename PointT , typename ConfigT >
using autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::Hash = std::unordered_multimap<Index, PointT>

◆ IT

template<typename PointT , typename ConfigT >
using autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::IT = typename Hash::const_iterator

◆ OutputVector

template<typename PointT , typename ConfigT >
using autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::OutputVector = typename std::vector<Output>

Constructor & Destructor Documentation

◆ SpatialHashBase()

template<typename PointT , typename ConfigT >
autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::SpatialHashBase ( const ConfigT &  cfg)
inlineexplicit

Constructor.

Parameters
[in]cfgThe configuration object for this class

Member Function Documentation

◆ begin()

template<typename PointT , typename ConfigT >
IT autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::begin ( ) const
inline

Get iterator to beginning of data structure.

Returns
Iterator

◆ bins_hit()

template<typename PointT , typename ConfigT >
Index autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::bins_hit ( ) const
inline

Get the number of bins touched during the lifetime of this object, for debugging and size tuning.

Returns
The total number of bins touched during near() queries

◆ capacity()

template<typename PointT , typename ConfigT >
Index autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::capacity ( ) const
inline

Get the maximum capacity of the data structure.

Returns
The capacity of the data structure

◆ cbegin()

template<typename PointT , typename ConfigT >
IT autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::cbegin ( ) const
inline

Get iterator to beginning of data structure.

Returns
Iterator

◆ cend()

template<typename PointT , typename ConfigT >
IT autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::cend ( ) const
inline

Get iterator to end of data structure.

Returns
Iterator

◆ clear()

template<typename PointT , typename ConfigT >
void autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::clear ( )
inline

Reset the state of the data structure.

◆ empty()

template<typename PointT , typename ConfigT >
bool8_t autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::empty ( ) const
inline

Whether the hash is empty.

Returns
True if data structure is empty

◆ end()

template<typename PointT , typename ConfigT >
IT autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::end ( ) const
inline

Get iterator to end of data structure.

Returns
Iterator

◆ erase()

template<typename PointT , typename ConfigT >
IT autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::erase ( const IT  point)
inline

Removes the specified element from the data structure.

Parameters
[in]pointAn iterator pointing to a point to be removed
Returns
An iterator pointing to the element after the erased element
Exceptions
std::domain_errorIf pt is invalid or does not belong to this data structure
Note
There is no reliable way to check if an iterator is invalid. The checks here are based on a heuristic and is not guaranteed to find all invalid iterators. This method should be used with care and only on valid iterators

◆ insert() [1/2]

template<typename PointT , typename ConfigT >
IT autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::insert ( const PointT &  pt)
inline

Inserts point.

Parameters
[in]ptThe Point to insert
Returns
Iterator pointing to the inserted point
Exceptions
std::length_errorIf the data structure is at capacity

◆ insert() [2/2]

template<typename PointT , typename ConfigT >
template<typename IteratorT >
void autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::insert ( IteratorT  begin,
IteratorT  end 
)
inline

Inserts a range of points.

Parameters
[in]beginThe start of the range of points to insert
[in]endThe end of the range of points to insert
Template Parameters
IteratorTThe iterator type
Exceptions
std::length_errorIf the range of points to insert exceeds the data structure's capacity

◆ near_impl()

template<typename PointT , typename ConfigT >
const OutputVector& autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::near_impl ( const float32_t  x,
const float32_t  y,
const float32_t  z,
const float32_t  radius 
)
inlineprotected

Finds all points within a fixed radius of a reference point.

Parameters
[in]xThe x component of the reference point
[in]yThe y component of the reference point
[in]zThe z component of the reference point, respected only if the spatial hash is not 2D.
[in]radiusThe radius within which to find all near points
Returns
A const reference to a vector containing iterators pointing to all points within the radius, and the actual distance to the reference point

◆ neighbors_found()

template<typename PointT , typename ConfigT >
Index autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::neighbors_found ( ) const
inline

Get number of near neighbors found during the lifetime of this object, for debugging and size tuning.

Returns
The total number of neighbors found during near() queries

◆ size()

template<typename PointT , typename ConfigT >
Index autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, ConfigT >::size ( ) const
inline

Get current number of element stored in this data structure.

Returns
Number of stored elements

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