ndt_sensor_model.hpp
Go to the documentation of this file.
1 // Copyright 2024 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_SENSOR_NDT_SENSOR_MODEL_HPP
16 #define BELUGA_SENSOR_NDT_SENSOR_MODEL_HPP
17 
18 #include <cassert>
19 #include <cstdint>
20 #include <filesystem>
21 #include <stdexcept>
22 #include <type_traits>
23 #include <unordered_map>
24 #include <vector>
25 
26 #include <H5Cpp.h>
27 
28 #include <Eigen/Core>
29 
30 #include <sophus/common.hpp>
31 #include <sophus/se2.hpp>
32 #include <sophus/se3.hpp>
33 #include <sophus/so2.hpp>
34 
38 
39 namespace beluga {
40 
41 namespace detail {
45 template <int N>
46 struct CellHasher {
48  size_t operator()(const Eigen::Vector<int, N> vector) const {
49  size_t seed = 0;
50  for (auto i = 0L; i < vector.size(); ++i) {
51  auto elem = *(vector.data() + i);
52  seed ^= std::hash<int>()(elem) + 0x9e3779b9 + (seed << 6) + (seed >> 2);
53  }
54  return seed;
55  }
56 };
57 
59 template <int NDim, typename Scalar = double>
60 inline NDTCell<NDim, Scalar> fit_points(const std::vector<Eigen::Vector<Scalar, NDim>>& points) {
61  static constexpr double kMinVariance = 1e-5;
62  Eigen::Map<const Eigen::Matrix<Scalar, NDim, Eigen::Dynamic>> points_view(
63  reinterpret_cast<const Scalar*>(points.data()), NDim, static_cast<int64_t>(points.size()));
64  const Eigen::Vector<Scalar, NDim> mean = points_view.rowwise().mean();
65  const Eigen::Matrix<Scalar, NDim, Eigen::Dynamic> centered = points_view.colwise() - mean;
66  // Use sample covariance.
67  Eigen::Matrix<Scalar, NDim, Eigen::Dynamic> cov =
68  (centered * centered.transpose()) / static_cast<double>(points_view.cols() - 1);
69  cov(0, 0) = std::max(cov(0, 0), kMinVariance);
70  cov(1, 1) = std::max(cov(1, 1), kMinVariance);
71  if constexpr (NDim == 3) {
72  cov(2, 2) = std::max(cov(2, 2), kMinVariance);
73  }
74  return NDTCell<NDim, Scalar>{mean, cov};
75 }
76 
80 template <int NDim, typename Scalar = double>
81 inline std::vector<NDTCell<NDim, Scalar>> to_cells(
82  const std::vector<Eigen::Vector<Scalar, NDim>>& points,
83  const double resolution) {
84  static constexpr int kMinPointsPerCell = 5;
85 
86  const Eigen::Map<const Eigen::Matrix<Scalar, NDim, Eigen::Dynamic>> points_view(
87  reinterpret_cast<const Scalar*>(points.data()), NDim, static_cast<int64_t>(points.size()));
88 
89  std::vector<NDTCell<NDim, Scalar>> ret;
90  ret.reserve(static_cast<size_t>(points_view.cols()) / kMinPointsPerCell);
91 
92  std::unordered_map<Eigen::Vector<int, NDim>, std::vector<Eigen::Vector<Scalar, NDim>>, CellHasher<NDim>> cell_grid;
93  for (const Eigen::Vector<Scalar, NDim>& col : points) {
94  cell_grid[(col / resolution).template cast<int>()].emplace_back(col);
95  }
96 
97  for (const auto& [cell, points_in_cell] : cell_grid) {
98  if (points_in_cell.size() < kMinPointsPerCell) {
99  continue;
100  }
101  ret.push_back(fit_points<NDim, Scalar>(points_in_cell));
102  }
103 
104  return ret;
105 }
107 const std::vector<Eigen::Vector2i> kDefaultNeighborKernel2d = {
108  Eigen::Vector2i{-1, -1}, //
109  Eigen::Vector2i{-1, -0}, //
110  Eigen::Vector2i{-1, 1}, //
111  Eigen::Vector2i{0, -1}, //
112  Eigen::Vector2i{0, 0}, //
113  Eigen::Vector2i{0, 1}, //
114  Eigen::Vector2i{1, -1}, //
115  Eigen::Vector2i{1, 0}, //
116  Eigen::Vector2i{1, 1}, //
117 };
118 
120 const std::vector<Eigen::Vector3i> kDefaultNeighborKernel3d = {
121  // TODO(Ramiro) revisit this kernel when we implement the 3D sensor model and extend this if it's computationally
122  // feasible.
123  Eigen::Vector3i{0, 0, 0}, //
124  Eigen::Vector3i{0, 0, 1}, //
125  Eigen::Vector3i{0, 0, -1}, //
126  Eigen::Vector3i{0, 1, 0}, //
127  Eigen::Vector3i{0, -1, 0}, //
128  Eigen::Vector3i{-1, 0, 0}, //
129  Eigen::Vector3i{1, 0, 0},
130 };
131 
133 template <int NDim>
134 constexpr std::conditional_t<NDim == 2, std::vector<Eigen::Vector2i>, std::vector<Eigen::Vector3i>>
136  if constexpr (NDim == 2) {
138  } else {
140  }
141 }
142 
143 } // namespace detail
144 
146 template <int NDim>
148  static_assert(NDim == 2 or NDim == 3, "Only 2D or 3D is supported for the NDT sensor model.");
150  double minimum_likelihood = 0;
152  double d1 = 1.0;
154  double d2 = 1.0;
156  std::conditional_t<NDim == 2, std::vector<Eigen::Vector2i>, std::vector<Eigen::Vector3i>> neighbors_kernel =
157  detail::get_default_neighbors_kernel<NDim>();
158 };
159 
162 
166 
171 template <typename SparseGridT>
173  public:
175  using ndt_cell_type = typename SparseGridT::mapped_type;
176  static_assert(std::is_same_v<SparseValueGrid<typename SparseGridT::map_type, ndt_cell_type::num_dim>, SparseGridT>);
177  static_assert(
178  ndt_cell_type::num_dim == 2 or ndt_cell_type::num_dim == 3,
179  "NDT sensor model is only implemented for 2D or 3D problems.");
181  using state_type = std::conditional_t<
182  ndt_cell_type::num_dim == 2,
186  using weight_type = double;
188  using measurement_type = std::vector<Eigen::Vector<typename ndt_cell_type::scalar_type, ndt_cell_type::num_dim>>;
190  using map_type = SparseGridT;
193 
195 
201  NDTSensorModel(param_type params, SparseGridT cells_data)
202  : params_{std::move(params)}, cells_data_{std::move(cells_data)} {
203  assert(params_.minimum_likelihood >= 0);
204  }
205 
207 
212  [[nodiscard]] auto operator()(measurement_type&& points) const {
213  return [this, cells = detail::to_cells<ndt_cell_type::num_dim, typename ndt_cell_type::scalar_type>(
214  points, cells_data_.resolution())](const state_type& state) -> weight_type {
215  return std::transform_reduce(
216  cells.cbegin(), cells.cend(), 1.0, std::plus{},
217  [this, state](const ndt_cell_type& ndt_cell) { return likelihood_at(state * ndt_cell); });
218  };
219  }
220 
223  [[nodiscard]] double likelihood_at(const ndt_cell_type& measurement) const {
224  double likelihood = 0;
225  const typename map_type::key_type measurement_cell = cells_data_.cell_near(measurement.mean);
226  for (const auto& offset : params_.neighbors_kernel) {
227  const auto maybe_ndt = cells_data_.data_at(measurement_cell + offset);
228  if (maybe_ndt.has_value()) {
229  likelihood += maybe_ndt->likelihood_at(measurement, params_.d1, params_.d2);
230  }
231  }
232  return std::max(likelihood, params_.minimum_likelihood);
233  }
234 
235  private:
237  const SparseGridT cells_data_;
238 };
239 
240 namespace io {
241 
252 template <typename NDTMapRepresentationT>
253 NDTMapRepresentationT load_from_hdf5(const std::filesystem::path& path_to_hdf5_file) {
254  static_assert(
255  std::is_same_v<typename NDTMapRepresentationT::mapped_type, NDTCell2d> or
256  std::is_same_v<typename NDTMapRepresentationT::mapped_type, NDTCell3d>);
257  static_assert(
258  std::is_same_v<typename NDTMapRepresentationT::key_type, Eigen::Vector2i> or
259  std::is_same_v<typename NDTMapRepresentationT::key_type, Eigen::Vector3i>);
260 
261  constexpr int kNumDim = NDTMapRepresentationT::key_type::RowsAtCompileTime;
262  if (!std::filesystem::exists(path_to_hdf5_file) || std::filesystem::is_directory(path_to_hdf5_file)) {
263  std::stringstream ss;
264  ss << "Couldn't find a valid HDF5 file at " << path_to_hdf5_file;
265  throw std::invalid_argument(ss.str());
266  }
267 
268  const H5::H5File file(path_to_hdf5_file, H5F_ACC_RDONLY);
269  const H5::DataSet means_dataset = file.openDataSet("means");
270  const H5::DataSet covariances_dataset = file.openDataSet("covariances");
271  const H5::DataSet resolution_dataset = file.openDataSet("resolution");
272  const H5::DataSet cells_dataset = file.openDataSet("cells");
273 
274  std::array<hsize_t, 2> dims_out;
275  means_dataset.getSpace().getSimpleExtentDims(dims_out.data(), nullptr);
276 
277  // The static cast is necessary because hsize_t and size_t are not the same in all platforms.
278  const std::array<std::size_t, 2> dims{
279  static_cast<std::size_t>(dims_out[0]),
280  static_cast<std::size_t>(dims_out[1]),
281  };
282 
283  Eigen::Matrix<double, kNumDim, Eigen::Dynamic> means_matrix(dims[1], dims[0]);
284  Eigen::Matrix<int, kNumDim, Eigen::Dynamic> cells_matrix(dims[1], dims[0]);
285 
286  means_dataset.read(means_matrix.data(), H5::PredType::NATIVE_DOUBLE);
287  cells_dataset.read(cells_matrix.data(), H5::PredType::NATIVE_INT);
288 
289  std::vector<Eigen::Array<double, kNumDim, kNumDim>> covariances(dims[0]);
290  covariances_dataset.read(covariances.data(), H5::PredType::NATIVE_DOUBLE);
291 
292  double resolution;
293 
294  resolution_dataset.read(&resolution, H5::PredType::NATIVE_DOUBLE);
295 
296  typename NDTMapRepresentationT::map_type map{};
297 
298  // Note: Ranges::zip_view doesn't seem to work in old Eigen.
299  for (size_t i = 0; i < covariances.size(); ++i) {
300  map[cells_matrix.col(static_cast<Eigen::Index>(i))] =
301  NDTCell<kNumDim, double>{means_matrix.col(static_cast<Eigen::Index>(i)), covariances.at(i)};
302  }
303 
304  return NDTMapRepresentationT{std::move(map), resolution};
305 }
306 
307 } // namespace io
308 
309 } // namespace beluga
310 
311 #endif
beluga::NDTSensorModel::map_type
SparseGridT map_type
Map representation type.
Definition: ndt_sensor_model.hpp:190
beluga::detail::kDefaultNeighborKernel2d
const std::vector< Eigen::Vector2i > kDefaultNeighborKernel2d
Default neighbor kernel for the 2D NDT sensor model.
Definition: ndt_sensor_model.hpp:107
eigen_compatibility.hpp
beluga::NDTSensorModel::measurement_type
std::vector< Eigen::Vector< typename ndt_cell_type::scalar_type, ndt_cell_type::num_dim > > measurement_type
Measurement type of the sensor: a point cloud for the range finder.
Definition: ndt_sensor_model.hpp:188
beluga::NDTSensorModel::likelihood_at
double likelihood_at(const ndt_cell_type &measurement) const
Definition: ndt_sensor_model.hpp:223
beluga::detail::CellHasher
Definition: ndt_sensor_model.hpp:46
beluga::detail::CellHasher::operator()
size_t operator()(const Eigen::Vector< int, N > vector) const
Hashes an integer N dimensional integer vector.
Definition: ndt_sensor_model.hpp:48
beluga::NDTSensorModel::operator()
auto operator()(measurement_type &&points) const
Returns a state weighting function conditioned on 2D / 3D lidar hits.
Definition: ndt_sensor_model.hpp:212
beluga::state
constexpr state_detail::state_fn state
Customization point object for accessing the state of a particle.
Definition: primitives.hpp:163
beluga::NDTCell
Representation for a cell of a N dimensional NDT cell.
Definition: ndt_cell.hpp:36
beluga::NDTSensorModel::ndt_cell_type
typename SparseGridT::mapped_type ndt_cell_type
NDT Cell type.
Definition: ndt_sensor_model.hpp:175
beluga::NDTSensorModel::cells_data_
const SparseGridT cells_data_
Definition: ndt_sensor_model.hpp:237
beluga::detail::get_default_neighbors_kernel
constexpr std::conditional_t< NDim==2, std::vector< Eigen::Vector2i >, std::vector< Eigen::Vector3i > > get_default_neighbors_kernel()
Helper to get the default neighbors kernel.
Definition: ndt_sensor_model.hpp:135
beluga::detail::kDefaultNeighborKernel3d
const std::vector< Eigen::Vector3i > kDefaultNeighborKernel3d
Default neighbor kernel for the 3D NDT sensor model.
Definition: ndt_sensor_model.hpp:120
se2.hpp
beluga::NDTSensorModel::weight_type
double weight_type
Weight type of the particle.
Definition: ndt_sensor_model.hpp:186
beluga::NDTSensorModel::state_type
std::conditional_t< ndt_cell_type::num_dim==2, Sophus::SE2< typename ndt_cell_type::scalar_type >, Sophus::SE3< typename ndt_cell_type::scalar_type > > state_type
State type of a particle.
Definition: ndt_sensor_model.hpp:184
beluga::NDTModelParam::minimum_likelihood
double minimum_likelihood
Likelihood for measurements that lie inside cells that are not present in the map.
Definition: ndt_sensor_model.hpp:150
common.hpp
beluga::NDTSensorModel::params_
const param_type params_
Definition: ndt_sensor_model.hpp:236
beluga::SparseValueGrid
Generic N dimensional sparse value regular grid.
Definition: sparse_value_grid.hpp:46
beluga::detail::fit_points
NDTCell< NDim, Scalar > fit_points(const std::vector< Eigen::Vector< Scalar, NDim >> &points)
Fit a vector of points to an NDT cell, by computing its mean and covariance.
Definition: ndt_sensor_model.hpp:60
Sophus::SE2
so2.hpp
Sophus::SE3
beluga::NDTSensorModel::NDTSensorModel
NDTSensorModel(param_type params, SparseGridT cells_data)
Constructs a NDTSensorModel instance.
Definition: ndt_sensor_model.hpp:201
beluga::NDTSensorModel
NDT sensor model for range finders.
Definition: ndt_sensor_model.hpp:172
beluga::io::load_from_hdf5
NDTMapRepresentationT load_from_hdf5(const std::filesystem::path &path_to_hdf5_file)
Definition: ndt_sensor_model.hpp:253
beluga::NDTModelParam::neighbors_kernel
std::conditional_t< NDim==2, std::vector< Eigen::Vector2i >, std::vector< Eigen::Vector3i > > neighbors_kernel
Neighbor kernel used for likelihood computation.
Definition: ndt_sensor_model.hpp:156
beluga::NDTModelParam::d2
double d2
Scaling parameter d2 in literature, used for scaling likelihoods.
Definition: ndt_sensor_model.hpp:154
beluga::detail::to_cells
std::vector< NDTCell< NDim, Scalar > > to_cells(const std::vector< Eigen::Vector< Scalar, NDim >> &points, const double resolution)
Definition: ndt_sensor_model.hpp:81
beluga::NDTModelParam
Parameters used to construct a NDTSensorModel instance.
Definition: ndt_sensor_model.hpp:147
Eigen::Vector
Eigen::Matrix< Scalar, Dims, 1 > Vector
Type alias for single-column matrices, available starting Eigen 3.4.
Definition: eigen_compatibility.hpp:24
beluga::NDTModelParam::d1
double d1
Scaling parameter d1 in literature, used for scaling likelihoods.
Definition: ndt_sensor_model.hpp:152
sparse_value_grid.hpp
Implementation of generic sparse value regular grid.
ndt_cell.hpp
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
se3.hpp


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