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