Go to the documentation of this file.
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>
51 class Costmap2DPublisher
58 std::string topic_name,
bool always_send_full_costmap =
false);
66 void updateBounds(
unsigned int x0,
unsigned int xn,
unsigned int y0,
unsigned int yn)
104 nav_msgs::OccupancyGrid
grid_;
108 #endif // COSTMAP_2D_COSTMAP_2D_PUBLISHER_H
std::string global_frame_
ros::Publisher costmap_update_pub_
A 2D costmap provides a mapping between points in the world and their associated "costs".
void publishCostmap()
Publishes the visualization data over ROS.
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.
bool always_send_full_costmap_
static char * cost_translation_table_
Translate from 0-255 values in costmap to -1 to 100 values in message.
void prepareGrid()
Prepare grid_ message for publication.
void onNewSubscription(const ros::SingleSubscriberPublisher &pub)
Publish the latest full costmap to the new subscriber.
ros::Publisher costmap_pub_
void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
Include the given bounds in the changed-rectangle.
bool active()
Check if the publisher is active.
nav_msgs::OccupancyGrid grid_
~Costmap2DPublisher()
Destructor.
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17