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