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