Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
More...
#include <occupancy_grid.hpp>

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::SE2d & | origin () 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 |
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
Definition at line 47 of file occupancy_grid.hpp.
|
inlineexplicit |
Constructor.
| grid | Occupancy grid message. |
Definition at line 74 of file occupancy_grid.hpp.
|
inline |
Get a reference to the underlying data storeage (ie. a row-major array).
Definition at line 84 of file occupancy_grid.hpp.
|
inline |
Get the height of the occupancy grid.
Definition at line 90 of file occupancy_grid.hpp.
|
inlinestaticprivate |
Definition at line 102 of file occupancy_grid.hpp.
|
inline |
Get the occupancy grid origin in the occupancy grid frame.
Definition at line 78 of file occupancy_grid.hpp.
|
inline |
Get the resolution of the occupancy grid discretization, in meters.
Definition at line 93 of file occupancy_grid.hpp.
|
inline |
Get the size of the occupancy grid (width() times height()).
Definition at line 81 of file occupancy_grid.hpp.
|
inlinestatic |
Get the traits for occupancy grid value interpretation.
Definition at line 96 of file occupancy_grid.hpp.
|
inline |
Get the width of the occupancy grid.
Definition at line 87 of file occupancy_grid.hpp.
|
private |
Definition at line 99 of file occupancy_grid.hpp.
|
private |
Definition at line 100 of file occupancy_grid.hpp.