Autoware.Auto
autoware::common::geometry::spatial_hash::Config< Derived > Class Template Reference

The base class for the configuration object for the SpatialHash class. More...

#include <spatial_hash_config.hpp>

Inheritance diagram for autoware::common::geometry::spatial_hash::Config< Derived >:
Collaboration diagram for autoware::common::geometry::spatial_hash::Config< Derived >:

Public Member Functions

 Config (const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y, const float32_t min_z, const float32_t max_z, const float32_t radius, const Index capacity)
 Constructor for spatial hash. More...
 
details::BinRange bin_range (const details::Index3 &ref, const float radius) const
 Given a reference index triple, compute the first and last bin. More...
 
bool8_t next_bin (const details::BinRange &range, details::Index3 &idx) const
 Get next index within a given range. More...
 
Index get_capacity () const
 Get the maximum capacity of the spatial hash. More...
 
float32_t radius2 () const
 Getter for the side length, equivalently the lookup radius. More...
 
Index bin (const float32_t x, const float32_t y, const float32_t z) const
 Compute the single index given a point. More...
 
bool is_candidate_bin (const details::Index3 &ref, const details::Index3 &query, const float ref_distance2) const
 Compute whether the query bin and reference bin could possibly contain a pair of points such that their distance is within a certain threshold. More...
 
details::Index3 index3 (const float32_t x, const float32_t y, const float32_t z) const
 Compute the decomposed index given a point. More...
 
Index index (const details::Index3 &idx) const
 Compute the composed single index given a decomposed index. More...
 
template<typename PointT >
float32_t distance_squared (const float32_t x, const float32_t y, const float32_t z, const PointT &pt) const
 Compute the squared distance between the two points. More...
 

Protected Member Functions

Index x_index (const float32_t x) const
 Computes the index in the x basis direction. More...
 
Index y_index (const float32_t y) const
 Computes the index in the y basis direction. More...
 
Index z_index (const float32_t z) const
 Computes the index in the z basis direction. More...
 
Index bin_impl (const Index xdx, const Index ydx) const
 Compose the provided index offsets. More...
 
Index bin_impl (const Index xdx, const Index ydx, const Index zdx) const
 Compose the provided index offsets. More...
 
Index bin_impl (const float32_t x, const float32_t y) const
 The index offset of a point given it's x and y values. More...
 
Index bin_impl (const float32_t x, const float32_t y, const float32_t z) const
 The index of a point given it's x, y and z values. More...
 
float32_t idx_distance (const Index ref_idx, const Index query_idx) const
 The distance between two indices as a float, where adjacent indices have zero distance (e.g. dist(0, 1) = 0) More...
 
float side_length2 () const
 Get side length squared. More...
 
- Protected Member Functions inherited from autoware::common::helper_functions::crtp< Derived >
const Derived & impl () const
 
Derived & impl ()
 

Detailed Description

template<typename Derived>
class autoware::common::geometry::spatial_hash::Config< Derived >

The base class for the configuration object for the SpatialHash class.

Template Parameters
DerivedThe type of the derived class to support static polymorphism/CRTP

Constructor & Destructor Documentation

◆ Config()

template<typename Derived >
autoware::common::geometry::spatial_hash::Config< Derived >::Config ( const float32_t  min_x,
const float32_t  max_x,
const float32_t  min_y,
const float32_t  max_y,
const float32_t  min_z,
const float32_t  max_z,
const float32_t  radius,
const Index  capacity 
)
inline

Constructor for spatial hash.

Parameters
[in]min_xThe minimum x value for the spatial hash
[in]max_xThe maximum x value for the spatial hash
[in]min_yThe minimum y value for the spatial hash
[in]max_yThe maximum y value for the spatial hash
[in]min_zThe minimum z value for the spatial hash
[in]max_zThe maximum z value for the spatial hash
[in]radiusThe look up radius
[in]capacityThe maximum number of points the spatial hash can store

Member Function Documentation

◆ bin()

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::bin ( const float32_t  x,
const float32_t  y,
const float32_t  z 
) const
inline

Compute the single index given a point.

Parameters
[in]xThe x component of the point
[in]yThe y component of the point
[in]zThe z component of the point
Returns
The combined index of the bin for a given point

◆ bin_impl() [1/4]

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::bin_impl ( const float32_t  x,
const float32_t  y 
) const
inlineprotected

The index offset of a point given it's x and y values.

Parameters
[in]xThe x value of a point
[in]ythe y value of a point
Returns
The index of the point in the 2D case, or the offset within a z-slice of the hash

◆ bin_impl() [2/4]

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::bin_impl ( const float32_t  x,
const float32_t  y,
const float32_t  z 
) const
inlineprotected

The index of a point given it's x, y and z values.

Parameters
[in]xThe x value of a point
[in]ythe y value of a point
[in]zthe z value of a point
Returns
The index of the bin for the specified point

◆ bin_impl() [3/4]

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::bin_impl ( const Index  xdx,
const Index  ydx 
) const
inlineprotected

Compose the provided index offsets.

◆ bin_impl() [4/4]

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::bin_impl ( const Index  xdx,
const Index  ydx,
const Index  zdx 
) const
inlineprotected

Compose the provided index offsets.

◆ bin_range()

template<typename Derived >
details::BinRange autoware::common::geometry::spatial_hash::Config< Derived >::bin_range ( const details::Index3 ref,
const float  radius 
) const
inline

Given a reference index triple, compute the first and last bin.

Parameters
[in]refThe reference index triple
[in]radiusThe allowable radius for any point in the reference bin to any point in the range
Returns
A pair where the first element is an index triple of the first bin, and the second element is an index triple for the last bin

◆ distance_squared()

template<typename Derived >
template<typename PointT >
float32_t autoware::common::geometry::spatial_hash::Config< Derived >::distance_squared ( const float32_t  x,
const float32_t  y,
const float32_t  z,
const PointT &  pt 
) const
inline

Compute the squared distance between the two points.

Template Parameters
PointTA point type with float members x, y and z, or point adapters defined
Parameters
[in]xThe x component of the first point
[in]yThe y component of the first point
[in]zThe z component of the first point
[in]ptThe other point being compared
Returns
The squared distance between the points (2d or 3d)

◆ get_capacity()

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::get_capacity ( ) const
inline

Get the maximum capacity of the spatial hash.

Returns
The capacity

◆ idx_distance()

template<typename Derived >
float32_t autoware::common::geometry::spatial_hash::Config< Derived >::idx_distance ( const Index  ref_idx,
const Index  query_idx 
) const
inlineprotected

The distance between two indices as a float, where adjacent indices have zero distance (e.g. dist(0, 1) = 0)

Not using fabs because Index is (possibly) unsigned

◆ index()

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::index ( const details::Index3 idx) const
inline

Compute the composed single index given a decomposed index.

Parameters
[in]idxA decomposed index triple for a bin
Returns
The composed bin index

◆ index3()

template<typename Derived >
details::Index3 autoware::common::geometry::spatial_hash::Config< Derived >::index3 ( const float32_t  x,
const float32_t  y,
const float32_t  z 
) const
inline

Compute the decomposed index given a point.

Parameters
[in]xThe x component of the point
[in]yThe y component of the point
[in]zThe z component of the point
Returns
The decomposed index triple of the bin for the given point

◆ is_candidate_bin()

template<typename Derived >
bool autoware::common::geometry::spatial_hash::Config< Derived >::is_candidate_bin ( const details::Index3 ref,
const details::Index3 query,
const float  ref_distance2 
) const
inline

Compute whether the query bin and reference bin could possibly contain a pair of points such that their distance is within a certain threshold.

Parameters
[in]refThe index triple of the bin containing the reference point
[in]queryThe index triple of the bin being queried
[in]ref_distance2The squared threshold distance
Returns
True if query and ref could possibly hold points within reference distance to one another

◆ next_bin()

template<typename Derived >
bool8_t autoware::common::geometry::spatial_hash::Config< Derived >::next_bin ( const details::BinRange range,
details::Index3 idx 
) const
inline

Get next index within a given range.

Returns
True if idx is valid and still in range
Parameters
[in]rangeThe max and min bin indices
[in,out]idxThe index to be incremented, updated even if a negative result occurs

◆ radius2()

template<typename Derived >
float32_t autoware::common::geometry::spatial_hash::Config< Derived >::radius2 ( ) const
inline

Getter for the side length, equivalently the lookup radius.

◆ side_length2()

template<typename Derived >
float autoware::common::geometry::spatial_hash::Config< Derived >::side_length2 ( ) const
inlineprotected

Get side length squared.

◆ x_index()

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::x_index ( const float32_t  x) const
inlineprotected

Computes the index in the x basis direction.

Parameters
[in]xThe x value of a point
Returns
The x offset of the index

◆ y_index()

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::y_index ( const float32_t  y) const
inlineprotected

Computes the index in the y basis direction.

Parameters
[in]yThe y value of a point
Returns
The x offset of the index

◆ z_index()

template<typename Derived >
Index autoware::common::geometry::spatial_hash::Config< Derived >::z_index ( const float32_t  z) const
inlineprotected

Computes the index in the z basis direction.

Parameters
[in]zThe z value of a point
Returns
The x offset of the index

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