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