Go to the documentation of this file.
20 #ifndef GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
21 #define GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
46 namespace spatial_hash
71 template<
typename Derived>
99 m_side_length{radius},
100 m_side_length2{radius * radius},
101 m_side_length_inv{1.0F / radius},
102 m_capacity{capacity},
103 m_max_x_idx{check_basis_direction(min_x, max_x)},
104 m_max_y_idx{check_basis_direction(min_y, max_y)},
105 m_max_z_idx{check_basis_direction(min_z, max_z)},
106 m_y_stride{m_max_x_idx + 1U},
107 m_z_stride{m_y_stride * (m_max_y_idx + 1U)}
109 if (radius <= 0.0F) {
110 throw std::domain_error(
"Error constructing SpatialHash: must have positive side length");
113 if ((m_max_y_idx + m_y_stride) > std::numeric_limits<Index>::max() / 2U) {
115 throw std::domain_error(
"SpatialHash::Config: voxel index may overflow!");
119 constexpr
auto FEPS = std::numeric_limits<float32_t>::epsilon();
124 if ((m_z_stride + m_max_z_idx) > std::numeric_limits<Index>::max() / 2U) {
126 throw std::domain_error(
"SpatialHash::Config: voxel index may overflow!");
129 if (std::numeric_limits<Index>::max() == m_max_z_idx) {
130 throw std::domain_error(
"SpatialHash::Config: max z index exceeds reasonable value");
141 constexpr
Index iradius = 1;
143 const Index xmin = (ref.
x > iradius) ? (ref.
x - iradius) : 0U;
144 const Index ymin = (ref.
y > iradius) ? (ref.
y - iradius) : 0U;
145 const Index zmin = (ref.
z > iradius) ? (ref.
z - iradius) : 0U;
147 const Index xmax = std::min(ref.
x + iradius, m_max_x_idx);
148 const Index ymax = std::min(ref.
y + iradius, m_max_y_idx);
149 const Index zmax = std::min(ref.
z + iradius, m_max_z_idx);
151 return {{xmin, ymin, zmin}, {xmax, ymax, zmax}};
162 if (idx.
x > range.second.x) {
163 idx.
x = range.first.x;
165 if (idx.
y > range.second.y) {
166 idx.
y = range.first.y;
168 if (idx.
z > range.second.z) {
185 return m_side_length2;
197 return this->impl().bin_(
x,
y, z);
207 return this->impl().valid(ref, query);
216 return this->impl().index3_(
x,
y, z);
223 return this->impl().index_(idx);
232 template<
typename Po
intT>
237 const PointT & pt)
const
239 return this->impl().distance_squared_(
x,
y, z, pt);
248 return static_cast<Index>(
249 std::floor((std::min(std::max(
x, m_min_x), m_max_x) - m_min_x) * m_side_length_inv));
256 return static_cast<Index>(
257 std::floor((std::min(std::max(
y, m_min_y), m_max_y) - m_min_y) * m_side_length_inv));
264 return static_cast<Index>(
265 std::floor((std::min(std::max(z, m_min_z), m_max_z) - m_min_z) * m_side_length_inv));
270 return xdx + (ydx * m_y_stride);
275 return bin_impl(xdx, ydx) + (zdx * m_z_stride);
284 return bin_impl(x_index(
x), y_index(
y));
293 return bin_impl(
x,
y) + (z_index(z) * m_z_stride);
300 const Index idist = (ref_idx >= query_idx) ? (ref_idx - query_idx) : (query_idx - ref_idx);
302 return std::max(dist, 0.0F);
311 throw std::domain_error(
"SpatialHash::Config: must have min < max");
318 constexpr
float64_t fltmax =
static_cast<float64_t>(std::numeric_limits<float32_t>::max());
319 if (fltmax <= width) {
320 throw std::domain_error(
"SpatialHash::Config: voxel size approaching floating point limit");
322 return static_cast<Index>(width);
358 const Index capacity);
389 template<
typename Po
intT>
394 const PointT & pt)
const
424 const Index capacity);
455 template<
typename Po
intT>
460 const PointT & pt)
const
465 return (
dx *
dx) + (
dy *
dy) + (dz * dz);
473 #endif // GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
bool8_t is_candidate_bin(const details::Index3 &ref, const details::Index3 &query) const
Compute whether the query bin and reference bin could possibly contain a pair of points such that the...
Definition: spatial_hash_config.hpp:205
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:47
This file includes common type definition.
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
details::BinRange bin_range(const details::Index3 &ref) const
Given a reference index triple, compute the first and last bin.
Definition: spatial_hash_config.hpp:138
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.
Definition: spatial_hash_config.hpp:233
dx
Definition: catr_diff.py:38
Configuration class for a 2d spatial hash.
Definition: spatial_hash_config.hpp:342
This file includes common functionality for 2D geometry, such as dot products.
bool8_t next_bin(const details::BinRange &range, details::Index3 &idx) const
Get next index within a given range.
Definition: spatial_hash_config.hpp:157
Index z
Definition: spatial_hash_config.hpp:63
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.
Definition: spatial_hash_config.hpp:84
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....
Definition: spatial_hash_config.hpp:297
Index y_index(const float32_t y) const
Computes the index in the y basis direction.
Definition: spatial_hash_config.hpp:254
Index z_index(const float32_t z) const
Computes the index in the z basis direction.
Definition: spatial_hash_config.hpp:262
bool bool8_t
Definition: types.hpp:39
Index get_capacity() const
Get the maximum capacity of the spatial hash.
Definition: spatial_hash_config.hpp:177
Internal struct for packing three indices together.
Definition: spatial_hash_config.hpp:59
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Index bin_impl(const Index xdx, const Index ydx) const
Compose the provided index offsets.
Definition: spatial_hash_config.hpp:268
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.
Definition: spatial_hash_config.hpp:291
The base class for the configuration object for the SpatialHash class.
Definition: spatial_hash_config.hpp:72
Index index(const details::Index3 &idx) const
Compute the composed single index given a decomposed index.
Definition: spatial_hash_config.hpp:221
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
Index bin(const float32_t x, const float32_t y, const float32_t z) const
Compute the single index given a point.
Definition: spatial_hash_config.hpp:195
float float32_t
Definition: types.hpp:45
float32_t radius2() const
Getter for the side length, equivalently the lookup radius.
Definition: spatial_hash_config.hpp:183
This file includes common helper functions.
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, 2d implementation.
Definition: spatial_hash_config.hpp:390
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, 3d implementation.
Definition: spatial_hash_config.hpp:456
Index x
Definition: spatial_hash_config.hpp:61
Configuration class for a 3d spatial hash.
Definition: spatial_hash_config.hpp:404
Index y
Definition: spatial_hash_config.hpp:62
auto y_(const PointT &pt)
Gets the y value for a point.
Definition: common_2d.hpp:56
details::Index3 index3(const float32_t x, const float32_t y, const float32_t z) const
Compute the decomposed index given a point.
Definition: spatial_hash_config.hpp:214
double float64_t
Definition: types.hpp:47
auto z_(const PointT &pt)
Gets the z value for a point.
Definition: common_2d.hpp:65
Index x_index(const float32_t x) const
Computes the index in the x basis direction.
Definition: spatial_hash_config.hpp:246
Index bin_impl(const Index xdx, const Index ydx, const Index zdx) const
Compose the provided index offsets.
Definition: spatial_hash_config.hpp:273
dy
Definition: catr_diff.py:39
std::pair< Index3, Index3 > BinRange
Definition: spatial_hash_config.hpp:66
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.
Definition: spatial_hash_config.hpp:282
std::size_t Index
Index type for identifying bins of the hash/lattice.
Definition: spatial_hash_config.hpp:49