spatial_hash.hpp
Go to the documentation of this file.
1 // Copyright 2022-2023 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef BELUGA_ALGORITHM_SPATIAL_HASH_HPP
16 #define BELUGA_ALGORITHM_SPATIAL_HASH_HPP
17 
18 #include <bitset>
19 #include <cmath>
20 #include <cstdint>
21 #include <limits>
22 #include <tuple>
23 #include <type_traits>
24 #include <utility>
25 
26 #include <sophus/se2.hpp>
27 
33 namespace beluga {
34 
35 namespace detail {
36 
38 
44 template <std::size_t N, std::size_t I>
45 constexpr std::size_t floor_and_fibo_hash(double value) {
46  constexpr auto kFib = []() {
47  if constexpr (std::is_same_v<std::size_t, std::uint64_t>) {
48  return 11400714819323198485LLU; // golden ratio for 64 bits
49  } else if constexpr (std::is_same_v<std::size_t, std::uint32_t>) {
50  return 2654435769U; // golden ratio for 32 bits
51  } else {
52  // Write false in a sufficiently complex way so as to confuse the compiler.
53  // See https://www.open-std.org/jtc1/sc22/wg21/docs/papers/2023/p2593r1.html
54  static_assert([](auto) { return false; }(std::integral_constant<std::size_t, N>{}));
55  }
56  }();
57 
58  using signed_type = std::make_signed_t<std::size_t>;
59  using unsigned_type = std::make_unsigned_t<std::size_t>;
60 
61  // floor the value and convert to integer
62  const auto signed_value = static_cast<signed_type>(std::floor(value));
63  // work with unsigned from now on
64  const auto unsigned_value = static_cast<unsigned_type>(signed_value);
65  // spread number information through all the bits using the fibonacci hash
66  const auto div_hashed_value = kFib * unsigned_value;
67  // rotate bits to avoid aliasing between different values of I
68  if constexpr (N * I != 0) {
69  const auto left_hash = (div_hashed_value << N * I);
70  const auto right_hash = (div_hashed_value >> (std::numeric_limits<std::size_t>::digits - N * I));
71  return left_hash | right_hash;
72  } else {
73  return div_hashed_value;
74  }
75 }
76 
79 
87 template <class T, std::size_t... Ids>
88 constexpr std::size_t hash_impl(
89  const T& value,
90  const std::array<double, sizeof...(Ids)>& resolution,
91  [[maybe_unused]] std::index_sequence<Ids...> index_sequence) {
92  constexpr auto kBits = std::numeric_limits<std::size_t>::digits / sizeof...(Ids);
93  return (detail::floor_and_fibo_hash<kBits, Ids>(std::get<Ids>(value) / resolution[Ids]) ^ ...);
94 }
95 
96 } // namespace detail
97 
99 template <class T, typename Enable = void>
100 struct spatial_hash {};
101 
103 template <class T, std::size_t N>
104 class spatial_hash<std::array<T, N>, std::enable_if_t<std::is_arithmetic_v<T>, void>> {
105  public:
107  using resolution_in_each_axis_t = std::array<double, N>;
108 
110 
114  explicit spatial_hash(const resolution_in_each_axis_t& resolution) : resolution_{resolution} {}
115 
117 
121  constexpr std::size_t operator()(const std::array<T, N>& array) const {
122  return detail::hash_impl(array, resolution_, std::make_index_sequence<N>());
123  }
124 
125  private:
127 };
128 
130 template <template <class...> class Tuple, class... Types>
131 class spatial_hash<Tuple<Types...>, std::enable_if_t<(std::is_arithmetic_v<Types> && ...), void>> {
132  public:
134  using resolution_in_each_axis_t = std::array<double, sizeof...(Types)>;
135 
137 
141  explicit spatial_hash(const resolution_in_each_axis_t& resolution) : resolution_{resolution} {}
142 
144 
148  constexpr std::size_t operator()(const Tuple<Types...>& tuple) const {
149  return detail::hash_impl(tuple, resolution_, std::make_index_sequence<sizeof...(Types)>());
150  }
151 
152  private:
154 };
155 
159 template <>
160 class spatial_hash<Sophus::SE2d, void> {
161  public:
163 
168  explicit spatial_hash(
169  double x_clustering_resolution,
170  double y_clustering_resolution,
171  double theta_clustering_resolution)
172  : underlying_hasher_{{x_clustering_resolution, y_clustering_resolution, theta_clustering_resolution}} {};
173 
175 
179  explicit spatial_hash(double linear_clustering_resolution, double angular_clustering_resolution)
180  : spatial_hash(linear_clustering_resolution, linear_clustering_resolution, angular_clustering_resolution){};
181 
183  spatial_hash() = default;
184 
186 
190  std::size_t operator()(const Sophus::SE2d& state) const {
191  const auto& position = state.translation();
192  return underlying_hasher_(std::make_tuple(position.x(), position.y(), state.so2().log()));
193  }
194 
195  private:
196  spatial_hash<std::tuple<double, double, double>> underlying_hasher_{{1., 1., 1.}};
197 };
198 
199 } // namespace beluga
200 
201 #endif
beluga::state
constexpr state_detail::state_fn state
Customization point object for accessing the state of a particle.
Definition: primitives.hpp:163
enable_if_t
typename std::enable_if< B, T >::type enable_if_t
beluga::spatial_hash< Sophus::SE2d, void >::operator()
std::size_t operator()(const Sophus::SE2d &state) const
Calculates the tuple hash, using the given resolution for x, y and rotation given at construction tim...
Definition: spatial_hash.hpp:190
beluga::spatial_hash< Sophus::SE2d, void >::spatial_hash
spatial_hash(double linear_clustering_resolution, double angular_clustering_resolution)
Constructs a spatial hasher given per-group resolutions.
Definition: spatial_hash.hpp:179
beluga::spatial_hash< std::array< T, N >, std::enable_if_t< std::is_arithmetic_v< T >, void > >::operator()
constexpr std::size_t operator()(const std::array< T, N > &array) const
Calculates the array hash, with the resolutions in each axis, given at construction time.
Definition: spatial_hash.hpp:121
beluga::spatial_hash< Sophus::SE2d, void >::spatial_hash
spatial_hash(double x_clustering_resolution, double y_clustering_resolution, double theta_clustering_resolution)
Constructs a spatial hasher given per-coordinate resolutions.
Definition: spatial_hash.hpp:168
beluga::detail::hash_impl
constexpr std::size_t hash_impl(const T &value, const std::array< double, sizeof...(Ids)> &resolution, [[maybe_unused]] std::index_sequence< Ids... > index_sequence)
Definition: spatial_hash.hpp:88
se2.hpp
beluga::spatial_hash< std::array< T, N >, std::enable_if_t< std::is_arithmetic_v< T >, void > >::spatial_hash
spatial_hash(const resolution_in_each_axis_t &resolution)
Constructs a spatial hasher from an std::array of doubles.
Definition: spatial_hash.hpp:114
Sophus
beluga::spatial_hash< Tuple< Types... >, std::enable_if_t<(std::is_arithmetic_v< Types > &&...), void > >::spatial_hash
spatial_hash(const resolution_in_each_axis_t &resolution)
Constructs a spatial hasher from an std::array of doubles.
Definition: spatial_hash.hpp:141
Sophus::SE2
beluga::spatial_hash< Tuple< Types... >, std::enable_if_t<(std::is_arithmetic_v< Types > &&...), void > >::resolution_in_each_axis_t
std::array< double, sizeof...(Types)> resolution_in_each_axis_t
Type that represents the resolution in each axis.
Definition: spatial_hash.hpp:134
beluga::spatial_hash
Callable class, allowing to calculate the hash of a particle state.
Definition: spatial_hash.hpp:100
beluga::spatial_hash< Tuple< Types... >, std::enable_if_t<(std::is_arithmetic_v< Types > &&...), void > >::resolution_
resolution_in_each_axis_t resolution_
Definition: spatial_hash.hpp:153
beluga::spatial_hash< std::array< T, N >, std::enable_if_t< std::is_arithmetic_v< T >, void > >::resolution_in_each_axis_t
std::array< double, N > resolution_in_each_axis_t
Type that represents the resolution in each axis.
Definition: spatial_hash.hpp:107
beluga::spatial_hash< Tuple< Types... >, std::enable_if_t<(std::is_arithmetic_v< Types > &&...), void > >::operator()
constexpr std::size_t operator()(const Tuple< Types... > &tuple) const
Calculates the array hash, with the resolutions in each axis, given at construction time.
Definition: spatial_hash.hpp:148
beluga::detail::floor_and_fibo_hash
constexpr std::size_t floor_and_fibo_hash(double value)
Returns the hashed and rotated floor of a value.
Definition: spatial_hash.hpp:45
std
Definition: circular_array.hpp:529
SE2d
SE2< double > SE2d
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
beluga::spatial_hash< std::array< T, N >, std::enable_if_t< std::is_arithmetic_v< T >, void > >::resolution_
resolution_in_each_axis_t resolution_
Definition: spatial_hash.hpp:126


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53