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