38 #ifndef COSTMAP_2D_COSTMAP_2D_PUBLISHER_H_ 39 #define COSTMAP_2D_COSTMAP_2D_PUBLISHER_H_ 42 #include <nav_msgs/OccupancyGrid.h> 43 #include <map_msgs/OccupancyGridUpdate.h> 59 std::string topic_name,
bool always_send_full_costmap =
false);
67 void updateBounds(
unsigned int x0,
unsigned int xn,
unsigned int y0,
unsigned int yn)
109 #endif // COSTMAP_2D_COSTMAP_2D_PUBLISHER_H
ros::Publisher costmap_pub_
bool always_send_full_costmap_
bool active()
Check if the publisher is active.
~Costmap2DPublisher()
Destructor.
void onNewSubscription(const ros::SingleSubscriberPublisher &pub)
Publish the latest full costmap to the new subscriber.
void prepareGrid()
Prepare grid_ message for publication.
static char * cost_translation_table_
Translate from 0-255 values in costmap to -1 to 100 values in message.
A tool to periodically publish visualization data from a Costmap2D.
std::string global_frame_
void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
Include the given bounds in the changed-rectangle.
ros::Publisher costmap_update_pub_
nav_msgs::OccupancyGrid grid_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Costmap2DPublisher(ros::NodeHandle *ros_node, Costmap2D *costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap=false)
Constructor for the Costmap2DPublisher.
void publishCostmap()
Publishes the visualization data over ROS.