diff --git a/beluga/include/beluga/algorithm/raycasting.hpp b/beluga/include/beluga/algorithm/raycasting.hpp index b0514f81a..6873ae70b 100644 --- a/beluga/include/beluga/algorithm/raycasting.hpp +++ b/beluga/include/beluga/algorithm/raycasting.hpp @@ -36,19 +36,19 @@ namespace beluga { /// Castable 2D ray. /** - * \tparam Grid A 2D grid + * \tparam OccupancyGrid A 2D occupancy grid * \tparam Algorithm A callable type, taking start and end * grid cells for a ray and returning the full trace. */ -template +template class Ray2d { public: /// Constructs 2D ray with default ray tracing algorithm. /** - * See Ray2d(const Grid &, Algorithm, const Sophus::SE2d&, double) + * See Ray2d(const OccupancyGrid &, Algorithm, const Sophus::SE2d&, double) * for further reference on constructor arguments. */ - explicit Ray2d(const Grid& grid, const Sophus::SE2d& source_pose, double max_range) noexcept + explicit Ray2d(const OccupancyGrid& grid, const Sophus::SE2d& source_pose, double max_range) noexcept : Ray2d(grid, Algorithm{}, source_pose, max_range) {} /// Constructs 2D ray with an specific ray tracing algorithm. @@ -59,10 +59,15 @@ class Ray2d { * same frame as that on which the `grid` origin is defined. * \param max_range Maximum range for the ray, in meters. */ - explicit Ray2d(const Grid& grid, Algorithm algorithm, const Sophus::SE2d& source_pose, double max_range) noexcept + explicit Ray2d( + const OccupancyGrid& grid, + Algorithm algorithm, + const Sophus::SE2d& source_pose, + double max_range) noexcept : grid_(grid), algorithm_(std::move(algorithm)), - source_pose_in_grid_frame_(grid_.origin().inverse() * source_pose), + source_pose_in_local_frame_(grid_.origin().inverse() * source_pose), + source_cell_(grid_.cell_near(source_pose_in_local_frame_.translation())), max_range_(max_range) {} /// Computes ray trace along a given direction. @@ -75,11 +80,10 @@ class Ray2d { const auto far_end_pose_in_source_frame = Sophus::SE2d{ Sophus::SO2d{0.}, Eigen::Vector2d{max_range_ * bearing.unit_complex().x(), max_range_ * bearing.unit_complex().y()}}; - const auto far_end_pose_in_grid_frame = source_pose_in_grid_frame_ * far_end_pose_in_source_frame; - const auto start_cell = grid_.cell(source_pose_in_grid_frame_.translation()); - const auto end_cell = grid_.cell(far_end_pose_in_grid_frame.translation()); - const auto cell_is_valid = [this](const auto& cell) { return grid_.valid(cell); }; - return algorithm_(start_cell, end_cell) | ranges::views::take_while(cell_is_valid); + const auto far_end_pose_in_local_frame = source_pose_in_local_frame_ * far_end_pose_in_source_frame; + const auto far_end_cell = grid_.cell_near(far_end_pose_in_local_frame.translation()); + const auto cell_is_valid = [this](const auto& cell) { return grid_.contains(cell); }; + return algorithm_(source_cell_, far_end_cell) | ranges::views::take_while(cell_is_valid); } /// Casts ray along a given direction. @@ -90,14 +94,11 @@ class Ray2d { * \return Distance in meters to first non free cell hit by the ray, if any. */ [[nodiscard]] std::optional cast(const Sophus::SO2d& bearing) const { - const auto is_free = [this](const auto& cell) { - // TODO(hidmic): move to occupancy grid API - return Grid::Traits::is_free(grid_.data()[grid_.index(cell)]); - }; for (const auto& cell : trace(bearing)) { - if (!is_free(cell)) { - const auto start_cell = grid_.cell(source_pose_in_grid_frame_.translation()); - const auto distance = (grid_.point(cell) - grid_.point(start_cell)).norm(); + if (!grid_.free_at(cell)) { + const auto source_position = grid_.coordinates_at(source_cell_); + const auto cell_position = grid_.coordinates_at(cell); + const auto distance = (cell_position - source_position).norm(); return std::make_optional(std::min(distance, max_range_)); } } @@ -105,9 +106,10 @@ class Ray2d { } private: - const Grid& grid_; + const OccupancyGrid& grid_; const Algorithm algorithm_; - const Sophus::SE2d source_pose_in_grid_frame_; + const Sophus::SE2d source_pose_in_local_frame_; + const Eigen::Vector2i source_cell_; const double max_range_; }; diff --git a/beluga/include/beluga/sensor/beam_model.hpp b/beluga/include/beluga/sensor/beam_model.hpp index 49841a037..9b74ad0e5 100644 --- a/beluga/include/beluga/sensor/beam_model.hpp +++ b/beluga/include/beluga/sensor/beam_model.hpp @@ -23,6 +23,7 @@ #include +#include #include #include #include @@ -65,7 +66,7 @@ struct BeamModelParam { * * \tparam Mixin The mixed-in type with no particular requirements. * \tparam OccupancyGrid Type representing an occupancy grid. - * It must satisfy \ref OccupancyGrid2dPage. + * It must satisfy \ref OccupancyGrid2Page. */ template class BeamSensorModel : public Mixin { @@ -89,8 +90,13 @@ class BeamSensorModel : public Mixin { * \param ...rest Arguments that are not used by this part of the mixin, but by others. */ template - explicit BeamSensorModel(const param_type& params, const OccupancyGrid& grid, Args&&... rest) - : Mixin(std::forward(rest)...), grid_{grid}, free_cells_{make_free_cells_vector(grid)}, params_{params} {} + explicit BeamSensorModel(const param_type& params, OccupancyGrid grid, Args&&... rest) + : Mixin(std::forward(rest)...), + params_{params}, + grid_{std::move(grid)}, + free_states_{ + grid_.coordinates_for(grid_.free_cells(), OccupancyGrid::Frame::kGlobal) | + ranges::to>} {} // TODO(ivanpauno): is sensor model the best place for this? // Maybe the map could be provided by a different part of the mixin, @@ -108,9 +114,8 @@ class BeamSensorModel : public Mixin { */ template [[nodiscard]] state_type make_random_state(Generator& gen) const { - auto index_distribution = std::uniform_int_distribution{0, free_cells_.size() - 1}; - return Sophus::SE2d{ - Sophus::SO2d::sampleUniform(gen), grid_.origin() * grid_.point(free_cells_[index_distribution(gen)])}; + auto index_distribution = std::uniform_int_distribution{0, free_states_.size() - 1}; + return Sophus::SE2d{Sophus::SO2d::sampleUniform(gen), free_states_[index_distribution(gen)]}; } /// Gets the importance weight for a particle with the provided state. @@ -166,22 +171,11 @@ class BeamSensorModel : public Mixin { } private: - static std::vector make_free_cells_vector(const OccupancyGrid& grid) { - auto free_cells = std::vector{}; - free_cells.reserve(grid.size()); - for (std::size_t index = 0; index < grid.size(); ++index) { - if (OccupancyGrid::Traits::is_free(grid.data()[index])) { - free_cells.push_back(index); - } - } - return free_cells; - } - + param_type params_; OccupancyGrid grid_; + std::vector free_states_; std::vector> points_; - std::vector free_cells_; mutable std::shared_mutex points_mutex_; - param_type params_; }; } // namespace beluga diff --git a/beluga/include/beluga/sensor/data/dense_grid.hpp b/beluga/include/beluga/sensor/data/dense_grid.hpp new file mode 100644 index 000000000..fba2c2721 --- /dev/null +++ b/beluga/include/beluga/sensor/data/dense_grid.hpp @@ -0,0 +1,167 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BELUGA_SENSOR_DATA_DENSE_GRID_HPP +#define BELUGA_SENSOR_DATA_DENSE_GRID_HPP + +#include +#include + +#include + +#include + +/** + * \file + * \brief Concepts and abstract implementations of dense grids. + */ + +namespace beluga { + +/** + * \page DenseGrid2Page Beluga named requirements: DenseGrid2 + * + * Dense grids support random, indexed access to each cell. These + * grids have a finite extent and thus can hold cell data in finite + * memory. Dense grids are regular grids, meaning they satisfy + * \ref RegularGrid2Page requirements. + * + * A type `G` satisfies `DenseGrid2` requirements if it satisfies + * \ref RegularGrid2Page and given `g` a possibly const instance of `G`: + * - `g.width()` returns the grid width, in grid cells along the grid + * x-axis, as an `std::size_t` value. + * - `g.height()` returns the grid height, in grid cells along the grid + * y-axis, as an `std::size_t` value. + * - given possibly const grid cell coordinates `xi` and `yi` of type `int`, + * `g.contains(xi, yi)` checks whether such cell is included in the grid; + * - given possibly const grid cell coordinates `pi` of `Eigen::Vector2i` type, + * `g.contains(p)` checks whether such cell is included in the grid; + * - given possibly const grid cell coordinates `xi` and `yi` of type `int`, + * `g.index_at(xi, yi)` retrieves the corresponding cell index of some type; + * - given possibly const grid cell coordinates `pi` of `Eigen::Vector2i` type, + * `g.index_at(pi)` retrieves the corresponding cell index of some type; + * - given possibly const grid cell coordinates `xi` and `yi` of type `int`, + * `g.data_at(xi, yi)` optionally returns cell data, if cell is included; + * - given possibly const grid cell coordinates `pi` of `Eigen::Vector2i` type, + * `g.data_at(p)` optionally returns cell data, if cell is included; + * - given possibly const grid cell index `i` of some type, `g.data_at(i)` + * optionally returns cell data, if cell is included; + * - given possibly const embedding space coordinates `x` and `y` of type `double`, + * `g.data_near(x, y)` optionally returns cell data, if cell is included; + * - given possibly const embedding space coordinates `p` of `Eigen::Vector2d` type, + * `g.data_near(p)` optionally returns cell data, if cell is included; + * - given possibly const grid cell coordinates `xi` and `yi` of type `int`, + * `g.neighborhood4(xi, yi)` computes the cell 4-connected neighborhood as + * a range of `Eigen::Vector2i` type; + * - given possibly const grid cell coordinates `pi` of `Eigen::Vector2i` type, + * `g.neighborhood4(p)` computes the cell 4-connected neighborhood as a + * range of `Eigen::Vector2i` type. + */ + +/// Dense 2D grid base type. +/** + * When instantiated, it satisfies \ref DenseGrid2Page. + * + * \tparam Derived Concrete dense grid type. It must define + * `Derived::width()`, `Derived::height()`, `Derived::resolution()`, + * `Derived::data_at(index)`, and `Derived::index_at(int, int)` + * as described in \ref DenseGrid2Page. + */ +template +class BaseDenseGrid2 : public BaseRegularGrid2 { + public: + /// Checks if a cell is included in the grid. + /** + * \param xi Grid cell x-axis coordinate. + * \param yi Grid cell y-axis coordinate. + */ + [[nodiscard]] bool contains(int xi, int yi) const { + return xi >= 0 && xi < static_cast(this->self().width()) && yi >= 0 && + yi < static_cast(this->self().height()); + } + + /// Checks if a cell is included in the grid. + /** + * \param pi Grid cell coordinates. + */ + [[nodiscard]] bool contains(const Eigen::Vector2i& pi) const { return this->self().contains(pi.x(), pi.y()); } + + /// Gets cell data, if included. + /** + * \param xi Grid cell x-axis coordinate. + * \param yi Grid cell y-axis coordinate. + * \return Cell data if included, `std::nullopt` otherwise. + */ + [[nodiscard]] auto data_at(int xi, int yi) const { + return this->self().contains(xi, yi) ? this->self().data_at(this->self().index_at(xi, yi)) : std::nullopt; + } + + /// Gets cell data, if included. + /** + * \param pi Grid cell coordinates. + * \return Cell data if included, `std::nullopt` otherwise. + */ + [[nodiscard]] auto data_at(const Eigen::Vector2i& pi) const { return this->self().data_at(pi.x(), pi.y()); } + + /// Gets nearest cell data, if included. + /** + * \param x Plane x-axis coordinate. + * \param y Plane y-axis coordinate. + * \return Cell data if included, `std::nullopt` otherwise. + */ + [[nodiscard]] auto data_near(double x, double y) const { return this->self().data_at(this->self().cell_near(x, y)); } + + /// Gets nearest cell data, if included. + /** + * \param p Plane coordinates. + * \return Cell data if included, `std::nullopt` otherwise. + */ + [[nodiscard]] auto data_near(const Eigen::Vector2d& p) const { return this->self().data_near(p.x(), p.y()); } + + /// Computes 4-connected neighborhood for cell. + /** + * \param xi Grid cell x-axis coordinate. + * \param yi Grid cell y-axis coordinate. + * \return range of neighbor cells. + */ + [[nodiscard]] auto neighborhood4(int xi, int yi) const { + auto result = std::vector{}; + if (xi < static_cast(this->self().width() - 1)) { + result.emplace_back(xi + 1, yi); + } + if (yi < static_cast(this->self().height() - 1)) { + result.emplace_back(xi, yi + 1); + } + if (xi > 0) { + result.emplace_back(xi - 1, yi); + } + if (yi > 0) { + result.emplace_back(xi, yi - 1); + } + return result; + } + + /// Computes 4-connected neighborhood for cell. + /** + * \param pi Grid cell coordinates. + * \return range of neighbor cells. + */ + [[nodiscard]] auto neighborhood4(const Eigen::Vector2i& pi) const { + return this->self().neighborhood4(pi.x(), pi.y()); + } +}; + +} // namespace beluga + +#endif diff --git a/beluga/include/beluga/sensor/data/linear_grid.hpp b/beluga/include/beluga/sensor/data/linear_grid.hpp new file mode 100644 index 000000000..0b295e7ff --- /dev/null +++ b/beluga/include/beluga/sensor/data/linear_grid.hpp @@ -0,0 +1,133 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BELUGA_SENSOR_DATA_LINEAR_GRID_HPP +#define BELUGA_SENSOR_DATA_LINEAR_GRID_HPP + +#include +#include +#include + +#include + +#include + +/** + * \file + * \brief Concepts and abstract implementations of linear (ie. contiguous storage) grids. + */ + +namespace beluga { + +/** + * \page LinearGrid2Page Beluga named requirements: LinearGrid2 + * + * Linear grids use contiguous memory layouts, and thus afford integer + * indexes. Linear grids are dense grids, meaning they satisfy + * \ref DenseGrid2Page requirements. + * + * A type `G` satisfies `LinearGrid2` requirements if it satisfies + * \ref DenseGrid2Page and given `g` a possibly const instance of `G`: + * - `g.data()` returns a possibly const reference to an indexable, + * random access linear data structure containing grid cell data values; + * - given possibly const grid cell index `i` of `std::size_t` type, + * `g.data_at(i)` optionally returns cell data, if cell is included; + * - given possibly const grid cell index `i` of `std::size_t` type, + * `g.coordinates_at(i)` returns embedding space coordinates as an + * `Eigen::Vector2d` value; + * - given possibly const grid cell index `i` of `std::size_t` type, + * `g.neighborhood4(i)` computes the cell 4-connected neighborhood as a + * range of `std::size_t` indices. + */ + +/// Linear 2D grid base type. +/** + * When instantiated, it satisfies \ref LinearGrid2Page. + * + * \tparam Derived Concrete linear grid type. It must define + * `Derived::width()`, `Derived::height()`, `Derived::resolution()`, + * `Derived::data_at(std::size_t)`, `Derived::index_at(int, int)`, + * and `Derived::data()` as described in \ref LinearGrid2Page. + */ +template +class BaseLinearGrid2 : public BaseDenseGrid2 { + public: + /// Computes index for given grid cell coordinates. + /* + * \param xi Grid cell x-axis coordinate. + * \param yi Grid cell y-axis coordinate. + */ + [[nodiscard]] std::size_t index_at(int xi, int yi) const { + return static_cast(yi) * this->self().width() + static_cast(xi); + } + + /// Computes index for given grid cell coordinates. + /** + * \param pi Grid cell coordinates. + */ + [[nodiscard]] std::size_t index_at(const Eigen::Vector2i& pi) const { return this->self().index_at(pi.x(), pi.y()); } + + using BaseDenseGrid2::coordinates_at; + + /// Compute plane coordinates given a grid cell index. + /** + * \param index Grid cell index. + * \return Plane coordinates of the cell centroid. + */ + [[nodiscard]] Eigen::Vector2d coordinates_at(std::size_t index) const { + return this->self().coordinates_at( + static_cast(index % this->self().width()), static_cast(index / this->self().width())); + } + + using BaseDenseGrid2::data_at; + + /// Gets cell data, if included. + /** + * \param index Grid cell index. + * \return Cell data if included, `std::nullopt` otherwise. + */ + [[nodiscard]] auto data_at(std::size_t index) const { + return index < this->self().size() ? std::make_optional(this->self().data()[index]) : std::nullopt; + } + + using BaseDenseGrid2::neighborhood4; + + /// Computes 4-connected neighborhood for cell. + /** + * \param index Grid cell index. + * \return range of neighbor cells' indices. + */ + [[nodiscard]] auto neighborhood4(std::size_t index) const { + auto result = std::vector{}; + const std::size_t xi = index % this->self().width(); + const std::size_t yi = index / this->self().width(); + if (xi < (this->self().width() - 1)) { + result.push_back(index + 1); + } + if (yi < (this->self().height() - 1)) { + result.push_back(index + this->self().width()); + } + if (xi > 0) { + result.push_back(index - 1); + } + if (yi > 0) { + result.push_back(index - this->self().width()); + } + return result; + } +}; + +} // namespace beluga + +#endif diff --git a/beluga/include/beluga/sensor/data/occupancy_grid.hpp b/beluga/include/beluga/sensor/data/occupancy_grid.hpp new file mode 100644 index 000000000..c6b3692c9 --- /dev/null +++ b/beluga/include/beluga/sensor/data/occupancy_grid.hpp @@ -0,0 +1,186 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BELUGA_SENSOR_DATA_OCCUPANCY_GRID_HPP +#define BELUGA_SENSOR_DATA_OCCUPANCY_GRID_HPP + +#include +#include +#include + +#include + +#include +#include +#include + +#include + +/** + * \file + * \brief Concepts and abstract implementations of occupancy grids. + */ + +namespace beluga { + +/** + * \page OccupancyGrid2Page Beluga named requirements: OccupancyGrid2d + * + * Occupancy grids model obstacle probability. These grids also define + * their own frame in the grid embedding space, adding so called global + * coordinates to regular (aka local) coordinates. Occupancy grids as + * defined in Beluga are linear grids, meaning they satisfy + * \ref LinearGrid2Page requirements. + * + * A type `G` satisfies `OccupancyGrid2d` requirements if it satisfies + * \ref LinearGrid2Page and given `g` a possible const instance of `G`: + * - `g.value_traits()` returns a value `t` of type `T` such that given a grid cell + * data value `v`: + * - `t.is_free(v)` returns true if the value is consistent with a free grid cell; + * - `t.is_occupied(v)` returns true if the value is consistent with an occupied grid cell; + * - `g.origin()` returns the transform, of `Sophus::SE2d` type, from the global to local + * frame in the grid embedding space; + * - given possibly const grid cell index `i` of `std::size_t` type, + * `g.free_at(i)` returns true if such cell is free; + * - given possibly const grid cell coordinates `xi` and `yi` of type `int`, + * `g.free_at(xi, yi)` returns true if such cell is free; + * - given possibly const grid cell coordinates `pi` of `Eigen::Vector2i` type, + * `g.free_at(p)` returns true if such cell is free; + * - given possibly const embedding space coordinates `x` and `y` of type `double`, + * `g.free_near(x, y)` returns true if the nearest cell is free; + * - given possibly const embedding space coordinates `p` of `Eigen::Vector2d` type, + * `g.free_near(p)` returns true if the nearest cell is free; + * - given possibly const grid cell index `i` of `std::size_t` type and frame `f`, + * `g.coordinates_at(i, f)` returns embedding space coordinates in the corresponding + * frame as an `Eigen::Vector2d` value; + * - given a possibly const range `r` of grid cell coordinates or indices and frame `f`, + * `g.coordinates_for(r, f)` returns a range of embedding space coordinates in the + * corresponding frame as `Eigen::Vector2d` values; + * - `g.free_cells()` returns a range of `std::size_t` indices to free grid cells; + * - `g.obstacle_data()` returns a range of `bool` values, representing grid cell occupancy; + */ + +/// Occupancy 2D grid base type. +/** + * When instantiated, it satisfies \ref OccupancyGrid2Page. + * + * \tparam Derived Concrete occupancy grid type. It must define + * `Derived::origin()`, `Derived::width()`, `Derived::height()`, + * `Derived::resolution()`, `Derived::data_at(std::size_t)`, + * `Derived::index_at(int, int)`, `Derived::data()`, and + * `Derived::value_traits()` as described in \ref OccupancyGrid2Page. + */ +template +class BaseOccupancyGrid2 : public BaseLinearGrid2 { + public: + /// Coordinate frames. + enum class Frame { kLocal, kGlobal }; + + /// Checks if cell is free. + /** + * Note cells not included in the grid are non-free too. + * + * \param index Grid cell index. + */ + [[nodiscard]] bool free_at(std::size_t index) const { + const auto data = this->self().data_at(index); + if (!data.has_value()) { + return false; + } + return this->self().value_traits().is_free(data.value()); + } + + /// Checks if cell is free. + /** + * Note cells not included in the grid are non-free too. + * + * \param xi Grid cell x-axis coordinate. + * \param yi Grid cell y-axis coordinate. + */ + [[nodiscard]] bool free_at(int xi, int yi) const { return this->self().free_at(this->self().index_at(xi, yi)); } + + /// Checks if cell is free. + /** + * Note cells not included in the grid are non-free too. + * + * \param pi Grid cell coordinates. + */ + [[nodiscard]] bool free_at(const Eigen::Vector2i& pi) const { return this->self().free_at(pi.x(), pi.y()); } + + /// Checks if nearest cell is free. + /** + * Note cells not included in the grid are non-free too. + * + * \param x Plane x-axis coordinate. + * \param y Plane y-axis coordinate. + */ + [[nodiscard]] bool free_near(double x, double y) const { return this->self().free_at(this->self().cell_near(x, y)); } + + /// Checks if nearest cell is free. + /** + * Note cells not included in the grid are non-free too. + * + * \param p Plane coordinates. + */ + [[nodiscard]] bool free_near(const Eigen::Vector2d& p) const { return this->self().free_near(p.x(), p.y()); } + + using BaseLinearGrid2::coordinates_at; + + /// Compute plane coordinates given grid cell coordinates. + /** + * \param index Grid cell index. + * \param frame Plane coordinate frame. + * \return Plane coordinates in the corresponding `frame`. + */ + [[nodiscard]] auto coordinates_at(std::size_t index, Frame frame) const { + auto position = this->self().coordinates_at(index); + if (frame == Frame::kGlobal) { + position = this->self().origin() * position; + } + return position; + } + + /// Compute plane coordinates for a range of grid cells. + /** + * \param cells Range of grid cell indices or coordinates. + * \param frame Plane coordinate frame. + * \return Range of plane coordinates in the corresponding `frame`. + */ + template + [[nodiscard]] auto coordinates_for(Range&& cells, Frame frame) const { + return cells | ranges::views::transform( + [this, frame](const auto& cell) { return this->self().coordinates_at(cell, frame); }); + } + + /// Retrieves range of free grid cell indices. + [[nodiscard]] auto free_cells() const { + return ranges::views::enumerate(this->self().data()) | + ranges::views::filter([value_traits = this->self().value_traits()](const auto& tuple) { + return value_traits.is_free(std::get<1>(tuple)); + }) | + ranges::views::transform([](const auto& tuple) { return std::get<0>(tuple); }); + } + + /// Retrieves grid data using true booleans for obstacles. + [[nodiscard]] auto obstacle_data() const { + return this->self().data() | + ranges::views::transform([value_traits = this->self().value_traits()](const auto& value) { + return value_traits.is_occupied(value); + }); + } +}; + +}; // namespace beluga + +#endif diff --git a/beluga/include/beluga/sensor/data/regular_grid.hpp b/beluga/include/beluga/sensor/data/regular_grid.hpp new file mode 100644 index 000000000..c5cf88bb0 --- /dev/null +++ b/beluga/include/beluga/sensor/data/regular_grid.hpp @@ -0,0 +1,131 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BELUGA_SENSOR_DATA_REGULAR_GRID_HPP +#define BELUGA_SENSOR_DATA_REGULAR_GRID_HPP + +#include + +#include + +#include + +#include + +/** + * \file + * \brief Concepts and abstract implementations of regular grids. + */ + +namespace beluga { + +/** + * \page RegularGrid2Page Beluga named requirements: RegularGrid2 + * + * Regular grids divide space in evenly sized portions or _cells_. A coordinate + * system over integers can thus be defined, in addition to that of the space + * in which the grid is embedded. + * + * A type `G` satisfies `RegularGrid2` requirements if given `g` a possibly + * const instance of `G`: + * - `g.resolution()` returns the side length of all grid cells as a `double`; + * - given possibly const embedding space coordinates `x` and `y` of type `double`, + * `g.cell_at(x, y)` returns grid cell coordinates as an `Eigen::Vector2d` value; + * - given possibly const embedding space coordinates `p` of `Eigen::Vector2d` type, + * `g.cell_at(p)` returns grid cell coordinates as an `Eigen::Vector2d` value; + * - given possibly const grid cell coordinates `xi` and `yi` of type `int`, + * `g.coordinates_at(xi, yi)` returns embedding space coordinates as an + * `Eigen::Vector2d` value; + * - given possibly const grid cell coordinates `pi` of `Eigen::Vector2i` type, + * `g.coordinates_at(p)` returns embedding space coordinates as an + * `Eigen::Vector2d` value; + * - given a possibly const range `r` of grid cell coordinates of `Eigen::Vector2i` + * type, `g.coordinates_for(r)` returns a range of embedding space coordinates as + * `Eigen::Vector2d` values. + */ + +/// Regularly spaced 2D grid base type. +/** + * When instantiated, it satisfies \ref RegularGrid2Page. + * + * \tparam Derived Concrete regular grid type. It must define + * `Derived::resolution()`, as described in \ref RegularGrid2Page. + */ +template +class BaseRegularGrid2 : public ciabatta::ciabatta_top { + public: + /// Compute nearest grid cell coordinates given plane coordinates. + /** + * Note this is a surjective function. + * + * \param x Plane x-axis coordinate. + * \param y Plane y-axis coordinate. + * \return Grid cell coordinates. + */ + [[nodiscard]] Eigen::Vector2i cell_near(double x, double y) const { + const auto xi = static_cast(std::floor(x / this->self().resolution())); + const auto yi = static_cast(std::floor(y / this->self().resolution())); + return Eigen::Vector2i{xi, yi}; + } + + /// Compute nearest grid cell coordinates given plane coordinates. + /** + * Note this is a surjective function. + * + * \param p Plane coordinates. + * \return Grid cell coordinates. + */ + [[nodiscard]] Eigen::Vector2i cell_near(const Eigen::Vector2d& p) const { + return this->self().cell_near(p.x(), p.y()); + } + + /// Compute plane coordinates given grid cell coordinates. + /** + * Note this is an injective function. + * + * \param xi Grid cell x-axis coordinate. + * \param yi Grid cell y-axis coordinate. + * \return Plane coordinates of the cell centroid. + */ + [[nodiscard]] Eigen::Vector2d coordinates_at(int xi, int yi) const { + return Eigen::Vector2d{ + (static_cast(xi) + 0.5) * this->self().resolution(), + (static_cast(yi) + 0.5) * this->self().resolution()}; + } + + /// Compute plane coordinates given grid cell coordinates. + /** + * Note this is an injective function. + * + * \param pi Grid cell coordinates. + * \return Plane coordinates of the cell centroid. + */ + [[nodiscard]] Eigen::Vector2d coordinates_at(const Eigen::Vector2i& pi) const { + return this->self().coordinates_at(pi.x(), pi.y()); + } + + /// Compute plane coordinates given a range of cell coordinates. + /** + * \param cells Range of grid cell identifiers. + * \return Range of plane coordinates. + */ + template + [[nodiscard]] auto coordinates_for(Range&& cells) const { + return cells | ranges::views::transform([this](const auto& cell) { return this->self().coordinates_at(cell); }); + } +}; + +} // namespace beluga + +#endif diff --git a/beluga/include/beluga/sensor/data/value_grid.hpp b/beluga/include/beluga/sensor/data/value_grid.hpp new file mode 100644 index 000000000..0fc1f206d --- /dev/null +++ b/beluga/include/beluga/sensor/data/value_grid.hpp @@ -0,0 +1,73 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BELUGA_SENSOR_DATA_VALUE_GRID_HPP +#define BELUGA_SENSOR_DATA_VALUE_GRID_HPP + +#include +#include +#include + +#include + +/** + * \file + * \brief Implementation of generic value grid. + */ + +namespace beluga { + +/// Generic 2D linear value grid. +/** + * \tparam T Any copyable type. + */ +template +class ValueGrid2 : public BaseLinearGrid2> { + public: + /// Constructs the grid. + /** + * \param data Grid data. + * \param width Grid width. Must evenly divide `data` size. + * \param resolution Grid resolution. + */ + explicit ValueGrid2(std::vector data, std::size_t width, double resolution = 1.) + : data_(std::move(data)), width_(width), height_(data_.size() / width), resolution_(resolution) { + assert(data_.size() % width == 0); + } + + /// Gets grid width. + [[nodiscard]] std::size_t width() const { return width_; } + + /// Gets grid height. + [[nodiscard]] std::size_t height() const { return height_; } + + /// Gets grid resolution. + [[nodiscard]] double resolution() const { return resolution_; } + + /// Gets grid size (ie. number of grid cells). + [[nodiscard]] std::size_t size() const { return data_.size(); } + + /// Gets grid data. + [[nodiscard]] const std::vector& data() const { return data_; } + + private: + std::vector data_; + std::size_t width_; + std::size_t height_; + double resolution_; +}; + +} // namespace beluga + +#endif diff --git a/beluga/include/beluga/sensor/likelihood_field_model.hpp b/beluga/include/beluga/sensor/likelihood_field_model.hpp index 900ad27cb..673d6d0b6 100644 --- a/beluga/include/beluga/sensor/likelihood_field_model.hpp +++ b/beluga/include/beluga/sensor/likelihood_field_model.hpp @@ -22,6 +22,8 @@ #include #include +#include +#include #include #include #include @@ -59,41 +61,6 @@ struct LikelihoodFieldModelParam { double sigma_hit; }; -/** - * \page OccupancyGrid2dPage Beluga named requirements: OccupancyGrid2d - * - * A type `G` satisfies the `OccupancyGrid2d` requirements if. - * Given `g` a possible const instance of `G`: - * - `g.size()` returns a `std::size_t`, representing the occupancy grid size. - * - `g.data()` returns a const [rancom access range](https://en.cppreference.com/w/cpp/ranges/random_access_range), - * with value type `C`. - * - `g.neighbors()` returns a range with value type std::size_t. - * The elements of the range are valid cell indexes, i.e. for each `i` of the returned range `i < g.size()` is true - * and `g.data()[i]` is valid. - * - `g.origin()` return the occupancy grid origin as a `Sophus::SE2d`. - * - Given possibly const values `x` and `y` of type `int`, `g.valid(x, y)` returns whether a cell at those - * discrete coordinates exists. - * - Given possibly const `Eigen::Vector2i` `c`, `g.valid(c)` is equivalent to `g.point(c.x(), c.y())`. - * - Given a possibly const `std::size_t` `i` less than `g.size()`, `g.point(i)` returns the continuous - * coordinates of the centroid of the cell at index `i` in the grid frame as a `Eigen::Vector2d`. - * - Given possibly const values `x` and `y` of type `int`, `g.point(x, y)` returns the continuous - * coordinates in the grid frame of the centroid of the cell at those discrete coordinates - * as a `Eigen::Vector2d`. - * - Given a possibly const `Eigen::Vector2i` `c`, `g.point(c)` is equivalent to `g.point(c.x(), c.y())`. - * - Given possibly const values `x` and `y` of type `double`, `g.index(x, y)` returns a `std::size`, - * representing the index of the cell. - * - Given a possibly const `Eigen::Vector2d` `p`, `g.index(p)` is equivalent to `g.index(p.x(), p.y())`. - * - Given possibly const values `x` and `y` of type `int`, `g.index(x, y)` returns a `std::size`, - * representing the index of the cell at those discrete coordinates. - * - Given a possibly const `Eigen::Vector2i` `c`, `g.index(c)` is equivalent to `g.index(c.x(), c.y())`. - * - * Given c a possible const instance of C: - * - OccupancyGrid::Traits::is_free(c) returns true if the cell is free, false if not. - * - OccupancyGrid::Traits::is_occupied(c) returns true if the cell is occupied, false if not. - * - OccupancyGrid::Traits::is_unknown(c) returns true if it is unknown whether the cell is occupied or not, - * else false. - */ - /// Likelihood field sensor model for range finders. /** * This class implements the LaserSensorModelInterface2d interface @@ -103,7 +70,7 @@ struct LikelihoodFieldModelParam { * * \tparam Mixin The mixed-in type with no particular requirements. * \tparam OccupancyGrid Type representing an occupancy grid. - * It must satisfy \ref OccupancyGrid2dPage. + * It must satisfy \ref OccupancyGrid2Page. */ template class LikelihoodFieldModel : public Mixin { @@ -127,12 +94,14 @@ class LikelihoodFieldModel : public Mixin { * \param ...rest Arguments that are not used by this part of the mixin, but by others. */ template - explicit LikelihoodFieldModel(const param_type& params, const OccupancyGrid& grid, Args&&... rest) + explicit LikelihoodFieldModel(const param_type& params, OccupancyGrid grid, Args&&... rest) : Mixin(std::forward(rest)...), params_{params}, - grid_{grid}, - free_cells_{make_free_cells_vector(grid)}, - likelihood_field_{make_likelihood_field(params, grid)} {} + grid_{std::move(grid)}, + free_states_{ + grid_.coordinates_for(grid_.free_cells(), OccupancyGrid::Frame::kGlobal) | + ranges::to>}, + likelihood_field_{make_likelihood_field(params, grid_)} {} /// Returns the likelihood field, constructed from the provided map. const auto& likelihood_field() const { return likelihood_field_; } @@ -153,9 +122,8 @@ class LikelihoodFieldModel : public Mixin { */ template [[nodiscard]] state_type make_random_state(Generator& gen) const { - auto index_distribution = std::uniform_int_distribution{0, free_cells_.size() - 1}; - return Sophus::SE2d{ - Sophus::SO2d::sampleUniform(gen), grid_.origin() * grid_.point(free_cells_[index_distribution(gen)])}; + auto index_distribution = std::uniform_int_distribution{0, free_states_.size() - 1}; + return Sophus::SE2d{Sophus::SO2d::sampleUniform(gen), free_states_[index_distribution(gen)]}; } /// Gets the importance weight for a particle with the provided state. @@ -173,13 +141,12 @@ class LikelihoodFieldModel : public Mixin { [this, x_offset = transform.translation().x(), y_offset = transform.translation().y(), cos_theta = transform.so2().unit_complex().x(), sin_theta = transform.so2().unit_complex().y(), unknown_space_occupancy_prob = 1. / params_.max_laser_distance](const auto& point) { - // Transform the end point of the laser to the global coordinate system. + // Transform the end point of the laser to the grid local coordinate system. // Not using Eigen/Sophus because they make the routine x10 slower. // See `benchmark_likelihood_field_model.cpp` for reference. const auto x = point.first * cos_theta - point.second * sin_theta + x_offset; const auto y = point.first * sin_theta + point.second * cos_theta + y_offset; - const auto index = grid_.index(x, y); - const auto pz = index < likelihood_field_.size() ? likelihood_field_[index] : unknown_space_occupancy_prob; + const auto pz = likelihood_field_.data_near(x, y).value_or(unknown_space_occupancy_prob); return pz * pz * pz; }); } @@ -193,41 +160,31 @@ class LikelihoodFieldModel : public Mixin { private: param_type params_; OccupancyGrid grid_; - std::vector free_cells_; - std::vector likelihood_field_; + std::vector free_states_; + ValueGrid2 likelihood_field_; std::vector> points_; mutable std::shared_mutex points_mutex_; - static std::vector make_free_cells_vector(const OccupancyGrid& grid) { - auto free_cells = std::vector{}; - free_cells.reserve(grid.size()); - for (std::size_t index = 0; index < grid.size(); ++index) { - if (OccupancyGrid::Traits::is_free(grid.data()[index])) { - free_cells.push_back(index); - } - } - return free_cells; - } - - static std::vector make_likelihood_field(const LikelihoodFieldModelParam& params, const OccupancyGrid& grid) { - const auto obstacle_map = grid.data() | ranges::views::transform(&OccupancyGrid::Traits::is_occupied); - - auto squared_distance = [&grid, squared_max_distance = params.max_obstacle_distance * params.max_obstacle_distance]( - std::size_t first, std::size_t second) { - return std::min((grid.point(first) - grid.point(second)).squaredNorm(), squared_max_distance); + static ValueGrid2 make_likelihood_field(const LikelihoodFieldModelParam& params, const OccupancyGrid& grid) { + const auto squared_distance = [&grid, + squared_max_distance = params.max_obstacle_distance * params.max_obstacle_distance]( + std::size_t first, std::size_t second) { + return std::min((grid.coordinates_at(first) - grid.coordinates_at(second)).squaredNorm(), squared_max_distance); }; - const auto distance_map = nearest_obstacle_distance_map( - obstacle_map, squared_distance, [&grid](std::size_t index) { return grid.neighbors(index); }); + const auto neighborhood = [&grid](std::size_t index) { return grid.neighborhood4(index); }; + + const auto distance_map = nearest_obstacle_distance_map(grid.obstacle_data(), squared_distance, neighborhood); - auto to_likelihood = [amplitude = - params.z_hit / (params.sigma_hit * std::sqrt(2 * Sophus::Constants::pi())), - two_squared_sigma = 2 * params.sigma_hit * params.sigma_hit, - offset = params.z_random / params.max_laser_distance](double squared_distance) { + const auto to_likelihood = [amplitude = + params.z_hit / (params.sigma_hit * std::sqrt(2 * Sophus::Constants::pi())), + two_squared_sigma = 2 * params.sigma_hit * params.sigma_hit, + offset = params.z_random / params.max_laser_distance](double squared_distance) { return amplitude * std::exp(-squared_distance / two_squared_sigma) + offset; }; - return distance_map | ranges::views::transform(to_likelihood) | ranges::to; + auto likelihood_data = distance_map | ranges::views::transform(to_likelihood) | ranges::to; + return ValueGrid2{std::move(likelihood_data), grid.width(), grid.resolution()}; } }; diff --git a/beluga/test/beluga/CMakeLists.txt b/beluga/test/beluga/CMakeLists.txt index f8e899fbb..5214c17c8 100644 --- a/beluga/test/beluga/CMakeLists.txt +++ b/beluga/test/beluga/CMakeLists.txt @@ -15,6 +15,10 @@ add_executable(test_beluga resampling_policies/test_resample_on_motion_policy.cpp resampling_policies/test_resampling_policies_poller.cpp resampling_policies/test_selective_resampling_policy.cpp + sensor/data/test_dense_grid.cpp + sensor/data/test_linear_grid.cpp + sensor/data/test_occupancy_grid.cpp + sensor/data/test_regular_grid.cpp sensor/test_beam_model.cpp sensor/test_likelihood_field_model.cpp test_mixin.cpp diff --git a/beluga/test/beluga/algorithm/test_raycasting.cpp b/beluga/test/beluga/algorithm/test_raycasting.cpp index da462a271..c65f7f78b 100644 --- a/beluga/test/beluga/algorithm/test_raycasting.cpp +++ b/beluga/test/beluga/algorithm/test_raycasting.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "beluga/algorithm/raycasting.hpp" +#include "beluga/test/static_occupancy_grid.hpp" #include @@ -20,101 +21,7 @@ namespace beluga { -template -class StaticOccupancyGrid { - public: - struct Traits { - static bool is_free(bool value) { return !value; } - static bool is_unknown(bool) { return false; } - static bool is_occupied(bool value) { return value; } - }; - - explicit StaticOccupancyGrid( - std::array array, - double resolution = 1.0, - const Sophus::SE2d& origin = Sophus::SE2d{}) - : grid_{array}, origin_{origin}, origin_inverse_{origin.inverse()}, resolution_{resolution} {} - - [[nodiscard]] std::size_t size() const { return grid_.size(); } - - [[nodiscard]] const auto& data() const { return grid_; } - - [[nodiscard]] const Sophus::SE2d& origin() const { return origin_; } - - [[nodiscard]] const Sophus::SE2d& origin_inverse() const { return origin_inverse_; } - - [[nodiscard]] bool valid(int xi, int yi) const { - return xi >= 0 && xi < static_cast(width()) && yi >= 0 && yi < static_cast(height()); - } - - [[nodiscard]] bool valid(const Eigen::Vector2i& cell) const { return valid(cell.x(), cell.y()); } - - [[nodiscard]] std::size_t index(double x, double y) const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return index(xi, yi); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2d& point) const { return index(point.x(), point.y()); } - - [[nodiscard]] std::size_t index(int xi, int yi) const { - if (!valid(xi, yi)) { - return size(); - } - return static_cast(xi) + static_cast(yi) * width(); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2i& cell) const { return index(cell.x(), cell.y()); } - - [[nodiscard]] Eigen::Vector2i cell(double x, double y) const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return Eigen::Vector2i{xi, yi}; - } - - [[nodiscard]] Eigen::Vector2i cell(const Eigen::Vector2d& point) const { return cell(point.x(), point.y()); } - - [[nodiscard]] Eigen::Vector2d point(int xi, int yi) const { - return Eigen::Vector2d{ - (static_cast(xi) + 0.5) * resolution(), (static_cast(yi) + 0.5) * resolution()}; - } - - [[nodiscard]] Eigen::Vector2d point(const Eigen::Vector2i& cell) const { return point(cell.x(), cell.y()); } - - [[nodiscard]] Eigen::Vector2d point(std::size_t index) const { - return Eigen::Vector2d{ - (static_cast(index % width()) + 0.5) * resolution(), - (static_cast(index / width()) + 0.5) * resolution()}; // NOLINT(bugprone-integer-division) - } - - [[nodiscard]] auto neighbors(std::size_t index) const { - auto result = std::vector{}; - const std::size_t row = index / width(); - const std::size_t col = index % width(); - if (row < (height() - 1)) { - result.push_back(index + width()); - } - if (row > 0) { - result.push_back(index - width()); - } - if (col < (width() - 1)) { - result.push_back(index + 1); - } - if (col > 0) { - result.push_back(index - 1); - } - return result; - } - [[nodiscard]] double resolution() const { return resolution_; } - [[nodiscard]] std::size_t width() const { return Cols; } - [[nodiscard]] std::size_t height() const { return Rows; } - - private: - std::array grid_; - Sophus::SE2d origin_; - Sophus::SE2d origin_inverse_; - double resolution_; -}; +using testing::StaticOccupancyGrid; TEST(Raycasting, Nominal) { constexpr double kResolution = 0.5; diff --git a/beluga/test/beluga/include/beluga/test/static_occupancy_grid.hpp b/beluga/test/beluga/include/beluga/test/static_occupancy_grid.hpp new file mode 100644 index 000000000..fd0ccaec2 --- /dev/null +++ b/beluga/test/beluga/include/beluga/test/static_occupancy_grid.hpp @@ -0,0 +1,62 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BELUGA_TEST_STATIC_OCCUPANCY_GRID_HPP +#define BELUGA_TEST_STATIC_OCCUPANCY_GRID_HPP + +#include +#include + +#include "beluga/sensor/data/occupancy_grid.hpp" + +#include + +namespace beluga::testing { + +template +class StaticOccupancyGrid : public BaseOccupancyGrid2> { + public: + struct ValueTraits { + [[nodiscard]] bool is_free(bool value) const { return !value; } + [[nodiscard]] bool is_unknown(bool) const { return false; } + [[nodiscard]] bool is_occupied(bool value) const { return value; } + }; + + explicit StaticOccupancyGrid( + std::array array, + double resolution = 1.0, + const Sophus::SE2d& origin = Sophus::SE2d{}) + : grid_{array}, origin_(origin), resolution_{resolution} {} + + [[nodiscard]] const Sophus::SE2d& origin() const { return origin_; } + + [[nodiscard]] auto& data() { return grid_; } + [[nodiscard]] const auto& data() const { return grid_; } + [[nodiscard]] std::size_t size() const { return grid_.size(); } + + [[nodiscard]] std::size_t width() const { return Cols; } + [[nodiscard]] std::size_t height() const { return Rows; } + [[nodiscard]] double resolution() const { return resolution_; } + + [[nodiscard]] auto value_traits() const { return ValueTraits{}; } + + private: + std::array grid_; + Sophus::SE2d origin_; + double resolution_; +}; + +} // namespace beluga::testing + +#endif diff --git a/beluga/test/beluga/sensor/data/test_dense_grid.cpp b/beluga/test/beluga/sensor/data/test_dense_grid.cpp new file mode 100644 index 000000000..a0cd2a8ff --- /dev/null +++ b/beluga/test/beluga/sensor/data/test_dense_grid.cpp @@ -0,0 +1,144 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include +#include +#include + +#include "beluga/sensor/data/dense_grid.hpp" + +#include + +#include + +namespace { + +template +class Image : public beluga::BaseDenseGrid2> { + public: + using index_type = std::pair; + using value_type = uint8_t; + + Image() = default; + + explicit Image(std::array, H> data) : data_(std::move(data)) {} + + [[nodiscard]] index_type index_at(int xi, int yi) const { + return index_type{static_cast(xi), static_cast(yi)}; + } + + [[nodiscard]] index_type index_at(const Eigen::Vector2i& pi) const { return index_at(pi.x(), pi.y()); } + + using beluga::BaseDenseGrid2>::data_at; + + [[nodiscard]] std::optional data_at(const index_type& index) const { + return index.first < W && index.second < H ? std::make_optional(data_[index.first][index.second]) : std::nullopt; + } + + [[nodiscard]] std::size_t width() const { return W; } + [[nodiscard]] std::size_t height() const { return H; } + [[nodiscard]] double resolution() const { return 1.; } + + private: + std::array, H> data_; +}; + +TEST(DenseGrid2, Limits) { + const auto grid = Image<5, 5>{}; + + EXPECT_TRUE(grid.contains(0, 0)); + EXPECT_FALSE(grid.contains(-1, 0)); + EXPECT_FALSE(grid.contains(0, -1)); + EXPECT_TRUE(grid.contains(2, 2)); + EXPECT_FALSE(grid.contains(5, 0)); + EXPECT_FALSE(grid.contains(0, 5)); + + EXPECT_TRUE(grid.contains(Eigen::Vector2i(0, 0))); + EXPECT_FALSE(grid.contains(Eigen::Vector2i(-1, 0))); + EXPECT_FALSE(grid.contains(Eigen::Vector2i(0, -1))); + EXPECT_TRUE(grid.contains(Eigen::Vector2i(2, 2))); + EXPECT_FALSE(grid.contains(Eigen::Vector2i(5, 0))); + EXPECT_FALSE(grid.contains(Eigen::Vector2i(0, 5))); +} + +TEST(DenseGrid2, Data) { + const auto grid = + Image<5, 5>({{{0, 0, 0, 0, 0}, {0, 1, 1, 1, 0}, {0, 1, 2, 1, 0}, {0, 1, 1, 1, 0}, {0, 0, 0, 0, 0}}}); + + EXPECT_EQ(grid.data_at(0, 0), 0); + EXPECT_EQ(grid.data_at(2, 2), 2); + EXPECT_EQ(grid.data_at(3, 1), 1); + EXPECT_EQ(grid.data_at(-1, 0), std::nullopt); + EXPECT_EQ(grid.data_at(0, -1), std::nullopt); + EXPECT_EQ(grid.data_at(5, 0), std::nullopt); + EXPECT_EQ(grid.data_at(0, 5), std::nullopt); + + EXPECT_EQ(grid.data_at(Eigen::Vector2i(0, 0)), 0); + EXPECT_EQ(grid.data_at(Eigen::Vector2i(2, 2)), 2); + EXPECT_EQ(grid.data_at(Eigen::Vector2i(3, 1)), 1); + EXPECT_EQ(grid.data_at(Eigen::Vector2i(-1, 0)), std::nullopt); + EXPECT_EQ(grid.data_at(Eigen::Vector2i(0, -1)), std::nullopt); + EXPECT_EQ(grid.data_at(Eigen::Vector2i(5, 0)), std::nullopt); + EXPECT_EQ(grid.data_at(Eigen::Vector2i(0, 5)), std::nullopt); +} + +TEST(DenseGrid2, NearestData) { + const auto grid = + Image<5, 5>({{{0, 0, 0, 0, 0}, {0, 1, 1, 1, 0}, {0, 1, 2, 1, 0}, {0, 1, 1, 1, 0}, {0, 0, 0, 0, 0}}}); + + EXPECT_EQ(grid.data_near(0.8, 0.2), 0); + EXPECT_EQ(grid.data_near(2.1, 2.9), 2); + EXPECT_EQ(grid.data_near(3.5, 1.5), 1); + EXPECT_EQ(grid.data_near(-0.1, 0), std::nullopt); + EXPECT_EQ(grid.data_near(0, -0.1), std::nullopt); + EXPECT_EQ(grid.data_near(5.25, 0), std::nullopt); + EXPECT_EQ(grid.data_near(0, 5.25), std::nullopt); + + EXPECT_EQ(grid.data_near(Eigen::Vector2d(0.8, 0.2)), 0); + EXPECT_EQ(grid.data_near(Eigen::Vector2d(2.1, 2.9)), 2); + EXPECT_EQ(grid.data_near(Eigen::Vector2d(3.5, 1.5)), 1); + EXPECT_EQ(grid.data_near(Eigen::Vector2d(-0.1, 0)), std::nullopt); + EXPECT_EQ(grid.data_near(Eigen::Vector2d(0, -0.1)), std::nullopt); + EXPECT_EQ(grid.data_near(Eigen::Vector2d(5.25, 0)), std::nullopt); + EXPECT_EQ(grid.data_near(Eigen::Vector2d(0, 5.25)), std::nullopt); +} + +TEST(DenseGrid2, Neighborhood4) { + const auto grid = Image<5, 5>{}; + + { + const auto expected_neighborhood = + std::vector{Eigen::Vector2i{3, 2}, Eigen::Vector2i{2, 3}, Eigen::Vector2i{1, 2}, Eigen::Vector2i{2, 1}}; + ASSERT_THAT(grid.neighborhood4(2, 2), testing::Pointwise(testing::Eq(), expected_neighborhood)); + ASSERT_THAT(grid.neighborhood4(Eigen::Vector2i(2, 2)), testing::Pointwise(testing::Eq(), expected_neighborhood)); + } + + { + const auto expected_neighborhood = std::vector{Eigen::Vector2i{1, 0}, Eigen::Vector2i{0, 1}}; + ASSERT_THAT(grid.neighborhood4(0, 0), testing::Pointwise(testing::Eq(), expected_neighborhood)); + ASSERT_THAT(grid.neighborhood4(Eigen::Vector2i(0, 0)), testing::Pointwise(testing::Eq(), expected_neighborhood)); + } + + { + const auto expected_neighborhood = std::vector{Eigen::Vector2i{3, 4}, Eigen::Vector2i{4, 3}}; + ASSERT_THAT(grid.neighborhood4(4, 4), testing::Pointwise(testing::Eq(), expected_neighborhood)); + ASSERT_THAT(grid.neighborhood4(Eigen::Vector2i(4, 4)), testing::Pointwise(testing::Eq(), expected_neighborhood)); + } +} + +} // namespace diff --git a/beluga/test/beluga/sensor/data/test_linear_grid.cpp b/beluga/test/beluga/sensor/data/test_linear_grid.cpp new file mode 100644 index 000000000..f711d1118 --- /dev/null +++ b/beluga/test/beluga/sensor/data/test_linear_grid.cpp @@ -0,0 +1,62 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include +#include + +#include "beluga/sensor/data/value_grid.hpp" + +#include + +namespace { + +TEST(LinearGrid2, Indices) { + constexpr std::size_t kWidth = 4; + const auto grid = beluga::ValueGrid2{{{true, false, true, false, false, true, false, true}}, kWidth}; + + EXPECT_EQ(grid.index_at(0, 0), 0); + EXPECT_EQ(grid.index_at(3, 1), 7); + + EXPECT_EQ(grid.index_at(Eigen::Vector2i(0, 0)), 0); + EXPECT_EQ(grid.index_at(Eigen::Vector2i(3, 1)), 7); +} + +TEST(LinearGrid2, CoordinatesAtIndex) { + constexpr std::size_t kWidth = 4; + constexpr std::size_t kResolution = 1; + const auto grid = + beluga::ValueGrid2{{{true, false, true, false, false, true, false, true}}, kWidth, kResolution}; + + EXPECT_EQ(grid.coordinates_at(0), Eigen::Vector2d(0.5, 0.5)); + EXPECT_EQ(grid.coordinates_at(3), Eigen::Vector2d(3.5, 0.5)); + EXPECT_EQ(grid.coordinates_at(5), Eigen::Vector2d(1.5, 1.5)); +} + +TEST(LinearGrid2, DataAtIndex) { + constexpr std::size_t kWidth = 4; + constexpr std::size_t kResolution = 1; + const auto grid = + beluga::ValueGrid2{{{true, false, true, false, false, true, false, true}}, kWidth, kResolution}; + + EXPECT_TRUE(grid.data_at(0).value()); + EXPECT_FALSE(grid.data_at(3).value()); + EXPECT_TRUE(grid.data_at(5).value()); + EXPECT_EQ(grid.data_at(10), std::nullopt); +} + +} // namespace diff --git a/beluga/test/beluga/sensor/data/test_occupancy_grid.cpp b/beluga/test/beluga/sensor/data/test_occupancy_grid.cpp new file mode 100644 index 000000000..6aa089da5 --- /dev/null +++ b/beluga/test/beluga/sensor/data/test_occupancy_grid.cpp @@ -0,0 +1,103 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include +#include + +#include "beluga/test/static_occupancy_grid.hpp" + +#include + +#include +#include + +namespace { + +using beluga::testing::StaticOccupancyGrid; + +TEST(OccupancyGrid2, FreeAtCell) { + constexpr double kResolution = 1.; + + const auto grid = StaticOccupancyGrid<5, 5>{ + {false, false, false, false, true, false, false, false, true, false, false, false, true, + false, false, false, true, false, false, false, true, false, false, false, false}, + kResolution}; + + EXPECT_TRUE(grid.free_at(0)); + EXPECT_FALSE(grid.free_at(8)); + EXPECT_FALSE(grid.free_at(2, 2)); + EXPECT_TRUE(grid.free_at(3, 2)); + EXPECT_FALSE(grid.free_at(Eigen::Vector2i(0, 4))); + EXPECT_TRUE(grid.free_at(Eigen::Vector2i(1, 4))); +} + +TEST(OccupancyGrid2, FreeNearCell) { + constexpr double kResolution = 1.; + + const auto grid = StaticOccupancyGrid<5, 5>{ + {false, false, false, false, true, false, false, false, true, false, false, false, true, + false, false, false, true, false, false, false, true, false, false, false, false}, + kResolution}; + + EXPECT_FALSE(grid.free_near(3.25, 1.75)); + EXPECT_TRUE(grid.free_near(4, 4.25)); + EXPECT_FALSE(grid.free_near(Eigen::Vector2d(3.25, 1.75))); + EXPECT_TRUE(grid.free_near(Eigen::Vector2d(4, 4.25))); +} + +TEST(OccupancyGrid2, GlobalCoordinatesAtCell) { + constexpr double kResolution = 1.; + const auto origin = Sophus::SE2d{Sophus::SO2d{Sophus::Constants::pi() / 2.}, Eigen::Vector2d{1., 1.}}; + const auto grid = StaticOccupancyGrid<5, 5>{ + {false, false, false, false, true, false, false, false, true, false, false, false, true, + false, false, false, true, false, false, false, true, false, false, false, false}, + kResolution, + origin}; + + constexpr auto kFrame = StaticOccupancyGrid<5, 5>::Frame::kGlobal; + EXPECT_TRUE(grid.coordinates_at(grid.index_at(2, 2), kFrame).isApprox(Eigen::Vector2d(-1.5, 3.5))); +} + +TEST(OccupancyGrid2, AllFreeCells) { + const auto grid = StaticOccupancyGrid<2, 5>{{false, false, false, false, true, false, false, false, true, false}}; + + const auto expected_free_cells = std::vector{0, 1, 2, 3, 5, 6, 7, 9}; + ASSERT_THAT(grid.free_cells() | ranges::to, testing::Pointwise(testing::Eq(), expected_free_cells)); +} + +TEST(OccupancyGrid2, ObstacleData) { + const auto grid = StaticOccupancyGrid<5, 2>{{false, false, false, false, true, false, false, false, true, false}}; + + // Data and obstacle data are equivalent in this case + ASSERT_THAT(grid.obstacle_data() | ranges::to, testing::Pointwise(testing::Eq(), grid.data())); +} + +TEST(OccupancyGrid2, GlobalCoordinatesForCells) { + constexpr double kResolution = 1.; + const auto origin = Sophus::SE2d{Sophus::SO2d{Sophus::Constants::pi() / 2.}, Eigen::Vector2d{1., 1.}}; + const auto grid = StaticOccupancyGrid<2, 3>{{false, true, false, true, false, true}, kResolution, origin}; + + constexpr auto kFrame = StaticOccupancyGrid<2, 3>::Frame::kGlobal; + const auto coordinates = grid.coordinates_for(grid.free_cells(), kFrame) | ranges::to; + EXPECT_EQ(coordinates.size(), 3); + EXPECT_TRUE(coordinates[0].isApprox(Eigen::Vector2d{0.5, 1.5})); + EXPECT_TRUE(coordinates[1].isApprox(Eigen::Vector2d{0.5, 3.5})); + EXPECT_TRUE(coordinates[2].isApprox(Eigen::Vector2d{-0.5, 2.5})); +} + +} // namespace diff --git a/beluga/test/beluga/sensor/data/test_regular_grid.cpp b/beluga/test/beluga/sensor/data/test_regular_grid.cpp new file mode 100644 index 000000000..4cb51183e --- /dev/null +++ b/beluga/test/beluga/sensor/data/test_regular_grid.cpp @@ -0,0 +1,58 @@ +// Copyright 2023 Ekumen, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "beluga/sensor/data/regular_grid.hpp" + +#include + +namespace { + +class TestRegularGrid2 : public beluga::BaseRegularGrid2 { + public: + [[nodiscard]] static double resolution() { return 1.; } +}; + +TEST(RegularGrid2, NearestCells) { + const auto grid = TestRegularGrid2{}; + + EXPECT_EQ(grid.cell_near(0, 0), Eigen::Vector2i(0, 0)); + EXPECT_EQ(grid.cell_near(1.5, 0.5), Eigen::Vector2i(1, 0)); + + EXPECT_EQ(grid.cell_near(Eigen::Vector2d(0, 0)), Eigen::Vector2i(0, 0)); + EXPECT_EQ(grid.cell_near(Eigen::Vector2d(1.5, 0.5)), Eigen::Vector2i(1, 0)); +} + +TEST(RegularGrid2, CoordinatesAtCell) { + const auto grid = TestRegularGrid2{}; + + EXPECT_TRUE(grid.coordinates_at(0, 0).isApprox(Eigen::Vector2d(0.5, 0.5))); + EXPECT_TRUE(grid.coordinates_at(1, 0).isApprox(Eigen::Vector2d(1.5, 0.5))); + + EXPECT_TRUE(grid.coordinates_at(Eigen::Vector2i(0, 0)).isApprox(Eigen::Vector2d(0.5, 0.5))); + EXPECT_TRUE(grid.coordinates_at(Eigen::Vector2i(1, 0)).isApprox(Eigen::Vector2d(1.5, 0.5))); +} + +TEST(RegularGrid2, CoordinatesForCells) { + const auto grid = TestRegularGrid2{}; + + const auto cells = std::vector{Eigen::Vector2i(1, 0), Eigen::Vector2i(4, 1)}; + const auto coordinates = grid.coordinates_for(cells) | ranges::to; + EXPECT_EQ(coordinates.size(), 2); + EXPECT_TRUE(coordinates[0].isApprox(Eigen::Vector2d(1.5, 0.5))); + EXPECT_TRUE(coordinates[1].isApprox(Eigen::Vector2d(4.5, 1.5))); +} + +} // namespace diff --git a/beluga/test/beluga/sensor/test_beam_model.cpp b/beluga/test/beluga/sensor/test_beam_model.cpp index af8752630..d8c5b4c46 100644 --- a/beluga/test/beluga/sensor/test_beam_model.cpp +++ b/beluga/test/beluga/sensor/test_beam_model.cpp @@ -12,110 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include + #include "beluga/algorithm/raycasting.hpp" #include "beluga/sensor.hpp" #include "beluga/sensor/beam_model.hpp" -#include "ciabatta/ciabatta.hpp" - -#include - -namespace beluga { - -template -class StaticOccupancyGrid { - public: - struct Traits { - static bool is_free(bool value) { return !value; } - static bool is_unknown(bool) { return false; } - static bool is_occupied(bool value) { return value; } - }; - - explicit StaticOccupancyGrid( - std::array array, - double resolution = 1.0, - const Sophus::SE2d& origin = Sophus::SE2d{}) - : grid_{array}, origin_{origin}, origin_inverse_{origin.inverse()}, resolution_{resolution} {} - - [[nodiscard]] std::size_t size() const { return grid_.size(); } - - [[nodiscard]] const auto& data() const { return grid_; } - - [[nodiscard]] const Sophus::SE2d& origin() const { return origin_; } - - [[nodiscard]] const Sophus::SE2d& origin_inverse() const { return origin_inverse_; } - [[nodiscard]] bool valid(int xi, int yi) const { - return xi >= 0 && xi < static_cast(width()) && yi >= 0 && yi < static_cast(height()); - } +#include "beluga/test/static_occupancy_grid.hpp" - [[nodiscard]] bool valid(const Eigen::Vector2i& cell) const { return valid(cell.x(), cell.y()); } - - [[nodiscard]] Eigen::Vector2i cell(double x, double y) const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return Eigen::Vector2i{xi, yi}; - } - - [[nodiscard]] Eigen::Vector2i cell(const Eigen::Vector2d& point) const { return cell(point.x(), point.y()); } - - [[nodiscard]] std::size_t index(int xi, int yi) const { - if (!valid(xi, yi)) { - return size(); // If the point is outside the map, return an invalid index - } - return static_cast(xi) + static_cast(yi) * width(); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2i& cell) const { return index(cell.x(), cell.y()); } - - [[nodiscard]] std::size_t index(double x, double y) const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return index(xi, yi); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2d& point) const { return index(point.x(), point.y()); } - - [[nodiscard]] Eigen::Vector2d point(int xi, int yi) const { - return Eigen::Vector2d{ - (static_cast(xi) + 0.5) * resolution(), (static_cast(yi) + 0.5) * resolution()}; - } - - [[nodiscard]] Eigen::Vector2d point(const Eigen::Vector2i& cell) const { return point(cell.x(), cell.y()); } - - [[nodiscard]] Eigen::Vector2d point(std::size_t index) const { - return point( - static_cast(index % width()), static_cast(index / width())); // NOLINT(bugprone-integer-division) - } - - [[nodiscard]] auto neighbors(std::size_t index) const { - auto result = std::vector{}; - const std::size_t row = index / width(); - const std::size_t col = index % width(); - if (row < (height() - 1)) { - result.push_back(index + width()); - } - if (row > 0) { - result.push_back(index - width()); - } - if (col < (width() - 1)) { - result.push_back(index + 1); - } - if (col > 0) { - result.push_back(index - 1); - } - return result; - } - [[nodiscard]] double resolution() const { return resolution_; } +#include "ciabatta/ciabatta.hpp" - private: - std::array grid_; - Sophus::SE2d origin_; - Sophus::SE2d origin_inverse_; - double resolution_; +namespace beluga { - [[nodiscard]] std::size_t width() const { return Cols; } - [[nodiscard]] std::size_t height() const { return Rows; } -}; +using beluga::testing::StaticOccupancyGrid; using UUT = ciabatta::mixin< ciabatta::curry>::mixin, diff --git a/beluga/test/beluga/sensor/test_likelihood_field_model.cpp b/beluga/test/beluga/sensor/test_likelihood_field_model.cpp index 770eacbe2..fdbb11495 100644 --- a/beluga/test/beluga/sensor/test_likelihood_field_model.cpp +++ b/beluga/test/beluga/sensor/test_likelihood_field_model.cpp @@ -12,79 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "beluga/sensor.hpp" +#include "beluga/sensor/likelihood_field_model.hpp" +#include "beluga/test/static_occupancy_grid.hpp" -#include -#include +#include "ciabatta/ciabatta.hpp" -namespace { +#include -template -class StaticOccupancyGrid { - public: - struct Traits { - static bool is_free(bool value) { return !value; } - static bool is_unknown(bool) { return false; } - static bool is_occupied(bool value) { return value; } - }; +namespace { - explicit StaticOccupancyGrid( - std::array array, - double resolution = 1.0, - const Sophus::SE2d& origin = Sophus::SE2d{}) - : grid_{array}, origin_{origin}, origin_inverse_{origin.inverse()}, resolution_{resolution} {} - - [[nodiscard]] std::size_t size() const { return grid_.size(); } - [[nodiscard]] const auto& data() const { return grid_; } - [[nodiscard]] const Sophus::SE2d& origin() const { return origin_; } - [[nodiscard]] const Sophus::SE2d& origin_inverse() const { return origin_inverse_; } - - [[nodiscard]] std::size_t index(double x, double y) const { - const auto x_index = static_cast(std::floor(x / resolution())); - const auto y_index = static_cast(std::floor(y / resolution())); - if (x_index >= width() || y_index >= height()) { - return size(); // If the point is outside the map, return an invalid index - } - return x_index + y_index * width(); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2d& point) const { return index(point.x(), point.y()); } - - [[nodiscard]] Eigen::Vector2d point(std::size_t index) const { - return Eigen::Vector2d{ - (static_cast(index % width()) + 0.5) * resolution(), - (static_cast(index / width()) + 0.5) * resolution()}; // NOLINT(bugprone-integer-division) - } - - [[nodiscard]] auto neighbors(std::size_t index) const { - auto result = std::vector{}; - const std::size_t row = index / width(); - const std::size_t col = index % width(); - if (row < (height() - 1)) { - result.push_back(index + width()); - } - if (row > 0) { - result.push_back(index - width()); - } - if (col < (width() - 1)) { - result.push_back(index + 1); - } - if (col > 0) { - result.push_back(index - 1); - } - return result; - } - - private: - std::array grid_; - Sophus::SE2d origin_; - Sophus::SE2d origin_inverse_; - double resolution_; - - [[nodiscard]] std::size_t width() const { return Cols; } - [[nodiscard]] std::size_t height() const { return Rows; } - [[nodiscard]] double resolution() const { return resolution_; } -}; +using beluga::testing::StaticOccupancyGrid; using UUT = ciabatta::mixin< ciabatta::curry>::mixin, @@ -112,7 +50,8 @@ TEST(LikelihoodFieldModel, LikelihoodField) { const auto params = beluga::LikelihoodFieldModelParam{2.0, 20.0, 0.5, 0.5, 0.2}; auto mixin = UUT{params, grid}; - ASSERT_THAT(mixin.likelihood_field(), testing::Pointwise(testing::DoubleNear(0.003), expected_likelihood_field)); + ASSERT_THAT( + mixin.likelihood_field().data(), testing::Pointwise(testing::DoubleNear(0.003), expected_likelihood_field)); } TEST(LikelihoodFieldModel, ImportanceWeight) { diff --git a/beluga/test/benchmark/CMakeLists.txt b/beluga/test/benchmark/CMakeLists.txt index 6f29dba91..f1de75a8f 100644 --- a/beluga/test/benchmark/CMakeLists.txt +++ b/beluga/test/benchmark/CMakeLists.txt @@ -7,6 +7,7 @@ add_executable(benchmark_beluga benchmark_sampling.cpp benchmark_spatial_hash.cpp benchmark_tuple_vector.cpp) +target_include_directories(benchmark_beluga PRIVATE ../beluga/include) target_link_libraries(benchmark_beluga PUBLIC benchmark::benchmark_main PRIVATE ${PROJECT_NAME} beluga_compile_options) diff --git a/beluga/test/benchmark/benchmark_raycasting.cpp b/beluga/test/benchmark/benchmark_raycasting.cpp index 4a8b67f75..eb7d671f4 100644 --- a/beluga/test/benchmark/benchmark_raycasting.cpp +++ b/beluga/test/benchmark/benchmark_raycasting.cpp @@ -17,6 +17,7 @@ #include #include +#include #include @@ -47,82 +48,7 @@ BENCHMARK_CAPTURE(BM_Bresenham2i, Modified, beluga::Bresenham2i::kModified) ->Range(128, 4096) ->Complexity(); -template -class StaticOccupancyGrid { - public: - struct Traits { - static bool is_free(bool value) { return !value; } - static bool is_unknown(bool) { return false; } - static bool is_occupied(bool value) { return value; } - }; - - explicit StaticOccupancyGrid( - std::array array, - double resolution = 1.0, - const Sophus::SE2d& origin = Sophus::SE2d{}) - : grid_{array}, origin_{origin}, resolution_{resolution} {} - - [[nodiscard]] std::size_t size() const { return grid_.size(); } - - [[nodiscard]] auto& data() { return grid_; } - - [[nodiscard]] const auto& data() const { return grid_; } - - [[nodiscard]] const Sophus::SE2d& origin() const { return origin_; } - - [[nodiscard]] bool valid(int xi, int yi) const { - return xi >= 0 && xi < static_cast(width()) && yi >= 0 && yi < static_cast(height()); - } - - [[nodiscard]] bool valid(const Eigen::Vector2i& cell) const { return valid(cell.x(), cell.y()); } - - [[nodiscard]] std::size_t index(double x, double y) const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return index(xi, yi); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2d& point) const { return index(point.x(), point.y()); } - - [[nodiscard]] std::size_t index(int xi, int yi) const { - if (!valid(xi, yi)) { - return size(); - } - return static_cast(xi) + static_cast(yi) * width(); - } - - [[nodiscard]] std::size_t index(const Eigen::Vector2i& cell) const { return index(cell.x(), cell.y()); } - - [[nodiscard]] Eigen::Vector2i cell(double x, double y) const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return Eigen::Vector2i{xi, yi}; - } - - [[nodiscard]] Eigen::Vector2i cell(const Eigen::Vector2d& point) const { return cell(point.x(), point.y()); } - - [[nodiscard]] Eigen::Vector2d point(int xi, int yi) const { - return Eigen::Vector2d{ - (static_cast(xi) + 0.5) * resolution(), (static_cast(yi) + 0.5) * resolution()}; - } - - [[nodiscard]] Eigen::Vector2d point(const Eigen::Vector2i& cell) const { return point(cell.x(), cell.y()); } - - [[nodiscard]] Eigen::Vector2d point(std::size_t index) const { - return Eigen::Vector2d{ - (static_cast(index % width()) + 0.5) * resolution(), - (static_cast(index / width()) + 0.5) * resolution()}; // NOLINT(bugprone-integer-division) - } - - [[nodiscard]] double resolution() const { return resolution_; } - [[nodiscard]] std::size_t width() const { return Cols; } - [[nodiscard]] std::size_t height() const { return Rows; } - - private: - std::array grid_; - Sophus::SE2d origin_; - double resolution_; -}; +using beluga::testing::StaticOccupancyGrid; void BM_RayCasting2d(benchmark::State& state) { constexpr double kMaxRange = 100.0; @@ -130,7 +56,7 @@ void BM_RayCasting2d(benchmark::State& state) { const auto n = static_cast(state.range(0)); auto grid = StaticOccupancyGrid<1280, 1280>{{}, kResolution}; - grid.data()[grid.index(n, n)] = true; + grid.data()[grid.index_at(n, n)] = true; const auto source_pose = Sophus::SE2d{0., Eigen::Vector2d{1., 1.}}; const auto beam_bearing = Sophus::SO2d{Sophus::Constants::pi() / 4.}; diff --git a/beluga_amcl/include/beluga_amcl/occupancy_grid.hpp b/beluga_amcl/include/beluga_amcl/occupancy_grid.hpp index 424ec1817..34a27fb11 100644 --- a/beluga_amcl/include/beluga_amcl/occupancy_grid.hpp +++ b/beluga_amcl/include/beluga_amcl/occupancy_grid.hpp @@ -22,6 +22,8 @@ #include #include +#include + #include #include #include @@ -29,144 +31,76 @@ namespace beluga_amcl { -class OccupancyGrid +class OccupancyGrid : public beluga::BaseOccupancyGrid2 { public: - struct Traits + struct ValueTraits { // https://wiki.ros.org/map_server#Value_Interpretation + static constexpr std::int8_t free_value = 0; + static constexpr std::int8_t unknown_value = -1; + static constexpr std::int8_t occupied_value = 100; - static bool is_free(std::int8_t value) + bool is_free(std::int8_t value) const { - return value == 0; + return value == free_value; } - static bool is_unknown(std::int8_t value) + bool is_unknown(std::int8_t value) const { - return value == -1; + return value == unknown_value; } - static bool is_occupied(std::int8_t value) + bool is_occupied(std::int8_t value) const { - return value == 100; + return value == occupied_value; } }; explicit OccupancyGrid(nav_msgs::msg::OccupancyGrid::SharedPtr grid) - : grid_{std::move(grid)}, - origin_{make_origin_transform(grid_->info.origin)} {} - - std::size_t size() const - { - return grid_->data.size(); - } - - const auto & data() const + : grid_(std::move(grid)), origin_(make_origin_transform(grid_->info.origin)) { - return grid_->data; } - const Sophus::SE2d & origin() const + [[nodiscard]] const Sophus::SE2d & origin() const { return origin_; } - bool valid(int xi, int yi) const - { - return xi >= 0 && xi < static_cast(width()) && - yi >= 0 && yi < static_cast(height()); - } - - bool valid(const Eigen::Vector2i & cell) const - { - return valid(cell.x(), cell.y()); - } - - Eigen::Vector2i cell(double x, double y) const - { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return Eigen::Vector2i{xi, yi}; - } - - Eigen::Vector2i cell(const Eigen::Vector2d & point) const - { - return cell(point.x(), point.y()); - } - - std::size_t index(int xi, int yi) const + std::size_t size() const { - if (!valid(xi, yi)) { - return size(); // If the point is outside the map, return an invalid index - } - return xi + yi * width(); + return grid_->data.size(); } - std::size_t index(const Eigen::Vector2i & cell) const {return index(cell.x(), cell.y());} - - std::size_t index(double x, double y) const + [[nodiscard]] const auto & data() const { - const auto xi = static_cast(std::floor(x / resolution() + 0.5)); - const auto yi = static_cast(std::floor(y / resolution() + 0.5)); - return index(xi, yi); + return grid_->data; } - std::size_t index(const Eigen::Vector2d & point) const {return index(point.x(), point.y());} - - Eigen::Vector2d point(int xi, int yi) const + std::size_t width() const { - return Eigen::Vector2d{ - (static_cast(xi) + 0.5) * resolution(), - (static_cast(yi) + 0.5) * resolution()}; + return grid_->info.width; } - Eigen::Vector2d point(const Eigen::Vector2i & cell) const {return point(cell.x(), cell.y());} - - Eigen::Vector2d point(std::size_t index) const + std::size_t height() const { - return point(static_cast(index % width()), static_cast(index / width())); + return grid_->info.height; } - auto neighbors(std::size_t index) const + [[nodiscard]] double resolution() const { - auto result = std::vector{}; - const std::size_t row = index / width(); - const std::size_t col = index % width(); - if (row < (height() - 1)) { - result.push_back(index + width()); - } - if (row > 0) { - result.push_back(index - width()); - } - if (col < (width() - 1)) { - result.push_back(index + 1); - } - if (col > 0) { - result.push_back(index - 1); - } - return result; + return grid_->info.resolution; } - double resolution() const + [[nodiscard]] auto value_traits() const { - return grid_->info.resolution; + return ValueTraits{}; } private: nav_msgs::msg::OccupancyGrid::SharedPtr grid_; Sophus::SE2d origin_; - std::size_t width() const - { - return grid_->info.width; - } - - std::size_t height() const - { - return grid_->info.height; - } - - static Sophus::SE2d make_origin_transform(const geometry_msgs::msg::Pose & origin) { const auto rotation = Sophus::SO2d{tf2::getYaw(origin.orientation)};