An interface for publishing NavGridOfDoubles/OccupancyGrid msgs and their updates periodically. More...
#include <nav_grid_publisher.h>

Public Member Functions | |
| void | setIgnoreValue (NumericType ignore_value) |
Protected Member Functions | |
| nav_msgs::OccupancyGrid | toOccupancyGrid (const ros::Time ×tamp) override |
| map_msgs::OccupancyGridUpdate | toOccupancyGridUpdate (const nav_core2::UIntBounds &bounds, const ros::Time ×tamp) override |
Protected Attributes | |
| NumericType | max_val_ |
| NumericType | min_val_ |
An interface for publishing NavGridOfDoubles/OccupancyGrid msgs and their updates periodically.
Definition at line 364 of file nav_grid_publisher.h.
| void nav_grid_pub_sub::ScaleGridPublisher< NumericType >::setIgnoreValue | ( | NumericType | ignore_value | ) | [inline] |
Definition at line 371 of file nav_grid_publisher.h.
| nav_msgs::OccupancyGrid nav_grid_pub_sub::ScaleGridPublisher< NumericType >::toOccupancyGrid | ( | const ros::Time & | timestamp | ) | [inline, override, protected, virtual] |
Definition at line 374 of file nav_grid_publisher.h.
| map_msgs::OccupancyGridUpdate nav_grid_pub_sub::ScaleGridPublisher< NumericType >::toOccupancyGridUpdate | ( | const nav_core2::UIntBounds & | bounds, |
| const ros::Time & | timestamp | ||
| ) | [inline, override, protected, virtual] |
Definition at line 380 of file nav_grid_publisher.h.
NumericType nav_grid_pub_sub::ScaleGridPublisher< NumericType >::max_val_ [protected] |
Definition at line 386 of file nav_grid_publisher.h.
NumericType nav_grid_pub_sub::ScaleGridPublisher< NumericType >::min_val_ [protected] |
Definition at line 386 of file nav_grid_publisher.h.