Static Public Member Functions | Static Public Attributes | List of all members
beluga_ros::OccupancyGrid::ValueTraits Struct Reference

Traits for occupancy grid value interpretation. More...

#include <occupancy_grid.hpp>

Static Public Member Functions

static bool is_free (std::int8_t value)
 Check if the given value corresponds to that of a free cell. More...
 
static bool is_occupied (std::int8_t value)
 Check if the given value corresponds to that of an occupied cell. More...
 
static bool is_unknown (std::int8_t value)
 Check if the given value corresponds to that of a cell of unknown occupancy. More...
 

Static Public Attributes

static constexpr std::int8_t kFreeValue = 0
 Free value in the standard ROS trinary interpretation. More...
 
static constexpr std::int8_t kOccupiedValue = 100
 Occupied value in the standard ROS trinary interpretation. More...
 
static constexpr std::int8_t kUnknownValue = -1
 Unknown value in the standard ROS trinary interpretation. More...
 

Detailed Description

Traits for occupancy grid value interpretation.

Assumes a standard ROS trinary interpretation.

Definition at line 53 of file occupancy_grid.hpp.

Member Function Documentation

◆ is_free()

static bool beluga_ros::OccupancyGrid::ValueTraits::is_free ( std::int8_t  value)
inlinestatic

Check if the given value corresponds to that of a free cell.

Definition at line 62 of file occupancy_grid.hpp.

◆ is_occupied()

static bool beluga_ros::OccupancyGrid::ValueTraits::is_occupied ( std::int8_t  value)
inlinestatic

Check if the given value corresponds to that of an occupied cell.

Definition at line 68 of file occupancy_grid.hpp.

◆ is_unknown()

static bool beluga_ros::OccupancyGrid::ValueTraits::is_unknown ( std::int8_t  value)
inlinestatic

Check if the given value corresponds to that of a cell of unknown occupancy.

Definition at line 65 of file occupancy_grid.hpp.

Member Data Documentation

◆ kFreeValue

constexpr std::int8_t beluga_ros::OccupancyGrid::ValueTraits::kFreeValue = 0
staticconstexpr

Free value in the standard ROS trinary interpretation.

Definition at line 55 of file occupancy_grid.hpp.

◆ kOccupiedValue

constexpr std::int8_t beluga_ros::OccupancyGrid::ValueTraits::kOccupiedValue = 100
staticconstexpr

Occupied value in the standard ROS trinary interpretation.

Definition at line 59 of file occupancy_grid.hpp.

◆ kUnknownValue

constexpr std::int8_t beluga_ros::OccupancyGrid::ValueTraits::kUnknownValue = -1
staticconstexpr

Unknown value in the standard ROS trinary interpretation.

Definition at line 57 of file occupancy_grid.hpp.


The documentation for this struct was generated from the following file:


beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02