Autoware.Auto
autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d > Class Template Reference

Explicit specialization of SpatialHash for 2D configuration. More...

#include <spatial_hash.hpp>

Inheritance diagram for autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >:
Collaboration diagram for autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >:

Public Types

using OutputVector = typename SpatialHashBase< PointT, Config2d >::OutputVector
 
- Public Types inherited from autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, Config2d >
using Hash = std::unordered_multimap< Index, PointT >
 
using IT = typename Hash::const_iterator
 
using OutputVector = typename std::vector< Output >
 

Public Member Functions

 SpatialHash (const Config2d &cfg)
 
const OutputVectornear (const float32_t x, const float32_t y, const float32_t radius)
 Finds all points within a fixed radius of a reference point. More...
 
const OutputVectornear (const PointT &pt, const float32_t radius)
 Finds all points within a fixed radius of a reference point. More...
 
- Public Member Functions inherited from autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, Config2d >
 SpatialHashBase (const Config2d &cfg)
 Constructor. More...
 
IT insert (const PointT &pt)
 Inserts point. More...
 
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...
 

Additional Inherited Members

- Protected Member Functions inherited from autoware::common::geometry::spatial_hash::SpatialHashBase< PointT, Config2d >
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>
class autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >

Explicit specialization of SpatialHash for 2D configuration.

Template Parameters
PointTThe point type stored in this data structure.

Member Typedef Documentation

◆ OutputVector

template<typename PointT >
using autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >::OutputVector = typename SpatialHashBase<PointT, Config2d>::OutputVector

Constructor & Destructor Documentation

◆ SpatialHash()

template<typename PointT >
autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >::SpatialHash ( const Config2d cfg)
inlineexplicit

Member Function Documentation

◆ near() [1/2]

template<typename PointT >
const OutputVector& autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >::near ( const float32_t  x,
const float32_t  y,
const float32_t  radius 
)
inline

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]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

◆ near() [2/2]

template<typename PointT >
const OutputVector& autoware::common::geometry::spatial_hash::SpatialHash< PointT, Config2d >::near ( const PointT &  pt,
const float32_t  radius 
)
inline

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

Parameters
[in]ptThe reference point. Only the x and y members are respected.
[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

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