Nav2 Navigation Stack - jazzy  jazzy
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  auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
98 
99  if (publish_voxel_) {
100  voxel_pub_ = node->create_publisher<nav2_msgs::msg::VoxelGrid>(
101  "voxel_grid", custom_qos);
102  voxel_pub_->on_activate();
103  }
104 
105  clearing_endpoints_pub_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(
106  "clearing_endpoints", custom_qos);
107  clearing_endpoints_pub_->on_activate();
108 
109  unknown_threshold_ += (VOXEL_BITS - size_z_);
110  matchSize();
111 
112  // Add callback for dynamic parameters
113  dyn_params_handler_ = node->add_on_set_parameters_callback(
114  std::bind(
116  this, std::placeholders::_1));
117 }
118 
120 {
121  auto node = node_.lock();
122  if (dyn_params_handler_ && node) {
123  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
124  }
125  dyn_params_handler_.reset();
126 }
127 
129 {
130  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
132  voxel_grid_.resize(size_x_, size_y_, size_z_);
133  assert(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
134 }
135 
137 {
138  // Call the base class method before adding our own functionality
140  resetMaps();
141 }
142 
144 {
145  // Call the base class method before adding our own functionality
146  // Note: at the time this was written, ObstacleLayer doesn't implement
147  // resetMaps so this goes to the next layer down Costmap2DLayer which also
148  // doesn't implement this, so it actually goes all the way to Costmap2D
150  voxel_grid_.reset();
151 }
152 
154  double robot_x, double robot_y, double robot_yaw, double * min_x,
155  double * min_y, double * max_x, double * max_y)
156 {
157  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
158 
159  if (rolling_window_) {
160  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
161  }
162  if (!enabled_) {
163  return;
164  }
165  useExtraBounds(min_x, min_y, max_x, max_y);
166 
167  bool current = true;
168  std::vector<Observation> observations, clearing_observations;
169 
170  // get the marking observations
171  current = getMarkingObservations(observations) && current;
172 
173  // get the clearing observations
174  current = getClearingObservations(clearing_observations) && current;
175 
176  // update the global current status
177  current_ = current;
178 
179  // raytrace freespace
180  for (unsigned int i = 0; i < clearing_observations.size(); ++i) {
181  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
182  }
183 
184  // place the new obstacles into a priority queue... each with a priority of zero to begin with
185  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end();
186  ++it)
187  {
188  const Observation & obs = *it;
189 
190  const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
191 
192  double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
193  double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
194 
195  sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
196  sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
197  sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
198 
199  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
200  // if the obstacle is too low, we won't add it
201  if (*iter_z < min_obstacle_height_) {
202  continue;
203  }
204 
205  // if the obstacle is too high or too far away from the robot we won't add it
206  if (*iter_z > max_obstacle_height_) {
207  continue;
208  }
209 
210  // compute the squared distance from the hitpoint to the pointcloud's origin
211  double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) +
212  (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) +
213  (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
214 
215  // if the point is far enough away... we won't consider it
216  if (sq_dist >= sq_obstacle_max_range) {
217  continue;
218  }
219 
220  // If the point is too close, do not consider it
221  if (sq_dist < sq_obstacle_min_range) {
222  continue;
223  }
224 
225  // now we need to compute the map coordinates for the observation
226  unsigned int mx, my, mz;
227  if (*iter_z < origin_z_) {
228  if (!worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz)) {
229  continue;
230  }
231  } else if (!worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz)) {
232  continue;
233  }
234 
235  // mark the cell in the voxel grid and check if we should also mark it in the costmap
236  if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)) {
237  unsigned int index = getIndex(mx, my);
238 
239  costmap_[index] = LETHAL_OBSTACLE;
240  touch(
241  static_cast<double>(*iter_x), static_cast<double>(*iter_y),
242  min_x, min_y, max_x, max_y);
243  }
244  }
245  }
246 
247  if (publish_voxel_) {
248  auto grid_msg = std::make_unique<nav2_msgs::msg::VoxelGrid>();
249  unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
250  grid_msg->size_x = voxel_grid_.sizeX();
251  grid_msg->size_y = voxel_grid_.sizeY();
252  grid_msg->size_z = voxel_grid_.sizeZ();
253  grid_msg->data.resize(size);
254  memcpy(&grid_msg->data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
255 
256  grid_msg->origin.x = origin_x_;
257  grid_msg->origin.y = origin_y_;
258  grid_msg->origin.z = origin_z_;
259 
260  grid_msg->resolutions.x = resolution_;
261  grid_msg->resolutions.y = resolution_;
262  grid_msg->resolutions.z = z_resolution_;
263  grid_msg->header.frame_id = global_frame_;
264  grid_msg->header.stamp = clock_->now();
265 
266  voxel_pub_->publish(std::move(grid_msg));
267  }
268 
269  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
270 }
271 
273  const Observation & clearing_observation, double * min_x,
274  double * min_y,
275  double * max_x,
276  double * max_y)
277 {
278  auto clearing_endpoints_ = std::make_unique<sensor_msgs::msg::PointCloud2>();
279 
280  if (clearing_observation.cloud_->height == 0 || clearing_observation.cloud_->width == 0) {
281  return;
282  }
283 
284  double sensor_x, sensor_y, sensor_z;
285  double ox = clearing_observation.origin_.x;
286  double oy = clearing_observation.origin_.y;
287  double oz = clearing_observation.origin_.z;
288 
289  if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)) {
290  RCLCPP_WARN(
291  logger_,
292  "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
293  "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
294  "The costmap cannot raytrace for it.",
295  ox, oy, oz,
296  origin_x_, origin_y_, origin_z_,
297  origin_x_ + getSizeInMetersX(), origin_y_ + getSizeInMetersY(),
298  origin_z_ + getSizeInMetersZ());
299 
300  return;
301  }
302 
303  bool publish_clearing_points;
304 
305  {
306  auto node = node_.lock();
307  if (!node) {
308  throw std::runtime_error{"Failed to lock node"};
309  }
310  publish_clearing_points = (node->count_subscribers("clearing_endpoints") > 0);
311  }
312 
313  clearing_endpoints_->data.clear();
314  clearing_endpoints_->width = clearing_observation.cloud_->width;
315  clearing_endpoints_->height = clearing_observation.cloud_->height;
316  clearing_endpoints_->is_dense = true;
317  clearing_endpoints_->is_bigendian = false;
318 
319  sensor_msgs::PointCloud2Modifier modifier(*clearing_endpoints_);
320  modifier.setPointCloud2Fields(
321  3, "x", 1, sensor_msgs::msg::PointField::FLOAT32,
322  "y", 1, sensor_msgs::msg::PointField::FLOAT32,
323  "z", 1, sensor_msgs::msg::PointField::FLOAT32);
324 
325  sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_x(*clearing_endpoints_, "x");
326  sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_y(*clearing_endpoints_, "y");
327  sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_z(*clearing_endpoints_, "z");
328 
329  // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
330  double map_end_x = origin_x_ + getSizeInMetersX();
331  double map_end_y = origin_y_ + getSizeInMetersY();
332  double map_end_z = origin_z_ + getSizeInMetersZ();
333 
334  sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_), "x");
335  sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_), "y");
336  sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_), "z");
337 
338  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
339  double wpx = *iter_x;
340  double wpy = *iter_y;
341  double wpz = *iter_z;
342 
343  double distance = dist(ox, oy, oz, wpx, wpy, wpz);
344  double scaling_fact = 1.0;
345  scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
346  wpx = scaling_fact * (wpx - ox) + ox;
347  wpy = scaling_fact * (wpy - oy) + oy;
348  wpz = scaling_fact * (wpz - oz) + oz;
349 
350  double a = wpx - ox;
351  double b = wpy - oy;
352  double c = wpz - oz;
353  double t = 1.0;
354  bool wp_outside = false;
355 
356  // we can only raytrace to a maximum z height
357  if (wpz > map_end_z) {
358  // we know we want the vector's z value to be max_z
359  t = std::max(0.0, std::min(t, (map_end_z - 0.01 - oz) / c));
360  wp_outside = true;
361  } else if (wpz < origin_z_) {
362  // and we can only raytrace down to the floor
363  // we know we want the vector's z value to be 0.0
364  t = std::min(t, (origin_z_ - oz) / c);
365  wp_outside = true;
366  }
367 
368  // the minimum value to raytrace from is the origin
369  if (wpx < origin_x_) {
370  t = std::min(t, (origin_x_ - ox) / a);
371  wp_outside = true;
372  }
373  if (wpy < origin_y_) {
374  t = std::min(t, (origin_y_ - oy) / b);
375  wp_outside = true;
376  }
377 
378  // the maximum value to raytrace to is the end of the map
379  if (wpx > map_end_x) {
380  t = std::min(t, (map_end_x - ox) / a);
381  wp_outside = true;
382  }
383  if (wpy > map_end_y) {
384  t = std::min(t, (map_end_y - oy) / b);
385  wp_outside = true;
386  }
387 
388  constexpr double wp_epsilon = 1e-5;
389  if (wp_outside) {
390  if (t > 0.0) {
391  t -= wp_epsilon;
392  } else if (t < 0.0) {
393  t += wp_epsilon;
394  }
395  }
396 
397  wpx = ox + a * t;
398  wpy = oy + b * t;
399  wpz = oz + c * t;
400 
401  double point_x, point_y, point_z;
402  if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z)) {
403  unsigned int cell_raytrace_max_range = cellDistance(clearing_observation.raytrace_max_range_);
404  unsigned int cell_raytrace_min_range = cellDistance(clearing_observation.raytrace_min_range_);
405 
406 
407  // voxel_grid_.markVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z);
408  voxel_grid_.clearVoxelLineInMap(
409  sensor_x, sensor_y, sensor_z, point_x, point_y, point_z,
410  costmap_,
411  unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
412  cell_raytrace_max_range, cell_raytrace_min_range);
413 
415  ox, oy, wpx, wpy, clearing_observation.raytrace_max_range_,
416  clearing_observation.raytrace_min_range_, min_x, min_y,
417  max_x,
418  max_y);
419 
420  if (publish_clearing_points) {
421  *clearing_endpoints_iter_x = wpx;
422  *clearing_endpoints_iter_y = wpy;
423  *clearing_endpoints_iter_z = wpz;
424 
425  ++clearing_endpoints_iter_x;
426  ++clearing_endpoints_iter_y;
427  ++clearing_endpoints_iter_z;
428  }
429  }
430  }
431 
432  if (publish_clearing_points) {
433  clearing_endpoints_->header.frame_id = global_frame_;
434  clearing_endpoints_->header.stamp = clearing_observation.cloud_->header.stamp;
435 
436  clearing_endpoints_pub_->publish(std::move(clearing_endpoints_));
437  }
438 }
439 
440 void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
441 {
442  // project the new origin into the grid
443  int cell_ox, cell_oy;
444  cell_ox = static_cast<int>((new_origin_x - origin_x_) / resolution_);
445  cell_oy = static_cast<int>((new_origin_y - origin_y_) / resolution_);
446 
447  // compute the associated world coordinates for the origin cell
448  // beacuase we want to keep things grid-aligned
449  double new_grid_ox, new_grid_oy;
450  new_grid_ox = origin_x_ + cell_ox * resolution_;
451  new_grid_oy = origin_y_ + cell_oy * resolution_;
452 
453  // To save casting from unsigned int to int a bunch of times
454  int size_x = size_x_;
455  int size_y = size_y_;
456 
457  // we need to compute the overlap of the new and existing windows
458  int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
459  lower_left_x = std::min(std::max(cell_ox, 0), size_x);
460  lower_left_y = std::min(std::max(cell_oy, 0), size_y);
461  upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
462  upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
463 
464  unsigned int cell_size_x = upper_right_x - lower_left_x;
465  unsigned int cell_size_y = upper_right_y - lower_left_y;
466 
467  // we need a map to store the obstacles in the window temporarily
468  unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y];
469  unsigned int * local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
470  unsigned int * voxel_map = voxel_grid_.getData();
471 
472  // copy the local window in the costmap to the local map
474  costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x,
475  cell_size_x,
476  cell_size_y);
478  voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x,
479  cell_size_x,
480  cell_size_y);
481 
482  // we'll reset our maps to unknown space if appropriate
483  resetMaps();
484 
485  // update the origin with the appropriate world coordinates
486  origin_x_ = new_grid_ox;
487  origin_y_ = new_grid_oy;
488 
489  // compute the starting cell location for copying data back in
490  int start_x = lower_left_x - cell_ox;
491  int start_y = lower_left_y - cell_oy;
492 
493  // now we want to copy the overlapping information back into the map, but in its new location
495  local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x,
496  cell_size_y);
498  local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_,
499  cell_size_x,
500  cell_size_y);
501 
502  // make sure to clean up
503  delete[] local_map;
504  delete[] local_voxel_map;
505 }
506 
511 rcl_interfaces::msg::SetParametersResult
513  std::vector<rclcpp::Parameter> parameters)
514 {
515  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
516  rcl_interfaces::msg::SetParametersResult result;
517  bool resize_map_needed = false;
518 
519  for (auto parameter : parameters) {
520  const auto & param_type = parameter.get_type();
521  const auto & param_name = parameter.get_name();
522 
523  if (param_type == ParameterType::PARAMETER_DOUBLE) {
524  if (param_name == name_ + "." + "min_obstacle_height") {
525  min_obstacle_height_ = parameter.as_double();
526  } else if (param_name == name_ + "." + "max_obstacle_height") {
527  max_obstacle_height_ = parameter.as_double();
528  } else if (param_name == name_ + "." + "origin_z") {
529  origin_z_ = parameter.as_double();
530  resize_map_needed = true;
531  } else if (param_name == name_ + "." + "z_resolution") {
532  z_resolution_ = parameter.as_double();
533  resize_map_needed = true;
534  }
535  } else if (param_type == ParameterType::PARAMETER_BOOL) {
536  if (param_name == name_ + "." + "enabled") {
537  enabled_ = parameter.as_bool();
538  current_ = false;
539  } else if (param_name == name_ + "." + "footprint_clearing_enabled") {
540  footprint_clearing_enabled_ = parameter.as_bool();
541  } else if (param_name == name_ + "." + "publish_voxel_map") {
542  RCLCPP_WARN(
543  logger_, "publish voxel map is not a dynamic parameter "
544  "cannot be changed while running. Rejecting parameter update.");
545  continue;
546  }
547 
548  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
549  if (param_name == name_ + "." + "z_voxels") {
550  size_z_ = parameter.as_int();
551  resize_map_needed = true;
552  } else if (param_name == name_ + "." + "unknown_threshold") {
553  unknown_threshold_ = parameter.as_int() + (VOXEL_BITS - size_z_);
554  } else if (param_name == name_ + "." + "mark_threshold") {
555  mark_threshold_ = parameter.as_int();
556  } else if (param_name == name_ + "." + "combination_method") {
557  combination_method_ = combination_method_from_int(parameter.as_int());
558  }
559  }
560  }
561 
562  if (resize_map_needed) {
563  matchSize();
564  }
565 
566  result.successful = true;
567  return result;
568 }
569 
570 } // namespace nav2_costmap_2d
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:221
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:392
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:529
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:524
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:65
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)
Covert world coordinates into map coordinates.
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Covert 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:64