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.hpp"
54 #include "nav2_util/lifecycle_node.hpp"
55 #include "tf2/LinearMath/Quaternion.hpp"
56 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
57 #include "nav2_util/service_server.hpp"
72 const nav2_util::LifecycleNode::WeakPtr & parent,
74 std::string global_frame,
75 std::string topic_name,
76 bool always_send_full_costmap =
false,
77 double map_vis_z = 0.0);
94 costmap_pub_->on_activate();
95 costmap_update_pub_->on_activate();
96 costmap_raw_pub_->on_activate();
97 costmap_raw_update_pub_->on_activate();
105 costmap_pub_->on_deactivate();
106 costmap_update_pub_->on_deactivate();
107 costmap_raw_pub_->on_deactivate();
108 costmap_raw_update_pub_->on_deactivate();
117 void updateBounds(
unsigned int x0,
unsigned int xn,
unsigned int y0,
unsigned int yn)
119 x0_ = std::min(x0, x0_);
120 xn_ = std::max(xn, xn_);
121 y0_ = std::min(y0, y0_);
122 yn_ = std::max(yn, yn_);
142 void prepareCostmap();
145 std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> createGridUpdateMsg();
147 std::unique_ptr<nav2_msgs::msg::CostmapUpdate> createCostmapUpdateMsg();
152 void updateGridParams();
155 void costmap_service_callback(
156 const std::shared_ptr<rmw_request_id_t> request_header,
157 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request> request,
158 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response);
160 rclcpp::Clock::SharedPtr clock_;
161 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
163 Costmap2D * costmap_;
164 std::string global_frame_;
165 std::string topic_name_;
166 unsigned int x0_, xn_, y0_, yn_;
167 double saved_origin_x_;
168 double saved_origin_y_;
170 bool always_send_full_costmap_;
174 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
175 rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr
179 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap>::SharedPtr costmap_raw_pub_;
180 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CostmapUpdate>::SharedPtr
181 costmap_raw_update_pub_;
185 std::shared_ptr<rclcpp_lifecycle::LifecycleNode>>::SharedPtr
188 float grid_resolution_;
189 unsigned int grid_width_, grid_height_;
190 std::unique_ptr<nav_msgs::msg::OccupancyGrid> grid_;
191 std::unique_ptr<nav2_msgs::msg::Costmap> costmap_raw_;
193 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".
A simple wrapper on ROS2 services server.