Nav2 Navigation Stack - humble  humble
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/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"
56 
57 namespace nav2_costmap_2d
58 {
64 {
65 public:
70  const nav2_util::LifecycleNode::WeakPtr & parent,
71  Costmap2D * costmap,
72  std::string global_frame,
73  std::string topic_name,
74  bool always_send_full_costmap = false);
75 
80 
84  void on_configure() {}
85 
89  void on_activate()
90  {
91  costmap_pub_->on_activate();
92  costmap_update_pub_->on_activate();
93  costmap_raw_pub_->on_activate();
94  }
95 
100  {
101  costmap_pub_->on_deactivate();
102  costmap_update_pub_->on_deactivate();
103  costmap_raw_pub_->on_deactivate();
104  }
105 
109  void on_cleanup() {}
110 
112  void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
113  {
114  x0_ = std::min(x0, x0_);
115  xn_ = std::max(xn, xn_);
116  y0_ = std::min(y0, y0_);
117  yn_ = std::max(yn, yn_);
118  }
119 
123  void publishCostmap();
124 
129  bool active()
130  {
131  return active_;
132  }
133 
134 private:
136  void prepareGrid();
137  void prepareCostmap();
138 
140  // void onNewSubscription(const ros::SingleSubscriberPublisher& pub);
141 
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);
147 
148  rclcpp::Clock::SharedPtr clock_;
149  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
150 
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_;
157  bool active_;
158  bool always_send_full_costmap_;
159 
160  // Publisher for translated costmap values as msg::OccupancyGrid used in visualization
161  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr costmap_pub_;
162  rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr
163  costmap_update_pub_;
164 
165  // Publisher for raw costmap values as msg::Costmap from layered costmap
166  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap>::SharedPtr costmap_raw_pub_;
167 
168  // Service for getting the costmaps
169  rclcpp::Service<nav2_msgs::srv::GetCostmap>::SharedPtr costmap_service_;
170 
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_;
175  // Translate from 0-255 values in costmap to -1 to 100 values in message.
176  static char * cost_translation_table_;
177 };
178 
179 } // namespace nav2_costmap_2d
180 
181 #endif // NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_HPP_
A tool to periodically publish visualization data from a Costmap2D.
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 publishCostmap()
Publishes the visualization data over ROS.
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