Go to the documentation of this file.
15 #ifndef BELUGA_ROS_OCCUPANCY_GRID_HPP
16 #define BELUGA_ROS_OCCUPANCY_GRID_HPP
28 #if BELUGA_ROS_VERSION == 2
29 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
30 #elif BELUGA_ROS_VERSION == 1
33 #error BELUGA_ROS_VERSION is not defined or invalid
74 explicit OccupancyGrid(beluga_ros::msg::OccupancyGridConstSharedPtr grid)
81 [[nodiscard]] std::size_t
size()
const {
return grid_->data.size(); }
84 [[nodiscard]]
const auto&
data()
const {
return grid_->data; }
87 [[nodiscard]] std::size_t
width()
const {
return grid_->info.width; }
90 [[nodiscard]] std::size_t
height()
const {
return grid_->info.height; }
99 beluga_ros::msg::OccupancyGridConstSharedPtr
grid_;
104 const auto translation = Eigen::Vector2d{
origin.position.x,
origin.position.y};
111 #endif // BELUGA_ROS_OCCUPANCY_GRID_HPP
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
double getYaw(const A &a)
double resolution() const
Get the resolution of the occupancy grid discretization, in meters.
std::size_t width() const
Get the width of the occupancy grid.
const Sophus::SE2d & origin() const
Get the occupancy grid origin in the occupancy grid frame.
static bool is_unknown(std::int8_t value)
Check if the given value corresponds to that of a cell of unknown occupancy.
static constexpr std::int8_t kFreeValue
Free value in the standard ROS trinary interpretation.
static Sophus::SE2d make_origin_transform(const beluga_ros::msg::Pose &origin)
Traits for occupancy grid value interpretation.
static auto value_traits()
Get the traits for occupancy grid value interpretation.
std::size_t size() const
Get the size of the occupancy grid (width() times height()).
static constexpr std::int8_t kUnknownValue
Unknown value in the standard ROS trinary interpretation.
const auto & data() const
Get a reference to the underlying data storeage (ie. a row-major array).
static bool is_occupied(std::int8_t value)
Check if the given value corresponds to that of an occupied cell.
std::size_t height() const
Get the height of the occupancy grid.
beluga_ros::msg::OccupancyGridConstSharedPtr grid_
OccupancyGrid(beluga_ros::msg::OccupancyGridConstSharedPtr grid)
static constexpr std::int8_t kOccupiedValue
Occupied value in the standard ROS trinary interpretation.
static bool is_free(std::int8_t value)
Check if the given value corresponds to that of a free cell.
The main Beluga ROS namespace.
beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02