Nav2 Navigation Stack - jazzy  jazzy
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  double map_vis_z)
59 : costmap_(costmap),
60  global_frame_(global_frame),
61  topic_name_(topic_name),
62  active_(false),
63  always_send_full_costmap_(always_send_full_costmap),
64  map_vis_z_(map_vis_z)
65 {
66  auto node = parent.lock();
67  clock_ = node->get_clock();
68  logger_ = node->get_logger();
69 
70  auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
71 
72  // TODO(bpwilcox): port onNewSubscription functionality for publisher
73  costmap_pub_ = node->create_publisher<nav_msgs::msg::OccupancyGrid>(
74  topic_name,
75  custom_qos);
76  costmap_raw_pub_ = node->create_publisher<nav2_msgs::msg::Costmap>(
77  topic_name + "_raw",
78  custom_qos);
79  costmap_update_pub_ = node->create_publisher<map_msgs::msg::OccupancyGridUpdate>(
80  topic_name + "_updates", custom_qos);
81  costmap_raw_update_pub_ = node->create_publisher<nav2_msgs::msg::CostmapUpdate>(
82  topic_name + "_raw_updates", custom_qos);
83 
84  // Create a service that will use the callback function to handle requests.
85  costmap_service_ = node->create_service<nav2_msgs::srv::GetCostmap>(
86  "get_" + topic_name, std::bind(
87  &Costmap2DPublisher::costmap_service_callback,
88  this, std::placeholders::_1, std::placeholders::_2,
89  std::placeholders::_3));
90 
91  if (cost_translation_table_ == NULL) {
92  cost_translation_table_ = new char[256];
93 
94  // special values:
95  cost_translation_table_[0] = 0; // NO obstacle
96  cost_translation_table_[253] = 99; // INSCRIBED obstacle
97  cost_translation_table_[254] = 100; // LETHAL obstacle
98  cost_translation_table_[255] = -1; // UNKNOWN
99 
100  // regular cost values scale the range 1 to 252 (inclusive) to fit
101  // into 1 to 98 (inclusive).
102  for (int i = 1; i < 253; i++) {
103  cost_translation_table_[i] = static_cast<char>(1 + (97 * (i - 1)) / 251);
104  }
105  }
106 
107  xn_ = yn_ = 0;
108  x0_ = costmap_->getSizeInCellsX();
109  y0_ = costmap_->getSizeInCellsY();
110 }
111 
113 
114 // TODO(bpwilcox): find equivalent/workaround to ros::SingleSubscriberPublishr
115 /*
116 void Costmap2DPublisher::onNewSubscription(const ros::SingleSubscriberPublisher& pub)
117 {
118  prepareGrid();
119  pub.publish(grid_);
120 } */
121 
122 
123 void Costmap2DPublisher::updateGridParams()
124 {
125  saved_origin_x_ = costmap_->getOriginX();
126  saved_origin_y_ = costmap_->getOriginY();
127  grid_resolution_ = costmap_->getResolution();
128  grid_width_ = costmap_->getSizeInCellsX();
129  grid_height_ = costmap_->getSizeInCellsY();
130 }
131 
132 // prepare grid_ message for publication.
133 void Costmap2DPublisher::prepareGrid()
134 {
135  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
136 
137  grid_ = std::make_unique<nav_msgs::msg::OccupancyGrid>();
138 
139  grid_->header.frame_id = global_frame_;
140  grid_->header.stamp = clock_->now();
141 
142  grid_->info.resolution = grid_resolution_;
143 
144  grid_->info.width = grid_width_;
145  grid_->info.height = grid_height_;
146 
147  double wx, wy;
148  costmap_->mapToWorld(0, 0, wx, wy);
149  grid_->info.origin.position.x = wx - grid_resolution_ / 2;
150  grid_->info.origin.position.y = wy - grid_resolution_ / 2;
151  grid_->info.origin.position.z = map_vis_z_;
152  grid_->info.origin.orientation.w = 1.0;
153 
154  grid_->data.resize(grid_->info.width * grid_->info.height);
155 
156  unsigned char * data = costmap_->getCharMap();
157  for (unsigned int i = 0; i < grid_->data.size(); i++) {
158  grid_->data[i] = cost_translation_table_[data[i]];
159  }
160 }
161 
162 void Costmap2DPublisher::prepareCostmap()
163 {
164  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
165  double resolution = costmap_->getResolution();
166 
167  costmap_raw_ = std::make_unique<nav2_msgs::msg::Costmap>();
168 
169  costmap_raw_->header.frame_id = global_frame_;
170  costmap_raw_->header.stamp = clock_->now();
171 
172  costmap_raw_->metadata.layer = "master";
173  costmap_raw_->metadata.resolution = resolution;
174 
175  costmap_raw_->metadata.size_x = costmap_->getSizeInCellsX();
176  costmap_raw_->metadata.size_y = costmap_->getSizeInCellsY();
177 
178  double wx, wy;
179  costmap_->mapToWorld(0, 0, wx, wy);
180  costmap_raw_->metadata.origin.position.x = wx - resolution / 2;
181  costmap_raw_->metadata.origin.position.y = wy - resolution / 2;
182  costmap_raw_->metadata.origin.position.z = 0.0;
183  costmap_raw_->metadata.origin.orientation.w = 1.0;
184 
185  costmap_raw_->data.resize(costmap_raw_->metadata.size_x * costmap_raw_->metadata.size_y);
186 
187  unsigned char * data = costmap_->getCharMap();
188  memcpy(costmap_raw_->data.data(), data, costmap_raw_->data.size());
189 }
190 
191 std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> Costmap2DPublisher::createGridUpdateMsg()
192 {
193  auto update = std::make_unique<map_msgs::msg::OccupancyGridUpdate>();
194 
195  update->header.stamp = clock_->now();
196  update->header.frame_id = global_frame_;
197  update->x = x0_;
198  update->y = y0_;
199  update->width = xn_ - x0_;
200  update->height = yn_ - y0_;
201  update->data.resize(update->width * update->height);
202 
203  std::uint32_t i = 0;
204  for (std::uint32_t y = y0_; y < yn_; y++) {
205  for (std::uint32_t x = x0_; x < xn_; x++) {
206  update->data[i++] = cost_translation_table_[costmap_->getCost(x, y)];
207  }
208  }
209  return update;
210 }
211 
212 std::unique_ptr<nav2_msgs::msg::CostmapUpdate> Costmap2DPublisher::createCostmapUpdateMsg()
213 {
214  auto msg = std::make_unique<nav2_msgs::msg::CostmapUpdate>();
215 
216  msg->header.stamp = clock_->now();
217  msg->header.frame_id = global_frame_;
218  msg->x = x0_;
219  msg->y = y0_;
220  msg->size_x = xn_ - x0_;
221  msg->size_y = yn_ - y0_;
222  msg->data.resize(msg->size_x * msg->size_y);
223 
224  std::uint32_t i = 0;
225  for (std::uint32_t y = y0_; y < yn_; y++) {
226  for (std::uint32_t x = x0_; x < xn_; x++) {
227  msg->data[i++] = costmap_->getCost(x, y);
228  }
229  }
230  return msg;
231 }
232 
234 {
235  float resolution = costmap_->getResolution();
236  if (always_send_full_costmap_ || grid_resolution_ != resolution ||
237  grid_width_ != costmap_->getSizeInCellsX() ||
238  grid_height_ != costmap_->getSizeInCellsY() ||
239  saved_origin_x_ != costmap_->getOriginX() ||
240  saved_origin_y_ != costmap_->getOriginY())
241  {
242  updateGridParams();
243  if (costmap_pub_->get_subscription_count() > 0) {
244  prepareGrid();
245  costmap_pub_->publish(std::move(grid_));
246  }
247  if (costmap_raw_pub_->get_subscription_count() > 0) {
248  prepareCostmap();
249  costmap_raw_pub_->publish(std::move(costmap_raw_));
250  }
251  } else if (x0_ < xn_) {
252  // Publish just update msgs
253  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
254  if (costmap_update_pub_->get_subscription_count() > 0) {
255  costmap_update_pub_->publish(createGridUpdateMsg());
256  }
257  if (costmap_raw_update_pub_->get_subscription_count() > 0) {
258  costmap_raw_update_pub_->publish(createCostmapUpdateMsg());
259  }
260  }
261 
262  xn_ = yn_ = 0;
263  x0_ = costmap_->getSizeInCellsX();
264  y0_ = costmap_->getSizeInCellsY();
265 }
266 
267 void
268 Costmap2DPublisher::costmap_service_callback(
269  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
270  const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>/*request*/,
271  const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
272 {
273  RCLCPP_DEBUG(logger_, "Received costmap service request");
274 
275  // TODO(bpwilcox): Grab correct orientation information
276  tf2::Quaternion quaternion;
277  quaternion.setRPY(0.0, 0.0, 0.0);
278 
279  auto size_x = costmap_->getSizeInCellsX();
280  auto size_y = costmap_->getSizeInCellsY();
281  auto data_length = size_x * size_y;
282  unsigned char * data = costmap_->getCharMap();
283  auto current_time = clock_->now();
284 
285  response->map.header.stamp = current_time;
286  response->map.header.frame_id = global_frame_;
287  response->map.metadata.size_x = size_x;
288  response->map.metadata.size_y = size_y;
289  response->map.metadata.resolution = costmap_->getResolution();
290  response->map.metadata.layer = "master";
291  response->map.metadata.map_load_time = current_time;
292  response->map.metadata.update_time = current_time;
293  response->map.metadata.origin.position.x = costmap_->getOriginX();
294  response->map.metadata.origin.position.y = costmap_->getOriginY();
295  response->map.metadata.origin.position.z = 0.0;
296  response->map.metadata.origin.orientation = tf2::toMsg(quaternion);
297  response->map.data.resize(data_length);
298  response->map.data.assign(data, data + data_length);
299 }
300 
301 } // end namespace nav2_costmap_2d
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.
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:279
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:544
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:514
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:539
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:519
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:534