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