Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
costmap_2d_publisher.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * Copyright (c) 2019, Samsung Research America, Inc.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Eitan Marder-Eppstein
37  * David V. Lu!!
38  *********************************************************************/
39 #ifndef NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_HPP_
40 #define NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_HPP_
41 
42 #include <algorithm>
43 #include <string>
44 #include <memory>
45 
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"
57 
58 namespace nav2_costmap_2d
59 {
65 {
66 public:
71  const nav2_util::LifecycleNode::WeakPtr & parent,
72  Costmap2D * costmap,
73  std::string global_frame,
74  std::string topic_name,
75  bool always_send_full_costmap = false,
76  double map_vis_z = 0.0);
77 
82 
86  void on_configure() {}
87 
91  void on_activate()
92  {
93  costmap_pub_->on_activate();
94  costmap_update_pub_->on_activate();
95  costmap_raw_pub_->on_activate();
96  costmap_raw_update_pub_->on_activate();
97  }
98 
103  {
104  costmap_pub_->on_deactivate();
105  costmap_update_pub_->on_deactivate();
106  costmap_raw_pub_->on_deactivate();
107  costmap_raw_update_pub_->on_deactivate();
108  }
109 
113  void on_cleanup() {}
114 
116  void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
117  {
118  x0_ = std::min(x0, x0_);
119  xn_ = std::max(xn, xn_);
120  y0_ = std::min(y0, y0_);
121  yn_ = std::max(yn, yn_);
122  }
123 
127  void publishCostmap();
128 
133  bool active()
134  {
135  return active_;
136  }
137 
138 private:
140  void prepareGrid();
141  void prepareCostmap();
142 
144  std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> createGridUpdateMsg();
146  std::unique_ptr<nav2_msgs::msg::CostmapUpdate> createCostmapUpdateMsg();
147 
149  // void onNewSubscription(const ros::SingleSubscriberPublisher& pub);
150 
151  void updateGridParams();
152 
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);
158 
159  rclcpp::Clock::SharedPtr clock_;
160  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
161 
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_;
168  bool active_;
169  bool always_send_full_costmap_;
170  double map_vis_z_;
171 
172  // Publisher for translated costmap values as msg::OccupancyGrid used in visualization
173  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
174  rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr
175  costmap_update_pub_;
176 
177  // Publisher for raw costmap values as msg::Costmap from layered costmap
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_;
181 
182  // Service for getting the costmaps
183  rclcpp::Service<nav2_msgs::srv::GetCostmap>::SharedPtr costmap_service_;
184 
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_;
189  // Translate from 0-255 values in costmap to -1 to 100 values in message.
190  static char * cost_translation_table_;
191 };
192 
193 } // namespace nav2_costmap_2d
194 
195 #endif // NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_HPP_
A tool to periodically publish visualization data from a Costmap2D.
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.
bool active()
Check if the publisher is active.
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".
Definition: costmap_2d.hpp:68