Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
voxel_layer.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 
39 #include "nav2_costmap_2d/voxel_layer.hpp"
40 
41 #include <algorithm>
42 #include <cassert>
43 #include <vector>
44 #include <memory>
45 #include <utility>
46 
47 #include "pluginlib/class_list_macros.hpp"
48 #include "sensor_msgs/point_cloud2_iterator.hpp"
49 
50 #define VOXEL_BITS 16
52 
53 using nav2_costmap_2d::NO_INFORMATION;
54 using nav2_costmap_2d::LETHAL_OBSTACLE;
55 using nav2_costmap_2d::FREE_SPACE;
56 using rcl_interfaces::msg::ParameterType;
57 
58 namespace nav2_costmap_2d
59 {
60 
62 {
64 
65  declareParameter("enabled", rclcpp::ParameterValue(true));
66  declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(true));
67  declareParameter("min_obstacle_height", rclcpp::ParameterValue(0.0));
68  declareParameter("max_obstacle_height", rclcpp::ParameterValue(2.0));
69  declareParameter("z_voxels", rclcpp::ParameterValue(10));
70  declareParameter("origin_z", rclcpp::ParameterValue(0.0));
71  declareParameter("z_resolution", rclcpp::ParameterValue(0.2));
72  declareParameter("unknown_threshold", rclcpp::ParameterValue(15));
73  declareParameter("mark_threshold", rclcpp::ParameterValue(0));
74  declareParameter("combination_method", rclcpp::ParameterValue(1));
75  declareParameter("publish_voxel_map", rclcpp::ParameterValue(false));
76 
77  auto node = node_.lock();
78  if (!node) {
79  throw std::runtime_error{"Failed to lock node"};
80  }
81 
82  node->get_parameter(name_ + "." + "enabled", enabled_);
83  node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
84  node->get_parameter(name_ + "." + "min_obstacle_height", min_obstacle_height_);
85  node->get_parameter(name_ + "." + "max_obstacle_height", max_obstacle_height_);
86  node->get_parameter(name_ + "." + "z_voxels", size_z_);
87  node->get_parameter(name_ + "." + "origin_z", origin_z_);
88  node->get_parameter(name_ + "." + "z_resolution", z_resolution_);
89  node->get_parameter(name_ + "." + "unknown_threshold", unknown_threshold_);
90  node->get_parameter(name_ + "." + "mark_threshold", mark_threshold_);
91  node->get_parameter(name_ + "." + "publish_voxel_map", publish_voxel_);
92 
93  int combination_method_param{};
94  node->get_parameter(name_ + "." + "combination_method", combination_method_param);
95  combination_method_ = combination_method_from_int(combination_method_param);
96 
97  if (publish_voxel_) {
98  voxel_pub_ = node->create_publisher<nav2_msgs::msg::VoxelGrid>(
99  "voxel_grid", nav2::qos::LatchedPublisherQoS());
100  voxel_pub_->on_activate();
101  }
102 
103  clearing_endpoints_pub_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(
104  "clearing_endpoints", nav2::qos::LatchedPublisherQoS());
105  clearing_endpoints_pub_->on_activate();
106 
107  unknown_threshold_ += (VOXEL_BITS - size_z_);
108  matchSize();
109 
110  // Add callback for dynamic parameters
111  dyn_params_handler_ = node->add_on_set_parameters_callback(
112  std::bind(
114  this, std::placeholders::_1));
115 }
116 
118 {
119  auto node = node_.lock();
120  if (dyn_params_handler_ && node) {
121  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
122  }
123  dyn_params_handler_.reset();
124 }
125 
127 {
128  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
130  voxel_grid_.resize(size_x_, size_y_, size_z_);
131  assert(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
132 }
133 
135 {
136  // Call the base class method before adding our own functionality
138  resetMaps();
139 }
140 
142 {
143  // Call the base class method before adding our own functionality
144  // Note: at the time this was written, ObstacleLayer doesn't implement
145  // resetMaps so this goes to the next layer down Costmap2DLayer which also
146  // doesn't implement this, so it actually goes all the way to Costmap2D
148  voxel_grid_.reset();
149 }
150 
152  double robot_x, double robot_y, double robot_yaw, double * min_x,
153  double * min_y, double * max_x, double * max_y)
154 {
155  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
156 
157  if (rolling_window_) {
158  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
159  }
160  if (!enabled_) {
161  return;
162  }
163  useExtraBounds(min_x, min_y, max_x, max_y);
164 
165  bool current = true;
166  std::vector<Observation> observations, clearing_observations;
167 
168  // get the marking observations
169  current = getMarkingObservations(observations) && current;
170 
171  // get the clearing observations
172  current = getClearingObservations(clearing_observations) && current;
173 
174  // update the global current status
175  current_ = current;
176 
177  // raytrace freespace
178  for (unsigned int i = 0; i < clearing_observations.size(); ++i) {
179  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
180  }
181 
182  // place the new obstacles into a priority queue... each with a priority of zero to begin with
183  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end();
184  ++it)
185  {
186  const Observation & obs = *it;
187 
188  const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
189 
190  double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
191  double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
192 
193  sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
194  sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
195  sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
196 
197  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
198  // if the obstacle is too low, we won't add it
199  if (*iter_z < min_obstacle_height_) {
200  continue;
201  }
202 
203  // if the obstacle is too high or too far away from the robot we won't add it
204  if (*iter_z > max_obstacle_height_) {
205  continue;
206  }
207 
208  // compute the squared distance from the hitpoint to the pointcloud's origin
209  double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) +
210  (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) +
211  (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
212 
213  // if the point is far enough away... we won't consider it
214  if (sq_dist >= sq_obstacle_max_range) {
215  continue;
216  }
217 
218  // If the point is too close, do not consider it
219  if (sq_dist < sq_obstacle_min_range) {
220  continue;
221  }
222 
223  // now we need to compute the map coordinates for the observation
224  unsigned int mx, my, mz;
225  if (*iter_z < origin_z_) {
226  if (!worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz)) {
227  continue;
228  }
229  } else if (!worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz)) {
230  continue;
231  }
232 
233  // mark the cell in the voxel grid and check if we should also mark it in the costmap
234  if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)) {
235  unsigned int index = getIndex(mx, my);
236 
237  costmap_[index] = LETHAL_OBSTACLE;
238  touch(
239  static_cast<double>(*iter_x), static_cast<double>(*iter_y),
240  min_x, min_y, max_x, max_y);
241  }
242  }
243  }
244 
245  if (publish_voxel_) {
246  auto grid_msg = std::make_unique<nav2_msgs::msg::VoxelGrid>();
247  unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
248  grid_msg->size_x = voxel_grid_.sizeX();
249  grid_msg->size_y = voxel_grid_.sizeY();
250  grid_msg->size_z = voxel_grid_.sizeZ();
251  grid_msg->data.resize(size);
252  memcpy(&grid_msg->data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
253 
254  grid_msg->origin.x = origin_x_;
255  grid_msg->origin.y = origin_y_;
256  grid_msg->origin.z = origin_z_;
257 
258  grid_msg->resolutions.x = resolution_;
259  grid_msg->resolutions.y = resolution_;
260  grid_msg->resolutions.z = z_resolution_;
261  grid_msg->header.frame_id = global_frame_;
262  grid_msg->header.stamp = clock_->now();
263 
264  voxel_pub_->publish(std::move(grid_msg));
265  }
266 
267  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
268 }
269 
271  const Observation & clearing_observation, double * min_x,
272  double * min_y,
273  double * max_x,
274  double * max_y)
275 {
276  auto clearing_endpoints_ = std::make_unique<sensor_msgs::msg::PointCloud2>();
277 
278  if (clearing_observation.cloud_->height == 0 || clearing_observation.cloud_->width == 0) {
279  return;
280  }
281 
282  double sensor_x, sensor_y, sensor_z;
283  double ox = clearing_observation.origin_.x;
284  double oy = clearing_observation.origin_.y;
285  double oz = clearing_observation.origin_.z;
286 
287  if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)) {
288  RCLCPP_WARN(
289  logger_,
290  "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
291  "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
292  "The costmap cannot raytrace for it.",
293  ox, oy, oz,
294  origin_x_, origin_y_, origin_z_,
295  origin_x_ + getSizeInMetersX(), origin_y_ + getSizeInMetersY(),
296  origin_z_ + getSizeInMetersZ());
297 
298  return;
299  }
300 
301  bool publish_clearing_points;
302 
303  {
304  auto node = node_.lock();
305  if (!node) {
306  throw std::runtime_error{"Failed to lock node"};
307  }
308  publish_clearing_points = (node->count_subscribers("clearing_endpoints") > 0);
309  }
310 
311  clearing_endpoints_->data.clear();
312  clearing_endpoints_->width = clearing_observation.cloud_->width;
313  clearing_endpoints_->height = clearing_observation.cloud_->height;
314  clearing_endpoints_->is_dense = true;
315  clearing_endpoints_->is_bigendian = false;
316 
317  sensor_msgs::PointCloud2Modifier modifier(*clearing_endpoints_);
318  modifier.setPointCloud2Fields(
319  3, "x", 1, sensor_msgs::msg::PointField::FLOAT32,
320  "y", 1, sensor_msgs::msg::PointField::FLOAT32,
321  "z", 1, sensor_msgs::msg::PointField::FLOAT32);
322 
323  sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_x(*clearing_endpoints_, "x");
324  sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_y(*clearing_endpoints_, "y");
325  sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_z(*clearing_endpoints_, "z");
326 
327  // we can pre-compute the endpoints of the map outside of the inner loop... we'll need these later
328  double map_end_x = origin_x_ + getSizeInMetersX();
329  double map_end_y = origin_y_ + getSizeInMetersY();
330  double map_end_z = origin_z_ + getSizeInMetersZ();
331 
332  sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_), "x");
333  sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_), "y");
334  sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_), "z");
335 
336  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
337  double wpx = *iter_x;
338  double wpy = *iter_y;
339  double wpz = *iter_z;
340 
341  double distance = dist(ox, oy, oz, wpx, wpy, wpz);
342  double scaling_fact = 1.0;
343  scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
344  wpx = scaling_fact * (wpx - ox) + ox;
345  wpy = scaling_fact * (wpy - oy) + oy;
346  wpz = scaling_fact * (wpz - oz) + oz;
347 
348  double a = wpx - ox;
349  double b = wpy - oy;
350  double c = wpz - oz;
351  double t = 1.0;
352  bool wp_outside = false;
353 
354  // we can only raytrace to a maximum z height
355  if (wpz > map_end_z) {
356  // we know we want the vector's z value to be max_z
357  t = std::max(0.0, std::min(t, (map_end_z - 0.01 - oz) / c));
358  wp_outside = true;
359  } else if (wpz < origin_z_) {
360  // and we can only raytrace down to the floor
361  // we know we want the vector's z value to be 0.0
362  t = std::min(t, (origin_z_ - oz) / c);
363  wp_outside = true;
364  }
365 
366  // the minimum value to raytrace from is the origin
367  if (wpx < origin_x_) {
368  t = std::min(t, (origin_x_ - ox) / a);
369  wp_outside = true;
370  }
371  if (wpy < origin_y_) {
372  t = std::min(t, (origin_y_ - oy) / b);
373  wp_outside = true;
374  }
375 
376  // the maximum value to raytrace to is the end of the map
377  if (wpx > map_end_x) {
378  t = std::min(t, (map_end_x - ox) / a);
379  wp_outside = true;
380  }
381  if (wpy > map_end_y) {
382  t = std::min(t, (map_end_y - oy) / b);
383  wp_outside = true;
384  }
385 
386  constexpr double wp_epsilon = 1e-5;
387  if (wp_outside) {
388  if (t > 0.0) {
389  t -= wp_epsilon;
390  } else if (t < 0.0) {
391  t += wp_epsilon;
392  }
393  }
394 
395  wpx = ox + a * t;
396  wpy = oy + b * t;
397  wpz = oz + c * t;
398 
399  double point_x, point_y, point_z;
400  if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z)) {
401  unsigned int cell_raytrace_max_range = cellDistance(clearing_observation.raytrace_max_range_);
402  unsigned int cell_raytrace_min_range = cellDistance(clearing_observation.raytrace_min_range_);
403 
404 
405  // voxel_grid_.markVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z);
406  voxel_grid_.clearVoxelLineInMap(
407  sensor_x, sensor_y, sensor_z, point_x, point_y, point_z,
408  costmap_,
409  unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
410  cell_raytrace_max_range, cell_raytrace_min_range);
411 
413  ox, oy, wpx, wpy, clearing_observation.raytrace_max_range_,
414  clearing_observation.raytrace_min_range_, min_x, min_y,
415  max_x,
416  max_y);
417 
418  if (publish_clearing_points) {
419  *clearing_endpoints_iter_x = wpx;
420  *clearing_endpoints_iter_y = wpy;
421  *clearing_endpoints_iter_z = wpz;
422 
423  ++clearing_endpoints_iter_x;
424  ++clearing_endpoints_iter_y;
425  ++clearing_endpoints_iter_z;
426  }
427  }
428  }
429 
430  if (publish_clearing_points) {
431  clearing_endpoints_->header.frame_id = global_frame_;
432  clearing_endpoints_->header.stamp = clearing_observation.cloud_->header.stamp;
433 
434  clearing_endpoints_pub_->publish(std::move(clearing_endpoints_));
435  }
436 }
437 
438 void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
439 {
440  // project the new origin into the grid
441  int cell_ox, cell_oy;
442  cell_ox = static_cast<int>((new_origin_x - origin_x_) / resolution_);
443  cell_oy = static_cast<int>((new_origin_y - origin_y_) / resolution_);
444 
445  // compute the associated world coordinates for the origin cell
446  // because we want to keep things grid-aligned
447  double new_grid_ox, new_grid_oy;
448  new_grid_ox = origin_x_ + cell_ox * resolution_;
449  new_grid_oy = origin_y_ + cell_oy * resolution_;
450 
451  // To save casting from unsigned int to int a bunch of times
452  int size_x = size_x_;
453  int size_y = size_y_;
454 
455  // we need to compute the overlap of the new and existing windows
456  int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
457  lower_left_x = std::min(std::max(cell_ox, 0), size_x);
458  lower_left_y = std::min(std::max(cell_oy, 0), size_y);
459  upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
460  upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
461 
462  unsigned int cell_size_x = upper_right_x - lower_left_x;
463  unsigned int cell_size_y = upper_right_y - lower_left_y;
464 
465  // we need a map to store the obstacles in the window temporarily
466  unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y];
467  unsigned int * local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
468  unsigned int * voxel_map = voxel_grid_.getData();
469 
470  // copy the local window in the costmap to the local map
472  costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x,
473  cell_size_x,
474  cell_size_y);
476  voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x,
477  cell_size_x,
478  cell_size_y);
479 
480  // we'll reset our maps to unknown space if appropriate
481  resetMaps();
482 
483  // update the origin with the appropriate world coordinates
484  origin_x_ = new_grid_ox;
485  origin_y_ = new_grid_oy;
486 
487  // compute the starting cell location for copying data back in
488  int start_x = lower_left_x - cell_ox;
489  int start_y = lower_left_y - cell_oy;
490 
491  // now we want to copy the overlapping information back into the map, but in its new location
493  local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x,
494  cell_size_y);
496  local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_,
497  cell_size_x,
498  cell_size_y);
499 
500  // make sure to clean up
501  delete[] local_map;
502  delete[] local_voxel_map;
503 }
504 
509 rcl_interfaces::msg::SetParametersResult
511  std::vector<rclcpp::Parameter> parameters)
512 {
513  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
514  rcl_interfaces::msg::SetParametersResult result;
515  bool resize_map_needed = false;
516 
517  for (auto parameter : parameters) {
518  const auto & param_type = parameter.get_type();
519  const auto & param_name = parameter.get_name();
520  if (param_name.find(name_ + ".") != 0) {
521  continue;
522  }
523 
524  if (param_type == ParameterType::PARAMETER_DOUBLE) {
525  if (param_name == name_ + "." + "min_obstacle_height") {
526  min_obstacle_height_ = parameter.as_double();
527  } else if (param_name == name_ + "." + "max_obstacle_height") {
528  max_obstacle_height_ = parameter.as_double();
529  } else if (param_name == name_ + "." + "origin_z") {
530  origin_z_ = parameter.as_double();
531  resize_map_needed = true;
532  } else if (param_name == name_ + "." + "z_resolution") {
533  z_resolution_ = parameter.as_double();
534  resize_map_needed = true;
535  }
536  } else if (param_type == ParameterType::PARAMETER_BOOL) {
537  if (param_name == name_ + "." + "enabled") {
538  enabled_ = parameter.as_bool();
539  current_ = false;
540  } else if (param_name == name_ + "." + "footprint_clearing_enabled") {
541  footprint_clearing_enabled_ = parameter.as_bool();
542  } else if (param_name == name_ + "." + "publish_voxel_map") {
543  RCLCPP_WARN(
544  logger_, "publish voxel map is not a dynamic parameter "
545  "cannot be changed while running. Rejecting parameter update.");
546  continue;
547  }
548 
549  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
550  if (param_name == name_ + "." + "z_voxels") {
551  size_z_ = parameter.as_int();
552  resize_map_needed = true;
553  } else if (param_name == name_ + "." + "unknown_threshold") {
554  unknown_threshold_ = parameter.as_int() + (VOXEL_BITS - size_z_);
555  } else if (param_name == name_ + "." + "mark_threshold") {
556  mark_threshold_ = parameter.as_int();
557  } else if (param_name == name_ + "." + "combination_method") {
558  combination_method_ = combination_method_from_int(parameter.as_int());
559  }
560  }
561  }
562 
563  if (resize_map_needed) {
564  matchSize();
565  }
566 
567  result.successful = true;
568  return result;
569 }
570 
571 } // namespace nav2_costmap_2d
A QoS profile for latched, reliable topics with a history of 1 messages.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:231
void copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
Copy a region of a source map into a destination map.
Definition: costmap_2d.hpp:428
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:561
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:556
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:124
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:253
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void matchSize()
Match the size of the master costmap.
CombinationMethod combination_method_from_int(const int value)
Converts an integer to a CombinationMethod enum and logs on failure.
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
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.hpp:47
bool getMarkingObservations(std::vector< nav2_costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
std::string global_frame_
The global frame for the costmap.
bool getClearingObservations(std::vector< nav2_costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double max_range, double min_range, double *min_x, double *min_y, double *max_x, double *max_y)
Process update costmap with raytracing the window bounds.
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 onInitialize()
Initialization process of layer on startup.
double min_obstacle_height_
Max Obstacle Height.
double max_obstacle_height_
Max Obstacle Height.
virtual void reset()
Reset this costmap.
Takes laser and pointcloud data to populate a 3D voxel representation of the environment.
Definition: voxel_layer.hpp:64
virtual void onInitialize()
Initialization process of layer on startup.
Definition: voxel_layer.cpp:61
virtual ~VoxelLayer()
Voxel Layer destructor.
double getSizeInMetersZ() const
Get the height of the voxel sizes in meters.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
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.
void updateOrigin(double new_origin_x, double new_origin_y)
Update the layer's origin to a new pose, often when in a rolling costmap.
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
Convert world coordinates into map coordinates.
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Convert world coordinates into map coordinates.
virtual void resetMaps()
Reset internal maps.
virtual void matchSize()
Match the size of the master costmap.
virtual void reset()
Reset this costmap.
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Find L2 norm distance in 3D.
virtual void raytraceFreespace(const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Use raycasting between 2 points to clear freespace.
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
Resizes a voxel grid to the desired size.
Definition: voxel_grid.cpp:67