OccupancyGrid Class Reference

OccupancyGrid Class Reference#

Beluga ROS: beluga_ros::OccupancyGrid Class Reference
Beluga ROS
beluga_ros::OccupancyGrid Class Reference

Thin wrapper type for 2D nav_msgs/OccupancyGrid messages. More...

#include <occupancy_grid.hpp>

Inheritance diagram for beluga_ros::OccupancyGrid:
[legend]
Collaboration diagram for beluga_ros::OccupancyGrid:
[legend]

Classes

struct  ValueTraits
 Traits for occupancy grid value interpretation. More...
 

Public Member Functions

 OccupancyGrid (beluga_ros::msg::OccupancyGridConstSharedPtr grid)
 
const Sophus::SE2d & origin () const
 Get the occupancy grid origin in the occupancy grid frame.
 
std::size_t size () const
 Get the size of the occupancy grid (width() times height()).
 
const auto & data () const
 Get a reference to the underlying data storeage (ie. a row-major array).
 
std::size_t width () const
 Get the width of the occupancy grid.
 
std::size_t height () const
 Get the height of the occupancy grid.
 
double resolution () const
 Get the resolution of the occupancy grid discretization, in meters.
 
- Public Member Functions inherited from beluga::BaseOccupancyGrid2< OccupancyGrid >
bool free_at (std::size_t index) const
 
bool free_at (int xi, int yi) const
 
bool free_at (const Eigen::Vector2i &pi) const
 
bool free_near (double x, double y) const
 
bool free_near (const Eigen::Vector2d &p) const
 
auto coordinates_at (std::size_t index, Frame frame) const
 
auto coordinates_for (Range &&cells, Frame frame) const
 
auto free_cells () const
 
auto obstacle_data () const
 
- Public Member Functions inherited from beluga::BaseLinearGrid2< class >
std::size_t index_at (int xi, int yi) const
 
std::size_t index_at (const Eigen::Vector2i &pi) const
 
Eigen::Vector2d coordinates_at (std::size_t index) const
 
auto data_at (std::size_t index) const
 
auto neighborhood4 (std::size_t index) const
 
- Public Member Functions inherited from beluga::BaseDenseGrid2< class >
bool contains (int xi, int yi) const
 
bool contains (const Eigen::Vector2i &pi) const
 
auto data_at (int xi, int yi) const
 
auto data_at (const Eigen::Vector2i &pi) const
 
auto data_near (double x, double y) const
 
auto data_near (const Eigen::Vector2d &p) const
 
auto neighborhood4 (int xi, int yi) const
 
auto neighborhood4 (const Eigen::Vector2i &pi) const
 
- Public Member Functions inherited from beluga::BaseRegularGrid< class, NDim >
Eigen::Vector< int, NDim > cell_near (const Eigen::Vector< double, NDim > &p) const
 
Eigen::Vector< double, NDim > coordinates_at (const Eigen::Vector< int, NDim > &pi) const
 
auto coordinates_for (Range &&cells) const
 

Static Public Member Functions

static auto value_traits ()
 Get the traits for occupancy grid value interpretation.
 

Additional Inherited Members

- Public Types inherited from beluga::BaseOccupancyGrid2< OccupancyGrid >
enum class  Frame
 

Detailed Description

Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.

Constructor & Destructor Documentation

◆ OccupancyGrid()

beluga_ros::OccupancyGrid::OccupancyGrid ( beluga_ros::msg::OccupancyGridConstSharedPtr  grid)
inlineexplicit

Constructor.

Parameters
gridOccupancy grid message.

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