Nav2 Navigation Stack - kilted  kilted
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_ = std::make_shared<nav2_util::ServiceServer<nav2_msgs::srv::GetCostmap,
86  std::shared_ptr<rclcpp_lifecycle::LifecycleNode>>>(
87  std::string("get_") + topic_name,
88  node,
89  std::bind(
90  &Costmap2DPublisher::costmap_service_callback, this,
91  std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
92 
93  if (cost_translation_table_ == NULL) {
94  cost_translation_table_ = new char[256];
95 
96  // special values:
97  cost_translation_table_[0] = 0; // NO obstacle
98  cost_translation_table_[253] = 99; // INSCRIBED obstacle
99  cost_translation_table_[254] = 100; // LETHAL obstacle
100  cost_translation_table_[255] = -1; // UNKNOWN
101 
102  // regular cost values scale the range 1 to 252 (inclusive) to fit
103  // into 1 to 98 (inclusive).
104  for (int i = 1; i < 253; i++) {
105  cost_translation_table_[i] = static_cast<char>(1 + (97 * (i - 1)) / 251);
106  }
107  }
108 
109  xn_ = yn_ = 0;
110  x0_ = costmap_->getSizeInCellsX();
111  y0_ = costmap_->getSizeInCellsY();
112 }
113 
115 
116 // TODO(bpwilcox): find equivalent/workaround to ros::SingleSubscriberPublisher
117 /*
118 void Costmap2DPublisher::onNewSubscription(const ros::SingleSubscriberPublisher& pub)
119 {
120  prepareGrid();
121  pub.publish(grid_);
122 } */
123 
124 
125 void Costmap2DPublisher::updateGridParams()
126 {
127  saved_origin_x_ = costmap_->getOriginX();
128  saved_origin_y_ = costmap_->getOriginY();
129  grid_resolution_ = costmap_->getResolution();
130  grid_width_ = costmap_->getSizeInCellsX();
131  grid_height_ = costmap_->getSizeInCellsY();
132 }
133 
134 // prepare grid_ message for publication.
135 void Costmap2DPublisher::prepareGrid()
136 {
137  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
138 
139  grid_ = std::make_unique<nav_msgs::msg::OccupancyGrid>();
140 
141  grid_->header.frame_id = global_frame_;
142  grid_->header.stamp = clock_->now();
143 
144  grid_->info.resolution = grid_resolution_;
145 
146  grid_->info.width = grid_width_;
147  grid_->info.height = grid_height_;
148 
149  double wx, wy;
150  costmap_->mapToWorld(0, 0, wx, wy);
151  grid_->info.origin.position.x = wx - grid_resolution_ / 2;
152  grid_->info.origin.position.y = wy - grid_resolution_ / 2;
153  grid_->info.origin.position.z = map_vis_z_;
154  grid_->info.origin.orientation.w = 1.0;
155 
156  grid_->data.resize(grid_->info.width * grid_->info.height);
157 
158  unsigned char * data = costmap_->getCharMap();
159  std::transform(data, data + grid_->data.size(), grid_->data.begin(),
160  [](unsigned char c) {return cost_translation_table_[c];});
161 }
162 
163 void Costmap2DPublisher::prepareCostmap()
164 {
165  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
166  double resolution = costmap_->getResolution();
167 
168  costmap_raw_ = std::make_unique<nav2_msgs::msg::Costmap>();
169 
170  costmap_raw_->header.frame_id = global_frame_;
171  costmap_raw_->header.stamp = clock_->now();
172 
173  costmap_raw_->metadata.layer = "master";
174  costmap_raw_->metadata.resolution = resolution;
175 
176  costmap_raw_->metadata.size_x = costmap_->getSizeInCellsX();
177  costmap_raw_->metadata.size_y = costmap_->getSizeInCellsY();
178 
179  double wx, wy;
180  costmap_->mapToWorld(0, 0, wx, wy);
181  costmap_raw_->metadata.origin.position.x = wx - resolution / 2;
182  costmap_raw_->metadata.origin.position.y = wy - resolution / 2;
183  costmap_raw_->metadata.origin.position.z = 0.0;
184  costmap_raw_->metadata.origin.orientation.w = 1.0;
185 
186  costmap_raw_->data.resize(costmap_raw_->metadata.size_x * costmap_raw_->metadata.size_y);
187 
188  unsigned char * data = costmap_->getCharMap();
189  memcpy(costmap_raw_->data.data(), data, costmap_raw_->data.size());
190 }
191 
192 std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> Costmap2DPublisher::createGridUpdateMsg()
193 {
194  auto update = std::make_unique<map_msgs::msg::OccupancyGridUpdate>();
195 
196  update->header.stamp = clock_->now();
197  update->header.frame_id = global_frame_;
198  update->x = x0_;
199  update->y = y0_;
200  update->width = xn_ - x0_;
201  update->height = yn_ - y0_;
202  update->data.resize(update->width * update->height);
203  const std::uint32_t map_width = costmap_->getSizeInCellsX();
204  unsigned char * costmap_data = costmap_->getCharMap();
205  std::uint32_t i = 0;
206  for (std::uint32_t y = y0_; y < yn_; y++) {
207  std::uint32_t row_start = y * map_width + x0_;
208  std::transform(costmap_data + row_start, costmap_data + row_start + update->width,
209  update->data.begin() + i,
210  [](unsigned char c) {return cost_translation_table_[c];});
211  i += update->width;
212  }
213  return update;
214 }
215 
216 std::unique_ptr<nav2_msgs::msg::CostmapUpdate> Costmap2DPublisher::createCostmapUpdateMsg()
217 {
218  auto msg = std::make_unique<nav2_msgs::msg::CostmapUpdate>();
219 
220  msg->header.stamp = clock_->now();
221  msg->header.frame_id = global_frame_;
222  msg->x = x0_;
223  msg->y = y0_;
224  msg->size_x = xn_ - x0_;
225  msg->size_y = yn_ - y0_;
226  msg->data.resize(msg->size_x * msg->size_y);
227  const std::uint32_t map_width = costmap_->getSizeInCellsX();
228  unsigned char * costmap_data = costmap_->getCharMap();
229 
230  std::uint32_t i = 0;
231  for (std::uint32_t y = y0_; y < yn_; y++) {
232  std::uint32_t row_start = y * map_width + x0_;
233  std::copy_n(costmap_data + row_start, msg->size_x, msg->data.begin() + i);
234  i += msg->size_x;
235  }
236  return msg;
237 }
238 
240 {
241  float resolution = costmap_->getResolution();
242  if (always_send_full_costmap_ || grid_resolution_ != resolution ||
243  grid_width_ != costmap_->getSizeInCellsX() ||
244  grid_height_ != costmap_->getSizeInCellsY() ||
245  saved_origin_x_ != costmap_->getOriginX() ||
246  saved_origin_y_ != costmap_->getOriginY())
247  {
248  updateGridParams();
249  if (costmap_pub_->get_subscription_count() > 0) {
250  prepareGrid();
251  costmap_pub_->publish(std::move(grid_));
252  }
253  if (costmap_raw_pub_->get_subscription_count() > 0) {
254  prepareCostmap();
255  costmap_raw_pub_->publish(std::move(costmap_raw_));
256  }
257  } else if (x0_ < xn_) {
258  // Publish just update msgs
259  std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
260  if (costmap_update_pub_->get_subscription_count() > 0) {
261  costmap_update_pub_->publish(createGridUpdateMsg());
262  }
263  if (costmap_raw_update_pub_->get_subscription_count() > 0) {
264  costmap_raw_update_pub_->publish(createCostmapUpdateMsg());
265  }
266  }
267 
268  xn_ = yn_ = 0;
269  x0_ = costmap_->getSizeInCellsX();
270  y0_ = costmap_->getSizeInCellsY();
271 }
272 
273 void
274 Costmap2DPublisher::costmap_service_callback(
275  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
276  const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>/*request*/,
277  const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
278 {
279  RCLCPP_DEBUG(logger_, "Received costmap service request");
280 
281  // TODO(bpwilcox): Grab correct orientation information
282  tf2::Quaternion quaternion;
283  quaternion.setRPY(0.0, 0.0, 0.0);
284 
285  auto size_x = costmap_->getSizeInCellsX();
286  auto size_y = costmap_->getSizeInCellsY();
287  auto data_length = size_x * size_y;
288  unsigned char * data = costmap_->getCharMap();
289  auto current_time = clock_->now();
290 
291  response->map.header.stamp = current_time;
292  response->map.header.frame_id = global_frame_;
293  response->map.metadata.size_x = size_x;
294  response->map.metadata.size_y = size_y;
295  response->map.metadata.resolution = costmap_->getResolution();
296  response->map.metadata.layer = "master";
297  response->map.metadata.map_load_time = current_time;
298  response->map.metadata.update_time = current_time;
299  response->map.metadata.origin.position.x = costmap_->getOriginX();
300  response->map.metadata.origin.position.y = costmap_->getOriginY();
301  response->map.metadata.origin.position.z = 0.0;
302  response->map.metadata.origin.orientation = tf2::toMsg(quaternion);
303  response->map.data.resize(data_length);
304  response->map.data.assign(data, data + data_length);
305 }
306 
307 } // 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:69
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 * 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:576
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:571
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:566
A simple wrapper on ROS2 services server.