Classes | Public Member Functions | Static Public Member Functions | Static Private Member Functions | Private Attributes | List of all members
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:
Inheritance graph
[legend]

Classes

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

Public Member Functions

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

Static Private Member Functions

static Sophus::SE2d make_origin_transform (const beluga_ros::msg::Pose &origin)
 

Private Attributes

beluga_ros::msg::OccupancyGridConstSharedPtr grid_
 
Sophus::SE2d origin_
 

Additional Inherited Members

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

Detailed Description

Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.

Definition at line 47 of file occupancy_grid.hpp.

Constructor & Destructor Documentation

◆ OccupancyGrid()

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

Constructor.

Parameters
gridOccupancy grid message.

Definition at line 74 of file occupancy_grid.hpp.

Member Function Documentation

◆ data()

const auto& beluga_ros::OccupancyGrid::data ( ) const
inline

Get a reference to the underlying data storeage (ie. a row-major array).

Definition at line 84 of file occupancy_grid.hpp.

◆ height()

std::size_t beluga_ros::OccupancyGrid::height ( ) const
inline

Get the height of the occupancy grid.

Definition at line 90 of file occupancy_grid.hpp.

◆ make_origin_transform()

static Sophus::SE2d beluga_ros::OccupancyGrid::make_origin_transform ( const beluga_ros::msg::Pose &  origin)
inlinestaticprivate

Definition at line 102 of file occupancy_grid.hpp.

◆ origin()

const Sophus::SE2d& beluga_ros::OccupancyGrid::origin ( ) const
inline

Get the occupancy grid origin in the occupancy grid frame.

Definition at line 78 of file occupancy_grid.hpp.

◆ resolution()

double beluga_ros::OccupancyGrid::resolution ( ) const
inline

Get the resolution of the occupancy grid discretization, in meters.

Definition at line 93 of file occupancy_grid.hpp.

◆ size()

std::size_t beluga_ros::OccupancyGrid::size ( ) const
inline

Get the size of the occupancy grid (width() times height()).

Definition at line 81 of file occupancy_grid.hpp.

◆ value_traits()

static auto beluga_ros::OccupancyGrid::value_traits ( )
inlinestatic

Get the traits for occupancy grid value interpretation.

Definition at line 96 of file occupancy_grid.hpp.

◆ width()

std::size_t beluga_ros::OccupancyGrid::width ( ) const
inline

Get the width of the occupancy grid.

Definition at line 87 of file occupancy_grid.hpp.

Member Data Documentation

◆ grid_

beluga_ros::msg::OccupancyGridConstSharedPtr beluga_ros::OccupancyGrid::grid_
private

Definition at line 99 of file occupancy_grid.hpp.

◆ origin_

Sophus::SE2d beluga_ros::OccupancyGrid::origin_
private

Definition at line 100 of file occupancy_grid.hpp.


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


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