occupancy_grid.hpp
Go to the documentation of this file.
1 // Copyright 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_SENSOR_DATA_OCCUPANCY_GRID_HPP
16 #define BELUGA_SENSOR_DATA_OCCUPANCY_GRID_HPP
17 
18 #include <cstdint>
19 #include <tuple>
20 #include <vector>
21 
23 
24 #include <range/v3/view/enumerate.hpp>
25 #include <range/v3/view/filter.hpp>
26 #include <range/v3/view/transform.hpp>
27 
28 #include <Eigen/Core>
29 
35 namespace beluga {
36 
74 
84 template <typename Derived>
85 class BaseOccupancyGrid2 : public BaseLinearGrid2<Derived> {
86  public:
88  enum class Frame : std::uint8_t { kLocal, kGlobal };
89 
91 
96  [[nodiscard]] bool free_at(std::size_t index) const {
97  const auto data = this->self().data_at(index);
98  if (!data.has_value()) {
99  return false;
100  }
101  return this->self().value_traits().is_free(data.value());
102  }
103 
105 
111  [[nodiscard]] bool free_at(int xi, int yi) const { return this->self().free_at(this->self().index_at(xi, yi)); }
112 
114 
119  [[nodiscard]] bool free_at(const Eigen::Vector2i& pi) const { return this->self().free_at(pi.x(), pi.y()); }
120 
122 
128  [[nodiscard]] bool free_near(double x, double y) const {
129  return this->self().free_at(this->self().cell_near(Eigen::Vector2d{x, y}));
130  }
131 
133 
138  [[nodiscard]] bool free_near(const Eigen::Vector2d& p) const { return this->self().free_near(p.x(), p.y()); }
139 
141 
143 
148  [[nodiscard]] auto coordinates_at(std::size_t index, Frame frame) const {
149  auto position = this->self().coordinates_at(index);
150  if (frame == Frame::kGlobal) {
151  position = this->self().origin() * position;
152  }
153  return position;
154  }
155 
157 
162  template <class Range>
163  [[nodiscard]] auto coordinates_for(Range&& cells, Frame frame) const {
164  return cells | ranges::views::transform(
165  [this, frame](const auto& cell) { return this->self().coordinates_at(cell, frame); });
166  }
167 
169  [[nodiscard]] auto free_cells() const {
170  return ranges::views::enumerate(this->self().data()) |
171  ranges::views::filter([value_traits = this->self().value_traits()](const auto& tuple) {
172  return value_traits.is_free(std::get<1>(tuple));
173  }) |
174  ranges::views::transform([](const auto& tuple) { return std::get<0>(tuple); });
175  }
176 
178  [[nodiscard]] auto obstacle_data() const {
179  return this->self().data() |
180  ranges::views::transform([value_traits = this->self().value_traits()](const auto& value) {
181  return value_traits.is_occupied(value);
182  });
183  }
184 };
185 
186 } // namespace beluga
187 
188 #endif
beluga::BaseLinearGrid2
Linear 2D grid base type.
Definition: linear_grid.hpp:64
beluga::BaseOccupancyGrid2::coordinates_at
auto coordinates_at(std::size_t index, Frame frame) const
Compute plane coordinates given grid cell coordinates.
Definition: occupancy_grid.hpp:148
beluga::BaseOccupancyGrid2::free_near
bool free_near(const Eigen::Vector2d &p) const
Checks if nearest cell is free.
Definition: occupancy_grid.hpp:138
beluga::BaseOccupancyGrid2::free_at
bool free_at(const Eigen::Vector2i &pi) const
Checks if cell is free.
Definition: occupancy_grid.hpp:119
linear_grid.hpp
Concepts and abstract implementations of linear (ie. contiguous storage) grids.
beluga::BaseOccupancyGrid2::free_near
bool free_near(double x, double y) const
Checks if nearest cell is free.
Definition: occupancy_grid.hpp:128
beluga::BaseOccupancyGrid2::free_at
bool free_at(std::size_t index) const
Checks if cell is free.
Definition: occupancy_grid.hpp:96
beluga::BaseOccupancyGrid2::Frame::kGlobal
@ kGlobal
beluga::BaseOccupancyGrid2
Occupancy 2D grid base type.
Definition: occupancy_grid.hpp:85
beluga::BaseOccupancyGrid2::obstacle_data
auto obstacle_data() const
Retrieves grid data using true booleans for obstacles.
Definition: occupancy_grid.hpp:178
beluga::BaseOccupancyGrid2::coordinates_for
auto coordinates_for(Range &&cells, Frame frame) const
Compute plane coordinates for a range of grid cells.
Definition: occupancy_grid.hpp:163
beluga::BaseOccupancyGrid2::free_cells
auto free_cells() const
Retrieves range of free grid cell indices.
Definition: occupancy_grid.hpp:169
beluga::BaseOccupancyGrid2::free_at
bool free_at(int xi, int yi) const
Checks if cell is free.
Definition: occupancy_grid.hpp:111
beluga::BaseLinearGrid2::data_at
auto data_at(std::size_t index) const
Gets cell data, if included.
Definition: linear_grid.hpp:100
beluga::BaseOccupancyGrid2::Frame::kLocal
@ kLocal
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
beluga::BaseOccupancyGrid2< StaticOccupancyGrid< Rows, Cols > >::Frame
Frame
Coordinate frames.
Definition: occupancy_grid.hpp:88


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