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