39 #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_HPP_
40 #define NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_HPP_
46 #include "rclcpp_lifecycle/lifecycle_node.hpp"
47 #include "nav2_costmap_2d/costmap_2d.hpp"
48 #include "nav_msgs/msg/occupancy_grid.hpp"
49 #include "map_msgs/msg/occupancy_grid_update.hpp"
50 #include "nav2_msgs/msg/costmap.hpp"
51 #include "nav2_msgs/srv/get_costmap.hpp"
52 #include "tf2/transform_datatypes.h"
53 #include "nav2_util/lifecycle_node.hpp"
54 #include "tf2/LinearMath/Quaternion.h"
55 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
70 const nav2_util::LifecycleNode::WeakPtr & parent,
72 std::string global_frame,
73 std::string topic_name,
74 bool always_send_full_costmap =
false);
91 costmap_pub_->on_activate();
92 costmap_update_pub_->on_activate();
93 costmap_raw_pub_->on_activate();
101 costmap_pub_->on_deactivate();
102 costmap_update_pub_->on_deactivate();
103 costmap_raw_pub_->on_deactivate();
112 void updateBounds(
unsigned int x0,
unsigned int xn,
unsigned int y0,
unsigned int yn)
114 x0_ = std::min(x0, x0_);
115 xn_ = std::max(xn, xn_);
116 y0_ = std::min(y0, y0_);
117 yn_ = std::max(yn, yn_);
137 void prepareCostmap();
143 void costmap_service_callback(
144 const std::shared_ptr<rmw_request_id_t> request_header,
145 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request> request,
146 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response);
148 rclcpp::Clock::SharedPtr clock_;
149 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
151 Costmap2D * costmap_;
152 std::string global_frame_;
153 std::string topic_name_;
154 unsigned int x0_, xn_, y0_, yn_;
155 double saved_origin_x_;
156 double saved_origin_y_;
158 bool always_send_full_costmap_;
161 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
162 rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr
166 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap>::SharedPtr costmap_raw_pub_;
169 rclcpp::Service<nav2_msgs::srv::GetCostmap>::SharedPtr costmap_service_;
171 float grid_resolution;
172 unsigned int grid_width, grid_height;
173 std::unique_ptr<nav_msgs::msg::OccupancyGrid> grid_;
174 std::unique_ptr<nav2_msgs::msg::Costmap> costmap_raw_;
176 static char * cost_translation_table_;
A tool to periodically publish visualization data from a Costmap2D.
void on_cleanup()
Cleanup node.
~Costmap2DPublisher()
Destructor.
Costmap2DPublisher(const nav2_util::LifecycleNode::WeakPtr &parent, Costmap2D *costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap=false)
Constructor for the Costmap2DPublisher.
void on_configure()
Configure node.
void publishCostmap()
Publishes the visualization data over ROS.
void on_deactivate()
deactivate node
bool active()
Check if the publisher is active.
void on_activate()
Activate node.
void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
Include the given bounds in the changed-rectangle.
A 2D costmap provides a mapping between points in the world and their associated "costs".