Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
static_layer.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * Copyright (c) 2015, Fetch Robotics, 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 
40 #include "nav2_costmap_2d/static_layer.hpp"
41 
42 #include <algorithm>
43 #include <string>
44 
45 #include "pluginlib/class_list_macros.hpp"
46 #include "tf2/convert.h"
47 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
48 #include "nav2_util/validate_messages.hpp"
49 
51 
52 using nav2_costmap_2d::NO_INFORMATION;
53 using nav2_costmap_2d::LETHAL_OBSTACLE;
54 using nav2_costmap_2d::FREE_SPACE;
55 using rcl_interfaces::msg::ParameterType;
56 
57 namespace nav2_costmap_2d
58 {
59 
61 : map_buffer_(nullptr)
62 {
63 }
64 
66 {
67 }
68 
69 void
71 {
72  global_frame_ = layered_costmap_->getGlobalFrameID();
73 
74  getParameters();
75 
76  rclcpp::QoS map_qos(10); // initialize to default
77  if (map_subscribe_transient_local_) {
78  map_qos.transient_local();
79  map_qos.reliable();
80  map_qos.keep_last(1);
81  }
82 
83  RCLCPP_INFO(
84  logger_,
85  "Subscribing to the map topic (%s) with %s durability",
86  map_topic_.c_str(),
87  map_subscribe_transient_local_ ? "transient local" : "volatile");
88 
89  auto node = node_.lock();
90  if (!node) {
91  throw std::runtime_error{"Failed to lock node"};
92  }
93 
94  map_sub_ = node->create_subscription<nav_msgs::msg::OccupancyGrid>(
95  map_topic_, map_qos,
96  std::bind(&StaticLayer::incomingMap, this, std::placeholders::_1));
97 
98  if (subscribe_to_updates_) {
99  RCLCPP_INFO(logger_, "Subscribing to updates");
100  map_update_sub_ = node->create_subscription<map_msgs::msg::OccupancyGridUpdate>(
101  map_topic_ + "_updates",
102  rclcpp::SystemDefaultsQoS(),
103  std::bind(&StaticLayer::incomingUpdate, this, std::placeholders::_1));
104  }
105 }
106 
107 void
109 {
110 }
111 
112 void
114 {
115  auto node = node_.lock();
116  if (dyn_params_handler_ && node) {
117  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
118  }
119  dyn_params_handler_.reset();
120 }
121 
122 void
124 {
125  has_updated_data_ = true;
126  current_ = false;
127 }
128 
129 void
131 {
132  int temp_lethal_threshold = 0;
133  double temp_tf_tol = 0.0;
134 
135  declareParameter("enabled", rclcpp::ParameterValue(true));
136  declareParameter("subscribe_to_updates", rclcpp::ParameterValue(false));
137  declareParameter("map_subscribe_transient_local", rclcpp::ParameterValue(true));
138  declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
139  declareParameter("map_topic", rclcpp::ParameterValue(""));
140  declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));
141 
142  auto node = node_.lock();
143  if (!node) {
144  throw std::runtime_error{"Failed to lock node"};
145  }
146 
147  node->get_parameter(name_ + "." + "enabled", enabled_);
148  node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_);
149  node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
150  std::string private_map_topic, global_map_topic;
151  node->get_parameter(name_ + "." + "map_topic", private_map_topic);
152  node->get_parameter("map_topic", global_map_topic);
153  if (!private_map_topic.empty()) {
154  map_topic_ = private_map_topic;
155  } else {
156  map_topic_ = global_map_topic;
157  }
158  node->get_parameter(
159  name_ + "." + "map_subscribe_transient_local",
160  map_subscribe_transient_local_);
161  node->get_parameter("track_unknown_space", track_unknown_space_);
162  node->get_parameter("use_maximum", use_maximum_);
163  node->get_parameter("lethal_cost_threshold", temp_lethal_threshold);
164  node->get_parameter("unknown_cost_value", unknown_cost_value_);
165  node->get_parameter("trinary_costmap", trinary_costmap_);
166  node->get_parameter("transform_tolerance", temp_tf_tol);
167 
168  // Enforce bounds
169  lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
170  map_received_ = false;
171  map_received_in_update_bounds_ = false;
172 
173  transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
174 
175  // Add callback for dynamic parameters
176  dyn_params_handler_ = node->add_on_set_parameters_callback(
177  std::bind(
179  this, std::placeholders::_1));
180 }
181 
182 void
183 StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
184 {
185  RCLCPP_DEBUG(logger_, "StaticLayer: Process map");
186 
187  unsigned int size_x = new_map.info.width;
188  unsigned int size_y = new_map.info.height;
189 
190  RCLCPP_DEBUG(
191  logger_,
192  "StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y,
193  new_map.info.resolution);
194 
195  // resize costmap if size, resolution or origin do not match
196  Costmap2D * master = layered_costmap_->getCostmap();
197  if (!layered_costmap_->isRolling() && (master->getSizeInCellsX() != size_x ||
198  master->getSizeInCellsY() != size_y ||
199  master->getResolution() != new_map.info.resolution ||
200  master->getOriginX() != new_map.info.origin.position.x ||
201  master->getOriginY() != new_map.info.origin.position.y ||
202  !layered_costmap_->isSizeLocked()))
203  {
204  // Update the size of the layered costmap (and all layers, including this one)
205  RCLCPP_INFO(
206  logger_,
207  "StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y,
208  new_map.info.resolution);
209  layered_costmap_->resizeMap(
210  size_x, size_y, new_map.info.resolution,
211  new_map.info.origin.position.x,
212  new_map.info.origin.position.y,
213  true);
214  } else if (size_x_ != size_x || size_y_ != size_y || // NOLINT
215  resolution_ != new_map.info.resolution ||
216  origin_x_ != new_map.info.origin.position.x ||
217  origin_y_ != new_map.info.origin.position.y)
218  {
219  // only update the size of the costmap stored locally in this layer
220  RCLCPP_INFO(
221  logger_,
222  "StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y,
223  new_map.info.resolution);
224  resizeMap(
225  size_x, size_y, new_map.info.resolution,
226  new_map.info.origin.position.x, new_map.info.origin.position.y);
227  }
228 
229  unsigned int index = 0;
230 
231  // we have a new map, update full size of map
232  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
233 
234  // initialize the costmap with static data
235  for (unsigned int i = 0; i < size_y; ++i) {
236  for (unsigned int j = 0; j < size_x; ++j) {
237  unsigned char value = new_map.data[index];
238  costmap_[index] = interpretValue(value);
239  ++index;
240  }
241  }
242 
243  map_frame_ = new_map.header.frame_id;
244 
245  x_ = y_ = 0;
246  width_ = size_x_;
247  height_ = size_y_;
248  has_updated_data_ = true;
249 
250  current_ = true;
251 }
252 
253 void
255 {
256  // If we are using rolling costmap, the static map size is
257  // unrelated to the size of the layered costmap
258  if (!layered_costmap_->isRolling()) {
259  Costmap2D * master = layered_costmap_->getCostmap();
260  resizeMap(
261  master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
262  master->getOriginX(), master->getOriginY());
263  }
264 }
265 
266 unsigned char
267 StaticLayer::interpretValue(unsigned char value)
268 {
269  // check if the static value is above the unknown or lethal thresholds
270  if (track_unknown_space_ && value == unknown_cost_value_) {
271  return NO_INFORMATION;
272  } else if (!track_unknown_space_ && value == unknown_cost_value_) {
273  return FREE_SPACE;
274  } else if (value >= lethal_threshold_) {
275  return LETHAL_OBSTACLE;
276  } else if (trinary_costmap_) {
277  return FREE_SPACE;
278  }
279 
280  double scale = static_cast<double>(value) / lethal_threshold_;
281  return scale * LETHAL_OBSTACLE;
282 }
283 
284 void
285 StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
286 {
287  if (!nav2_util::validateMsg(*new_map)) {
288  RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting.");
289  return;
290  }
291  if (!map_received_) {
292  processMap(*new_map);
293  map_received_ = true;
294  return;
295  }
296  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
297  map_buffer_ = new_map;
298 }
299 
300 void
301 StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
302 {
303  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
304  if (update->y < static_cast<int32_t>(y_) ||
305  y_ + height_ < update->y + update->height ||
306  update->x < static_cast<int32_t>(x_) ||
307  x_ + width_ < update->x + update->width)
308  {
309  RCLCPP_WARN(
310  logger_,
311  "StaticLayer: Map update ignored. Exceeds bounds of static layer.\n"
312  "Static layer origin: %d, %d bounds: %d X %d\n"
313  "Update origin: %d, %d bounds: %d X %d",
314  x_, y_, width_, height_, update->x, update->y, update->width,
315  update->height);
316  return;
317  }
318 
319  if (update->header.frame_id != map_frame_) {
320  RCLCPP_WARN(
321  logger_,
322  "StaticLayer: Map update ignored. Current map is in frame %s "
323  "but update was in frame %s",
324  map_frame_.c_str(), update->header.frame_id.c_str());
325  return;
326  }
327 
328  unsigned int di = 0;
329  for (unsigned int y = 0; y < update->height; y++) {
330  unsigned int index_base = (update->y + y) * size_x_;
331  for (unsigned int x = 0; x < update->width; x++) {
332  unsigned int index = index_base + x + update->x;
333  costmap_[index] = interpretValue(update->data[di++]);
334  }
335  }
336 
337  has_updated_data_ = true;
338 }
339 
340 
341 void
343  double robot_x, double robot_y, double robot_yaw, double * min_x,
344  double * min_y,
345  double * max_x,
346  double * max_y)
347 {
348  if (!map_received_) {
349  map_received_in_update_bounds_ = false;
350  return;
351  }
352  map_received_in_update_bounds_ = true;
353 
354  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
355 
356  // If there is a new available map, load it.
357  if (map_buffer_) {
358  processMap(*map_buffer_);
359  map_buffer_ = nullptr;
360  }
361 
362  if (!layered_costmap_->isRolling() ) {
363  if (!(has_updated_data_ || has_extra_bounds_)) {
364  return;
365  }
366  }
367 
368  useExtraBounds(min_x, min_y, max_x, max_y);
369 
370  double wx, wy;
371 
372  mapToWorld(x_, y_, wx, wy);
373  *min_x = std::min(wx, *min_x);
374  *min_y = std::min(wy, *min_y);
375 
376  mapToWorld(x_ + width_, y_ + height_, wx, wy);
377  *max_x = std::max(wx, *max_x);
378  *max_y = std::max(wy, *max_y);
379 
380  has_updated_data_ = false;
381 
382  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
383 }
384 
385 void
387  double robot_x, double robot_y, double robot_yaw,
388  double * min_x, double * min_y,
389  double * max_x,
390  double * max_y)
391 {
392  if (!footprint_clearing_enabled_) {return;}
393 
394  transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
395 
396  for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
397  touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
398  }
399 }
400 
401 void
403  nav2_costmap_2d::Costmap2D & master_grid,
404  int min_i, int min_j, int max_i, int max_j)
405 {
406  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
407  if (!enabled_) {
408  return;
409  }
410  if (!map_received_in_update_bounds_) {
411  static int count = 0;
412  // throttle warning down to only 1/10 message rate
413  if (++count == 10) {
414  RCLCPP_WARN(logger_, "Can't update static costmap layer, no map received");
415  count = 0;
416  }
417  return;
418  }
419 
420  if (footprint_clearing_enabled_) {
421  setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
422  }
423 
424  if (!layered_costmap_->isRolling()) {
425  // if not rolling, the layered costmap (master_grid) has same coordinates as this layer
426  if (!use_maximum_) {
427  updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
428  } else {
429  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
430  }
431  } else {
432  // If rolling window, the master_grid is unlikely to have same coordinates as this layer
433  unsigned int mx, my;
434  double wx, wy;
435  // Might even be in a different frame
436  geometry_msgs::msg::TransformStamped transform;
437  try {
438  transform = tf_->lookupTransform(
439  map_frame_, global_frame_, tf2::TimePointZero,
440  transform_tolerance_);
441  } catch (tf2::TransformException & ex) {
442  RCLCPP_ERROR(logger_, "StaticLayer: %s", ex.what());
443  return;
444  }
445  // Copy map data given proper transformations
446  tf2::Transform tf2_transform;
447  tf2::fromMsg(transform.transform, tf2_transform);
448 
449  for (int i = min_i; i < max_i; ++i) {
450  for (int j = min_j; j < max_j; ++j) {
451  // Convert master_grid coordinates (i,j) into global_frame_(wx,wy) coordinates
452  layered_costmap_->getCostmap()->mapToWorld(i, j, wx, wy);
453  // Transform from global_frame_ to map_frame_
454  tf2::Vector3 p(wx, wy, 0);
455  p = tf2_transform * p;
456  // Set master_grid with cell from map
457  if (worldToMap(p.x(), p.y(), mx, my)) {
458  if (!use_maximum_) {
459  master_grid.setCost(i, j, getCost(mx, my));
460  } else {
461  master_grid.setCost(i, j, std::max(getCost(mx, my), master_grid.getCost(i, j)));
462  }
463  }
464  }
465  }
466  }
467  current_ = true;
468 }
469 
474 rcl_interfaces::msg::SetParametersResult
476  std::vector<rclcpp::Parameter> parameters)
477 {
478  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
479  rcl_interfaces::msg::SetParametersResult result;
480 
481  for (auto parameter : parameters) {
482  const auto & param_type = parameter.get_type();
483  const auto & param_name = parameter.get_name();
484 
485  if (param_name == name_ + "." + "map_subscribe_transient_local" ||
486  param_name == name_ + "." + "map_topic" ||
487  param_name == name_ + "." + "subscribe_to_updates")
488  {
489  RCLCPP_WARN(
490  logger_, "%s is not a dynamic parameter "
491  "cannot be changed while running. Rejecting parameter update.", param_name.c_str());
492  } else if (param_type == ParameterType::PARAMETER_DOUBLE) {
493  if (param_name == name_ + "." + "transform_tolerance") {
494  transform_tolerance_ = tf2::durationFromSec(parameter.as_double());
495  }
496  } else if (param_type == ParameterType::PARAMETER_BOOL) {
497  if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
498  enabled_ = parameter.as_bool();
499 
500  x_ = y_ = 0;
501  width_ = size_x_;
502  height_ = size_y_;
503  has_updated_data_ = true;
504  current_ = false;
505  } else if (param_name == name_ + "." + "footprint_clearing_enabled") {
506  footprint_clearing_enabled_ = parameter.as_bool();
507  }
508  }
509  }
510  result.successful = true;
511  return result;
512 }
513 
514 } // namespace nav2_costmap_2d
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
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
Definition: costmap_2d.cpp:110
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:285
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:544
bool setConvexPolygonCost(const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
Definition: costmap_2d.cpp:399
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
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:274
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
Definition: layer.cpp:70
bool isRolling()
If this costmap is rolling or not.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
Resize the map to a new size, resolution, or origin.
bool isSizeLocked()
Get if the size of the costmap is locked.
Takes in a map generated from SLAM to add costs to costmap.
void getParameters()
Get parameters of layer.
virtual ~StaticLayer()
Static Layer destructor.
virtual void deactivate()
Deactivate this layer.
bool has_updated_data_
frame that map is located in
unsigned char interpretValue(unsigned char value)
Interpret the value in the static map given on the topic to convert into costs for the costmap to uti...
StaticLayer()
Static Layer constructor.
virtual void matchSize()
Match the size of the master costmap.
virtual void onInitialize()
Initialization process of layer on startup.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Clear costmap layer info below the robot's footprint.
virtual void activate()
Activate this layer.
void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
Callback to update the costmap's map from the map_server (or SLAM) with an update in a particular are...
void incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
Callback to update the costmap's map from the map_server.
std::string global_frame_
The global frame for the costmap.
void processMap(const nav_msgs::msg::OccupancyGrid &new_map)
Process a new map coming from a topic.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual void reset()
Reset this costmap.
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
Definition: footprint.cpp:110