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/msg/costmap_update.hpp"
52 #include "nav2_msgs/srv/get_costmap.hpp"
53 #include "tf2/transform_datatypes.h"
54 #include "nav2_util/lifecycle_node.hpp"
55 #include "tf2/LinearMath/Quaternion.h"
56 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
71 const nav2_util::LifecycleNode::WeakPtr & parent,
73 std::string global_frame,
74 std::string topic_name,
75 bool always_send_full_costmap =
false,
76 double map_vis_z = 0.0);
93 costmap_pub_->on_activate();
94 costmap_update_pub_->on_activate();
95 costmap_raw_pub_->on_activate();
96 costmap_raw_update_pub_->on_activate();
104 costmap_pub_->on_deactivate();
105 costmap_update_pub_->on_deactivate();
106 costmap_raw_pub_->on_deactivate();
107 costmap_raw_update_pub_->on_deactivate();
116 void updateBounds(
unsigned int x0,
unsigned int xn,
unsigned int y0,
unsigned int yn)
118 x0_ = std::min(x0, x0_);
119 xn_ = std::max(xn, xn_);
120 y0_ = std::min(y0, y0_);
121 yn_ = std::max(yn, yn_);
141 void prepareCostmap();
144 std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> createGridUpdateMsg();
146 std::unique_ptr<nav2_msgs::msg::CostmapUpdate> createCostmapUpdateMsg();
151 void updateGridParams();
154 void costmap_service_callback(
155 const std::shared_ptr<rmw_request_id_t> request_header,
156 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request> request,
157 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response);
159 rclcpp::Clock::SharedPtr clock_;
160 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
162 Costmap2D * costmap_;
163 std::string global_frame_;
164 std::string topic_name_;
165 unsigned int x0_, xn_, y0_, yn_;
166 double saved_origin_x_;
167 double saved_origin_y_;
169 bool always_send_full_costmap_;
173 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
174 rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr
178 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap>::SharedPtr costmap_raw_pub_;
179 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CostmapUpdate>::SharedPtr
180 costmap_raw_update_pub_;
183 rclcpp::Service<nav2_msgs::srv::GetCostmap>::SharedPtr costmap_service_;
185 float grid_resolution_;
186 unsigned int grid_width_, grid_height_;
187 std::unique_ptr<nav_msgs::msg::OccupancyGrid> grid_;
188 std::unique_ptr<nav2_msgs::msg::Costmap> costmap_raw_;
190 static char * cost_translation_table_;
A tool to periodically publish visualization data from a Costmap2D.
void on_cleanup()
Cleanup node.
~Costmap2DPublisher()
Destructor.
void on_configure()
Configure node.
void publishCostmap()
Publishes the visualization data over ROS.
Costmap2DPublisher(const nav2_util::LifecycleNode::WeakPtr &parent, Costmap2D *costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap=false, double map_vis_z=0.0)
Constructor for the Costmap2DPublisher.
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".