Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
obstacle_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  * Steve Macenski
38  *********************************************************************/
39 #include "nav2_costmap_2d/obstacle_layer.hpp"
40 
41 #include <algorithm>
42 #include <memory>
43 #include <string>
44 #include <vector>
45 
46 #include "pluginlib/class_list_macros.hpp"
47 #include "sensor_msgs/point_cloud2_iterator.hpp"
48 #include "nav2_costmap_2d/costmap_math.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 
58 using rcl_interfaces::msg::ParameterType;
59 
60 namespace nav2_costmap_2d
61 {
62 
64 {
65  dyn_params_handler_.reset();
66  for (auto & notifier : observation_notifiers_) {
67  notifier.reset();
68  }
69 }
70 
72 {
73  bool track_unknown_space;
74  double transform_tolerance;
75 
76  // The topics that we'll subscribe to from the parameter server
77  std::string topics_string;
78 
79  declareParameter("enabled", rclcpp::ParameterValue(true));
80  declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(true));
81  declareParameter("min_obstacle_height", rclcpp::ParameterValue(0.0));
82  declareParameter("max_obstacle_height", rclcpp::ParameterValue(2.0));
83  declareParameter("combination_method", rclcpp::ParameterValue(1));
84  declareParameter("observation_sources", rclcpp::ParameterValue(std::string("")));
85 
86  auto node = node_.lock();
87  if (!node) {
88  throw std::runtime_error{"Failed to lock node"};
89  }
90 
91  node->get_parameter(name_ + "." + "enabled", enabled_);
92  node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
93  node->get_parameter(name_ + "." + "min_obstacle_height", min_obstacle_height_);
94  node->get_parameter(name_ + "." + "max_obstacle_height", max_obstacle_height_);
95  node->get_parameter(name_ + "." + "combination_method", combination_method_);
96  node->get_parameter("track_unknown_space", track_unknown_space);
97  node->get_parameter("transform_tolerance", transform_tolerance);
98  node->get_parameter(name_ + "." + "observation_sources", topics_string);
99 
100  dyn_params_handler_ = node->add_on_set_parameters_callback(
101  std::bind(
103  this,
104  std::placeholders::_1));
105 
106  RCLCPP_INFO(
107  logger_,
108  "Subscribed to Topics: %s", topics_string.c_str());
109 
110  rolling_window_ = layered_costmap_->isRolling();
111 
112  if (track_unknown_space) {
113  default_value_ = NO_INFORMATION;
114  } else {
115  default_value_ = FREE_SPACE;
116  }
117 
119  current_ = true;
120  was_reset_ = false;
121 
122  global_frame_ = layered_costmap_->getGlobalFrameID();
123 
124  auto sub_opt = rclcpp::SubscriptionOptions();
125  sub_opt.callback_group = callback_group_;
126 
127  // now we need to split the topics based on whitespace which we can use a stringstream for
128  std::stringstream ss(topics_string);
129 
130  std::string source;
131  while (ss >> source) {
132  // get the parameters for the specific topic
133  double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
134  std::string topic, sensor_frame, data_type;
135  bool inf_is_valid, clearing, marking;
136 
137  declareParameter(source + "." + "topic", rclcpp::ParameterValue(source));
138  declareParameter(source + "." + "sensor_frame", rclcpp::ParameterValue(std::string("")));
139  declareParameter(source + "." + "observation_persistence", rclcpp::ParameterValue(0.0));
140  declareParameter(source + "." + "expected_update_rate", rclcpp::ParameterValue(0.0));
141  declareParameter(source + "." + "data_type", rclcpp::ParameterValue(std::string("LaserScan")));
142  declareParameter(source + "." + "min_obstacle_height", rclcpp::ParameterValue(0.0));
143  declareParameter(source + "." + "max_obstacle_height", rclcpp::ParameterValue(0.0));
144  declareParameter(source + "." + "inf_is_valid", rclcpp::ParameterValue(false));
145  declareParameter(source + "." + "marking", rclcpp::ParameterValue(true));
146  declareParameter(source + "." + "clearing", rclcpp::ParameterValue(false));
147  declareParameter(source + "." + "obstacle_max_range", rclcpp::ParameterValue(2.5));
148  declareParameter(source + "." + "obstacle_min_range", rclcpp::ParameterValue(0.0));
149  declareParameter(source + "." + "raytrace_max_range", rclcpp::ParameterValue(3.0));
150  declareParameter(source + "." + "raytrace_min_range", rclcpp::ParameterValue(0.0));
151 
152  node->get_parameter(name_ + "." + source + "." + "topic", topic);
153  node->get_parameter(name_ + "." + source + "." + "sensor_frame", sensor_frame);
154  node->get_parameter(
155  name_ + "." + source + "." + "observation_persistence",
156  observation_keep_time);
157  node->get_parameter(
158  name_ + "." + source + "." + "expected_update_rate",
159  expected_update_rate);
160  node->get_parameter(name_ + "." + source + "." + "data_type", data_type);
161  node->get_parameter(name_ + "." + source + "." + "min_obstacle_height", min_obstacle_height);
162  node->get_parameter(name_ + "." + source + "." + "max_obstacle_height", max_obstacle_height);
163  node->get_parameter(name_ + "." + source + "." + "inf_is_valid", inf_is_valid);
164  node->get_parameter(name_ + "." + source + "." + "marking", marking);
165  node->get_parameter(name_ + "." + source + "." + "clearing", clearing);
166 
167  if (!(data_type == "PointCloud2" || data_type == "LaserScan")) {
168  RCLCPP_FATAL(
169  logger_,
170  "Only topics that use point cloud2s or laser scans are currently supported");
171  throw std::runtime_error(
172  "Only topics that use point cloud2s or laser scans are currently supported");
173  }
174 
175  // get the obstacle range for the sensor
176  double obstacle_max_range, obstacle_min_range;
177  node->get_parameter(name_ + "." + source + "." + "obstacle_max_range", obstacle_max_range);
178  node->get_parameter(name_ + "." + source + "." + "obstacle_min_range", obstacle_min_range);
179 
180  // get the raytrace ranges for the sensor
181  double raytrace_max_range, raytrace_min_range;
182  node->get_parameter(name_ + "." + source + "." + "raytrace_min_range", raytrace_min_range);
183  node->get_parameter(name_ + "." + source + "." + "raytrace_max_range", raytrace_max_range);
184 
185 
186  RCLCPP_DEBUG(
187  logger_,
188  "Creating an observation buffer for source %s, topic %s, frame %s",
189  source.c_str(), topic.c_str(),
190  sensor_frame.c_str());
191 
192  // create an observation buffer
193  observation_buffers_.push_back(
194  std::shared_ptr<ObservationBuffer
195  >(
196  new ObservationBuffer(
197  node, topic, observation_keep_time, expected_update_rate,
198  min_obstacle_height,
199  max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
200  raytrace_min_range, *tf_,
202  sensor_frame, tf2::durationFromSec(transform_tolerance))));
203 
204  // check if we'll add this buffer to our marking observation buffers
205  if (marking) {
206  marking_buffers_.push_back(observation_buffers_.back());
207  }
208 
209  // check if we'll also add this buffer to our clearing observation buffers
210  if (clearing) {
211  clearing_buffers_.push_back(observation_buffers_.back());
212  }
213 
214  RCLCPP_DEBUG(
215  logger_,
216  "Created an observation buffer for source %s, topic %s, global frame: %s, "
217  "expected update rate: %.2f, observation persistence: %.2f",
218  source.c_str(), topic.c_str(),
219  global_frame_.c_str(), expected_update_rate, observation_keep_time);
220 
221  rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
222  custom_qos_profile.depth = 50;
223 
224  // create a callback for the topic
225  if (data_type == "LaserScan") {
226  auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
227  rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
228  sub->unsubscribe();
229 
230  auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
231  *sub, *tf_, global_frame_, 50,
232  node->get_node_logging_interface(),
233  node->get_node_clock_interface(),
234  tf2::durationFromSec(transform_tolerance));
235 
236  if (inf_is_valid) {
237  filter->registerCallback(
238  std::bind(
239  &ObstacleLayer::laserScanValidInfCallback, this, std::placeholders::_1,
240  observation_buffers_.back()));
241 
242  } else {
243  filter->registerCallback(
244  std::bind(
245  &ObstacleLayer::laserScanCallback, this, std::placeholders::_1,
246  observation_buffers_.back()));
247  }
248 
249  observation_subscribers_.push_back(sub);
250 
251  observation_notifiers_.push_back(filter);
252  observation_notifiers_.back()->setTolerance(rclcpp::Duration::from_seconds(0.05));
253 
254  } else {
255  auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
256  rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
257  sub->unsubscribe();
258 
259  if (inf_is_valid) {
260  RCLCPP_WARN(
261  logger_,
262  "obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
263  }
264 
265  auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>>(
266  *sub, *tf_, global_frame_, 50,
267  node->get_node_logging_interface(),
268  node->get_node_clock_interface(),
269  tf2::durationFromSec(transform_tolerance));
270 
271  filter->registerCallback(
272  std::bind(
273  &ObstacleLayer::pointCloud2Callback, this, std::placeholders::_1,
274  observation_buffers_.back()));
275 
276  observation_subscribers_.push_back(sub);
277  observation_notifiers_.push_back(filter);
278  }
279 
280  if (sensor_frame != "") {
281  std::vector<std::string> target_frames;
282  target_frames.push_back(global_frame_);
283  target_frames.push_back(sensor_frame);
284  observation_notifiers_.back()->setTargetFrames(target_frames);
285  }
286  }
287 }
288 
289 rcl_interfaces::msg::SetParametersResult
291  std::vector<rclcpp::Parameter> parameters)
292 {
293  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
294  rcl_interfaces::msg::SetParametersResult result;
295 
296  for (auto parameter : parameters) {
297  const auto & param_type = parameter.get_type();
298  const auto & param_name = parameter.get_name();
299 
300  if (param_type == ParameterType::PARAMETER_DOUBLE) {
301  if (param_name == name_ + "." + "min_obstacle_height") {
302  min_obstacle_height_ = parameter.as_double();
303  } else if (param_name == name_ + "." + "max_obstacle_height") {
304  max_obstacle_height_ = parameter.as_double();
305  }
306  } else if (param_type == ParameterType::PARAMETER_BOOL) {
307  if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
308  enabled_ = parameter.as_bool();
309  if (enabled_) {
310  current_ = false;
311  }
312  } else if (param_name == name_ + "." + "footprint_clearing_enabled") {
313  footprint_clearing_enabled_ = parameter.as_bool();
314  }
315  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
316  if (param_name == name_ + "." + "combination_method") {
317  combination_method_ = parameter.as_int();
318  }
319  }
320  }
321 
322  result.successful = true;
323  return result;
324 }
325 
326 void
328  sensor_msgs::msg::LaserScan::ConstSharedPtr message,
329  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
330 {
331  // project the laser into a point cloud
332  sensor_msgs::msg::PointCloud2 cloud;
333  cloud.header = message->header;
334 
335  // project the scan into a point cloud
336  try {
337  projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
338  } catch (tf2::TransformException & ex) {
339  RCLCPP_WARN(
340  logger_,
341  "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
342  global_frame_.c_str(),
343  ex.what());
344  projector_.projectLaser(*message, cloud);
345  } catch (std::runtime_error & ex) {
346  RCLCPP_WARN(
347  logger_,
348  "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
349  " Ignore this message. what(): %s",
350  ex.what());
351  return;
352  }
353 
354  // buffer the point cloud
355  buffer->lock();
356  buffer->bufferCloud(cloud);
357  buffer->unlock();
358 }
359 
360 void
362  sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
363  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
364 {
365  // Filter positive infinities ("Inf"s) to max_range.
366  float epsilon = 0.0001; // a tenth of a millimeter
367  sensor_msgs::msg::LaserScan message = *raw_message;
368  for (size_t i = 0; i < message.ranges.size(); i++) {
369  float range = message.ranges[i];
370  if (!std::isfinite(range) && range > 0) {
371  message.ranges[i] = message.range_max - epsilon;
372  }
373  }
374 
375  // project the laser into a point cloud
376  sensor_msgs::msg::PointCloud2 cloud;
377  cloud.header = message.header;
378 
379  // project the scan into a point cloud
380  try {
381  projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
382  } catch (tf2::TransformException & ex) {
383  RCLCPP_WARN(
384  logger_,
385  "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
386  global_frame_.c_str(), ex.what());
387  projector_.projectLaser(message, cloud);
388  } catch (std::runtime_error & ex) {
389  RCLCPP_WARN(
390  logger_,
391  "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
392  " Ignore this message. what(): %s",
393  ex.what());
394  return;
395  }
396 
397  // buffer the point cloud
398  buffer->lock();
399  buffer->bufferCloud(cloud);
400  buffer->unlock();
401 }
402 
403 void
405  sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
406  const std::shared_ptr<ObservationBuffer> & buffer)
407 {
408  // buffer the point cloud
409  buffer->lock();
410  buffer->bufferCloud(*message);
411  buffer->unlock();
412 }
413 
414 void
416  double robot_x, double robot_y, double robot_yaw, double * min_x,
417  double * min_y, double * max_x, double * max_y)
418 {
419  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
420  if (rolling_window_) {
421  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
422  }
423  if (!enabled_) {
424  return;
425  }
426  useExtraBounds(min_x, min_y, max_x, max_y);
427 
428  bool current = true;
429  std::vector<Observation> observations, clearing_observations;
430 
431  // get the marking observations
432  current = current && getMarkingObservations(observations);
433 
434  // get the clearing observations
435  current = current && getClearingObservations(clearing_observations);
436 
437  // update the global current status
438  current_ = current;
439 
440  // raytrace freespace
441  for (unsigned int i = 0; i < clearing_observations.size(); ++i) {
442  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
443  }
444 
445  // place the new obstacles into a priority queue... each with a priority of zero to begin with
446  for (std::vector<Observation>::const_iterator it = observations.begin();
447  it != observations.end(); ++it)
448  {
449  const Observation & obs = *it;
450 
451  const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
452 
453  double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
454  double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
455 
456  sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
457  sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
458  sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud, "z");
459 
460  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
461  double px = *iter_x, py = *iter_y, pz = *iter_z;
462 
463  // if the obstacle is too low, we won't add it
464  if (pz < min_obstacle_height_) {
465  RCLCPP_DEBUG(logger_, "The point is too low");
466  continue;
467  }
468 
469  // if the obstacle is too high or too far away from the robot we won't add it
470  if (pz > max_obstacle_height_) {
471  RCLCPP_DEBUG(logger_, "The point is too high");
472  continue;
473  }
474 
475  // compute the squared distance from the hitpoint to the pointcloud's origin
476  double sq_dist =
477  (px -
478  obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y) +
479  (pz - obs.origin_.z) * (pz - obs.origin_.z);
480 
481  // if the point is far enough away... we won't consider it
482  if (sq_dist >= sq_obstacle_max_range) {
483  RCLCPP_DEBUG(logger_, "The point is too far away");
484  continue;
485  }
486 
487  // if the point is too close, do not conisder it
488  if (sq_dist < sq_obstacle_min_range) {
489  RCLCPP_DEBUG(logger_, "The point is too close");
490  continue;
491  }
492 
493  // now we need to compute the map coordinates for the observation
494  unsigned int mx, my;
495  if (!worldToMap(px, py, mx, my)) {
496  RCLCPP_DEBUG(logger_, "Computing map coords failed");
497  continue;
498  }
499 
500  unsigned int index = getIndex(mx, my);
501  costmap_[index] = LETHAL_OBSTACLE;
502  touch(px, py, min_x, min_y, max_x, max_y);
503  }
504  }
505 
506  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
507 }
508 
509 void
511  double robot_x, double robot_y, double robot_yaw,
512  double * min_x, double * min_y,
513  double * max_x,
514  double * max_y)
515 {
516  if (!footprint_clearing_enabled_) {return;}
517  transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
518 
519  for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
520  touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
521  }
522 }
523 
524 void
526  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j,
527  int max_i,
528  int max_j)
529 {
530  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
531  if (!enabled_) {
532  return;
533  }
534 
535  // if not current due to reset, set current now after clearing
536  if (!current_ && was_reset_) {
537  was_reset_ = false;
538  current_ = true;
539  }
540 
541  if (footprint_clearing_enabled_) {
542  setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
543  }
544 
545  switch (combination_method_) {
546  case 0: // Overwrite
547  updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
548  break;
549  case 1: // Maximum
550  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
551  break;
552  default: // Nothing
553  break;
554  }
555 }
556 
557 void
558 ObstacleLayer::addStaticObservation(
560  bool marking, bool clearing)
561 {
562  if (marking) {
563  static_marking_observations_.push_back(obs);
564  }
565  if (clearing) {
566  static_clearing_observations_.push_back(obs);
567  }
568 }
569 
570 void
571 ObstacleLayer::clearStaticObservations(bool marking, bool clearing)
572 {
573  if (marking) {
574  static_marking_observations_.clear();
575  }
576  if (clearing) {
577  static_clearing_observations_.clear();
578  }
579 }
580 
581 bool
582 ObstacleLayer::getMarkingObservations(std::vector<Observation> & marking_observations) const
583 {
584  bool current = true;
585  // get the marking observations
586  for (unsigned int i = 0; i < marking_buffers_.size(); ++i) {
587  marking_buffers_[i]->lock();
588  marking_buffers_[i]->getObservations(marking_observations);
589  current = marking_buffers_[i]->isCurrent() && current;
590  marking_buffers_[i]->unlock();
591  }
592  marking_observations.insert(
593  marking_observations.end(),
594  static_marking_observations_.begin(), static_marking_observations_.end());
595  return current;
596 }
597 
598 bool
599 ObstacleLayer::getClearingObservations(std::vector<Observation> & clearing_observations) const
600 {
601  bool current = true;
602  // get the clearing observations
603  for (unsigned int i = 0; i < clearing_buffers_.size(); ++i) {
604  clearing_buffers_[i]->lock();
605  clearing_buffers_[i]->getObservations(clearing_observations);
606  current = clearing_buffers_[i]->isCurrent() && current;
607  clearing_buffers_[i]->unlock();
608  }
609  clearing_observations.insert(
610  clearing_observations.end(),
611  static_clearing_observations_.begin(), static_clearing_observations_.end());
612  return current;
613 }
614 
615 void
617  const Observation & clearing_observation, double * min_x,
618  double * min_y,
619  double * max_x,
620  double * max_y)
621 {
622  double ox = clearing_observation.origin_.x;
623  double oy = clearing_observation.origin_.y;
624  const sensor_msgs::msg::PointCloud2 & cloud = *(clearing_observation.cloud_);
625 
626  // get the map coordinates of the origin of the sensor
627  unsigned int x0, y0;
628  if (!worldToMap(ox, oy, x0, y0)) {
629  RCLCPP_WARN(
630  logger_,
631  "Sensor origin at (%.2f, %.2f) is out of map bounds (%.2f, %.2f) to (%.2f, %.2f). "
632  "The costmap cannot raytrace for it.",
633  ox, oy,
634  origin_x_, origin_y_,
635  origin_x_ + getSizeInMetersX(), origin_y_ + getSizeInMetersY());
636  return;
637  }
638 
639  // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
640  double origin_x = origin_x_, origin_y = origin_y_;
641  double map_end_x = origin_x + size_x_ * resolution_;
642  double map_end_y = origin_y + size_y_ * resolution_;
643 
644 
645  touch(ox, oy, min_x, min_y, max_x, max_y);
646 
647  // for each point in the cloud, we want to trace a line from the origin
648  // and clear obstacles along it
649  sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud, "x");
650  sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud, "y");
651 
652  for (; iter_x != iter_x.end(); ++iter_x, ++iter_y) {
653  double wx = *iter_x;
654  double wy = *iter_y;
655 
656  // now we also need to make sure that the enpoint we're raytracing
657  // to isn't off the costmap and scale if necessary
658  double a = wx - ox;
659  double b = wy - oy;
660 
661  // the minimum value to raytrace from is the origin
662  if (wx < origin_x) {
663  double t = (origin_x - ox) / a;
664  wx = origin_x;
665  wy = oy + b * t;
666  }
667  if (wy < origin_y) {
668  double t = (origin_y - oy) / b;
669  wx = ox + a * t;
670  wy = origin_y;
671  }
672 
673  // the maximum value to raytrace to is the end of the map
674  if (wx > map_end_x) {
675  double t = (map_end_x - ox) / a;
676  wx = map_end_x - .001;
677  wy = oy + b * t;
678  }
679  if (wy > map_end_y) {
680  double t = (map_end_y - oy) / b;
681  wx = ox + a * t;
682  wy = map_end_y - .001;
683  }
684 
685  // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint
686  unsigned int x1, y1;
687 
688  // check for legality just in case
689  if (!worldToMap(wx, wy, x1, y1)) {
690  continue;
691  }
692 
693  unsigned int cell_raytrace_max_range = cellDistance(clearing_observation.raytrace_max_range_);
694  unsigned int cell_raytrace_min_range = cellDistance(clearing_observation.raytrace_min_range_);
695  MarkCell marker(costmap_, FREE_SPACE);
696  // and finally... we can execute our trace to clear obstacles along that line
697  raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_max_range, cell_raytrace_min_range);
698 
700  ox, oy, wx, wy, clearing_observation.raytrace_max_range_,
701  clearing_observation.raytrace_min_range_, min_x, min_y, max_x,
702  max_y);
703  }
704 }
705 
706 void
708 {
709  for (auto & notifier : observation_notifiers_) {
710  notifier->clear();
711  }
712 
713  // if we're stopped we need to re-subscribe to topics
714  for (unsigned int i = 0; i < observation_subscribers_.size(); ++i) {
715  if (observation_subscribers_[i] != NULL) {
716  observation_subscribers_[i]->subscribe();
717  }
718  }
720 }
721 
722 void
724 {
725  for (unsigned int i = 0; i < observation_subscribers_.size(); ++i) {
726  if (observation_subscribers_[i] != NULL) {
727  observation_subscribers_[i]->unsubscribe();
728  }
729  }
730 }
731 
732 void
734  double ox, double oy, double wx, double wy, double max_range, double min_range,
735  double * min_x, double * min_y, double * max_x, double * max_y)
736 {
737  double dx = wx - ox, dy = wy - oy;
738  double full_distance = hypot(dx, dy);
739  if (full_distance < min_range) {
740  return;
741  }
742  double scale = std::min(1.0, max_range / full_distance);
743  double ex = ox + dx * scale, ey = oy + dy * scale;
744  touch(ex, ey, min_x, min_y, max_x, max_y);
745 }
746 
747 void
749 {
750  resetMaps();
752  current_ = false;
753  was_reset_ = true;
754 }
755 
756 void
758 {
759  for (unsigned int i = 0; i < observation_buffers_.size(); ++i) {
760  if (observation_buffers_[i]) {
761  observation_buffers_[i]->resetLastUpdated();
762  }
763  }
764 }
765 
766 } // namespace nav2_costmap_2d
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:211
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX, unsigned int min_length=0)
Raytrace a line and apply some action at each step.
Definition: costmap_2d.hpp:430
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
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
Definition: costmap_2d.cpp:330
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
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:516
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:511
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:255
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.
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.
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.hpp:47
Takes in laser and pointcloud data to populate into 2D costmap.
void pointCloud2Callback(sensor_msgs::msg::PointCloud2::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
virtual void activate()
Activate the layer.
std::vector< std::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
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.
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
void laserScanCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
void resetBuffersLastUpdated()
triggers the update of observations buffer
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
void laserScanValidInfCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_...
std::vector< std::shared_ptr< message_filters::SubscriberBase< rclcpp_lifecycle::LifecycleNode > > > observation_subscribers_
Used for the observation message filters.
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 deactivate()
Deactivate the layer.
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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual ~ObstacleLayer()
A destructor.
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
virtual void onInitialize()
Initialization process of layer on startup.
double min_obstacle_height_
Max Obstacle Height.
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
double max_obstacle_height_
Max Obstacle Height.
virtual void reset()
Reset this costmap.
virtual void raytraceFreespace(const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
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 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