Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap_2d_publisher.cpp
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 #include "nav2_costmap_2d/costmap_2d_publisher.hpp"
40 
41 #include <string>
42 #include <memory>
43 #include <utility>
44 
45 #include "nav2_costmap_2d/cost_values.hpp"
46 
47 namespace nav2_costmap_2d
48 {
49 
50 char * Costmap2DPublisher::cost_translation_table_ = NULL;
51 
53  const nav2_util::LifecycleNode::WeakPtr & parent,
54  Costmap2D * costmap,
55  std::string global_frame,
56  std::string topic_name,
57  bool always_send_full_costmap)
58 : costmap_(costmap),
59  global_frame_(global_frame),
60  topic_name_(topic_name),
61  active_(false),
62  always_send_full_costmap_(always_send_full_costmap)
63 {
64  auto node = parent.lock();
65  clock_ = node->get_clock();
66  logger_ = node->get_logger();
67 
68  auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
69 
70  // TODO(bpwilcox): port onNewSubscription functionality for publisher
71  costmap_pub_ = node->create_publisher<nav_msgs::msg::OccupancyGrid>(
72  topic_name,
73  custom_qos);
74  costmap_raw_pub_ = node->create_publisher<nav2_msgs::msg::Costmap>(
75  topic_name + "_raw",
76  custom_qos);
77  costmap_update_pub_ = node->create_publisher<map_msgs::msg::OccupancyGridUpdate>(
78  topic_name + "_updates", custom_qos);
79 
80  // Create a service that will use the callback function to handle requests.
81  costmap_service_ = node->create_service<nav2_msgs::srv::GetCostmap>(
82  "get_costmap", std::bind(
83  &Costmap2DPublisher::costmap_service_callback,
84  this, std::placeholders::_1, std::placeholders::_2,
85  std::placeholders::_3));
86 
87  if (cost_translation_table_ == NULL) {
88  cost_translation_table_ = new char[256];
89 
90  // special values:
91  cost_translation_table_[0] = 0; // NO obstacle
92  cost_translation_table_[253] = 99; // INSCRIBED obstacle
93  cost_translation_table_[254] = 100; // LETHAL obstacle
94  cost_translation_table_[255] = -1; // UNKNOWN
95 
96  // regular cost values scale the range 1 to 252 (inclusive) to fit
97  // into 1 to 98 (inclusive).
98  for (int i = 1; i < 253; i++) {
99  cost_translation_table_[i] = static_cast<char>(1 + (97 * (i - 1)) / 251);
100  }
101  }
102 
103  xn_ = yn_ = 0;
104  x0_ = costmap_->getSizeInCellsX();
105  y0_ = costmap_->getSizeInCellsY();
106 }
107 
109 
110 // TODO(bpwilcox): find equivalent/workaround to ros::SingleSubscriberPublishr
111 /*
112 void Costmap2DPublisher::onNewSubscription(const ros::SingleSubscriberPublisher& pub)
113 {
114  prepareGrid();
115  pub.publish(grid_);
116 } */
117 
118 // prepare grid_ message for publication.
119 void Costmap2DPublisher::prepareGrid()
120 {
121  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
122  grid_resolution = costmap_->getResolution();
123  grid_width = costmap_->getSizeInCellsX();
124  grid_height = costmap_->getSizeInCellsY();
125 
126  grid_ = std::make_unique<nav_msgs::msg::OccupancyGrid>();
127 
128  grid_->header.frame_id = global_frame_;
129  grid_->header.stamp = clock_->now();
130 
131  grid_->info.resolution = grid_resolution;
132 
133  grid_->info.width = grid_width;
134  grid_->info.height = grid_height;
135 
136  double wx, wy;
137  costmap_->mapToWorld(0, 0, wx, wy);
138  grid_->info.origin.position.x = wx - grid_resolution / 2;
139  grid_->info.origin.position.y = wy - grid_resolution / 2;
140  grid_->info.origin.position.z = 0.0;
141  grid_->info.origin.orientation.w = 1.0;
142  saved_origin_x_ = costmap_->getOriginX();
143  saved_origin_y_ = costmap_->getOriginY();
144 
145  grid_->data.resize(grid_->info.width * grid_->info.height);
146 
147  unsigned char * data = costmap_->getCharMap();
148  for (unsigned int i = 0; i < grid_->data.size(); i++) {
149  grid_->data[i] = cost_translation_table_[data[i]];
150  }
151 }
152 
153 void Costmap2DPublisher::prepareCostmap()
154 {
155  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
156  double resolution = costmap_->getResolution();
157 
158  costmap_raw_ = std::make_unique<nav2_msgs::msg::Costmap>();
159 
160  costmap_raw_->header.frame_id = global_frame_;
161  costmap_raw_->header.stamp = clock_->now();
162 
163  costmap_raw_->metadata.layer = "master";
164  costmap_raw_->metadata.resolution = resolution;
165 
166  costmap_raw_->metadata.size_x = costmap_->getSizeInCellsX();
167  costmap_raw_->metadata.size_y = costmap_->getSizeInCellsY();
168 
169  double wx, wy;
170  costmap_->mapToWorld(0, 0, wx, wy);
171  costmap_raw_->metadata.origin.position.x = wx - resolution / 2;
172  costmap_raw_->metadata.origin.position.y = wy - resolution / 2;
173  costmap_raw_->metadata.origin.position.z = 0.0;
174  costmap_raw_->metadata.origin.orientation.w = 1.0;
175 
176  costmap_raw_->data.resize(costmap_raw_->metadata.size_x * costmap_raw_->metadata.size_y);
177 
178  unsigned char * data = costmap_->getCharMap();
179  for (unsigned int i = 0; i < costmap_raw_->data.size(); i++) {
180  costmap_raw_->data[i] = data[i];
181  }
182 }
183 
185 {
186  if (costmap_raw_pub_->get_subscription_count() > 0) {
187  prepareCostmap();
188  costmap_raw_pub_->publish(std::move(costmap_raw_));
189  }
190  float resolution = costmap_->getResolution();
191 
192  if (always_send_full_costmap_ || grid_resolution != resolution ||
193  grid_width != costmap_->getSizeInCellsX() ||
194  grid_height != costmap_->getSizeInCellsY() ||
195  saved_origin_x_ != costmap_->getOriginX() ||
196  saved_origin_y_ != costmap_->getOriginY())
197  {
198  if (costmap_pub_->get_subscription_count() > 0) {
199  prepareGrid();
200  costmap_pub_->publish(std::move(grid_));
201  }
202  } else if (x0_ < xn_) {
203  if (costmap_update_pub_->get_subscription_count() > 0) {
204  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
205  // Publish Just an Update
206  auto update = std::make_unique<map_msgs::msg::OccupancyGridUpdate>();
207  update->header.stamp = rclcpp::Time();
208  update->header.frame_id = global_frame_;
209  update->x = x0_;
210  update->y = y0_;
211  update->width = xn_ - x0_;
212  update->height = yn_ - y0_;
213  update->data.resize(update->width * update->height);
214  unsigned int i = 0;
215  for (unsigned int y = y0_; y < yn_; y++) {
216  for (unsigned int x = x0_; x < xn_; x++) {
217  unsigned char cost = costmap_->getCost(x, y);
218  update->data[i++] = cost_translation_table_[cost];
219  }
220  }
221  costmap_update_pub_->publish(std::move(update));
222  }
223  }
224 
225  xn_ = yn_ = 0;
226  x0_ = costmap_->getSizeInCellsX();
227  y0_ = costmap_->getSizeInCellsY();
228 }
229 
230 void
231 Costmap2DPublisher::costmap_service_callback(
232  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
233  const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>/*request*/,
234  const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
235 {
236  RCLCPP_DEBUG(logger_, "Received costmap service request");
237 
238  // TODO(bpwilcox): Grab correct orientation information
239  tf2::Quaternion quaternion;
240  quaternion.setRPY(0.0, 0.0, 0.0);
241 
242  auto size_x = costmap_->getSizeInCellsX();
243  auto size_y = costmap_->getSizeInCellsY();
244  auto data_length = size_x * size_y;
245  unsigned char * data = costmap_->getCharMap();
246  auto current_time = clock_->now();
247 
248  response->map.header.stamp = current_time;
249  response->map.header.frame_id = global_frame_;
250  response->map.metadata.size_x = size_x;
251  response->map.metadata.size_y = size_y;
252  response->map.metadata.resolution = costmap_->getResolution();
253  response->map.metadata.layer = "master";
254  response->map.metadata.map_load_time = current_time;
255  response->map.metadata.update_time = current_time;
256  response->map.metadata.origin.position.x = costmap_->getOriginX();
257  response->map.metadata.origin.position.y = costmap_->getOriginY();
258  response->map.metadata.origin.position.z = 0.0;
259  response->map.metadata.origin.orientation = tf2::toMsg(quaternion);
260  response->map.data.resize(data_length);
261  response->map.data.assign(data, data + data_length);
262 }
263 
264 } // end namespace nav2_costmap_2d
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.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:281
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:266
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:261
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:531
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:526
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:521