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) |
Public Member Functions inherited from nav_grid_pub_sub::GenericGridPublisher< NumericType, nav_2d_msgs::NavGridOfDoubles, nav_2d_msgs::NavGridOfDoublesUpdate > | |
| GenericGridPublisher (nav_grid::NavGrid< NumericType > &data) | |
| void | init (ros::NodeHandle &nh, const std::string &nav_grid_topic="grid", const std::string &occupancy_grid_topic="costmap", const std::string &update_area_topic="update_area", bool publish_updates=true, ros::Duration full_publish_cycle=ros::Duration(0), ros::Duration update_publish_cycle=ros::Duration(0)) |
| Initialize method for determining what gets published when. More... | |
| void | publish () |
| Publish the full grid if the full_publish_cycle allows. More... | |
| void | publish (const nav_core2::UIntBounds &bounds) |
| Publish the full grid or updates, as dictated by parameters passed to init. More... | |
Protected Attributes | |
| NumericType | ignore_value_ { std::numeric_limits<NumericType>::max() } |
| NumericType | max_val_ |
| NumericType | min_val_ |
Protected Attributes inherited from nav_grid_pub_sub::GenericGridPublisher< NumericType, nav_2d_msgs::NavGridOfDoubles, nav_2d_msgs::NavGridOfDoublesUpdate > | |
| nav_grid::NavGrid< NumericType > & | data_ |
| ros::Duration | full_publish_cycle_ |
| ros::Time | last_full_publish_ |
| ros::Time | last_update_publish_ |
| ros::Publisher | nav_pub_ |
| ros::Publisher | nav_update_pub_ |
| ros::Publisher | occ_pub_ |
| ros::Publisher | occ_update_pub_ |
| bool | publish_updates_ |
| nav_grid::NavGridInfo | saved_info_ |
| ros::Time | synced_time_stamp_ |
| ros::Publisher | update_area_pub_ |
| nav_core2::UIntBounds | update_bounds_ |
| ros::Duration | update_publish_cycle_ |
An interface for publishing NavGridOfDoubles/OccupancyGrid msgs and their updates periodically.
Definition at line 364 of file nav_grid_publisher.h.
|
inline |
Definition at line 371 of file nav_grid_publisher.h.
|
inlineoverrideprotectedvirtual |
Definition at line 374 of file nav_grid_publisher.h.
|
inlineoverrideprotectedvirtual |
Definition at line 380 of file nav_grid_publisher.h.
|
protected |
Definition at line 386 of file nav_grid_publisher.h.
|
protected |
Definition at line 387 of file nav_grid_publisher.h.
|
protected |
Definition at line 387 of file nav_grid_publisher.h.