Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
range_sensor_layer.cpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 David V. Lu!!
5  * Copyright (c) 2020, Bytes Robotics
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 the copyright holder 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 HOLDER 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 
36 #include <angles/angles.h>
37 #include <algorithm>
38 #include <list>
39 #include <limits>
40 #include <string>
41 #include <vector>
42 
43 #include "pluginlib/class_list_macros.hpp"
44 #include "geometry_msgs/msg/point_stamped.hpp"
45 #include "nav2_costmap_2d/range_sensor_layer.hpp"
46 
48 
49 using nav2_costmap_2d::LETHAL_OBSTACLE;
50 using nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
51 using nav2_costmap_2d::NO_INFORMATION;
52 
53 using namespace std::literals::chrono_literals;
54 
55 namespace nav2_costmap_2d
56 {
57 
58 RangeSensorLayer::RangeSensorLayer() {}
59 
60 void RangeSensorLayer::onInitialize()
61 {
62  current_ = true;
63  was_reset_ = false;
64  buffered_readings_ = 0;
65  last_reading_time_ = clock_->now();
66  default_value_ = to_cost(0.5);
67 
68  matchSize();
69  resetRange();
70 
71  auto node = node_.lock();
72  if (!node) {
73  throw std::runtime_error{"Failed to lock node"};
74  }
75 
76  declareParameter("enabled", rclcpp::ParameterValue(true));
77  node->get_parameter(name_ + "." + "enabled", enabled_);
78  declareParameter("phi", rclcpp::ParameterValue(1.2));
79  node->get_parameter(name_ + "." + "phi", phi_v_);
80  declareParameter("inflate_cone", rclcpp::ParameterValue(1.0));
81  node->get_parameter(name_ + "." + "inflate_cone", inflate_cone_);
82  declareParameter("no_readings_timeout", rclcpp::ParameterValue(0.0));
83  node->get_parameter(name_ + "." + "no_readings_timeout", no_readings_timeout_);
84  declareParameter("clear_threshold", rclcpp::ParameterValue(0.2));
85  node->get_parameter(name_ + "." + "clear_threshold", clear_threshold_);
86  declareParameter("mark_threshold", rclcpp::ParameterValue(0.8));
87  node->get_parameter(name_ + "." + "mark_threshold", mark_threshold_);
88  declareParameter("clear_on_max_reading", rclcpp::ParameterValue(false));
89  node->get_parameter(name_ + "." + "clear_on_max_reading", clear_on_max_reading_);
90 
91  double temp_tf_tol = 0.0;
92  node->get_parameter("transform_tolerance", temp_tf_tol);
93  transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
94 
95  std::vector<std::string> topic_names{};
96  declareParameter("topics", rclcpp::ParameterValue(topic_names));
97  node->get_parameter(name_ + "." + "topics", topic_names);
98 
99  InputSensorType input_sensor_type = InputSensorType::ALL;
100  std::string sensor_type_name;
101  declareParameter("input_sensor_type", rclcpp::ParameterValue("ALL"));
102  node->get_parameter(name_ + "." + "input_sensor_type", sensor_type_name);
103 
104  std::transform(
105  sensor_type_name.begin(), sensor_type_name.end(),
106  sensor_type_name.begin(), ::toupper);
107  RCLCPP_INFO(
108  logger_, "%s: %s as input_sensor_type given",
109  name_.c_str(), sensor_type_name.c_str());
110 
111  if (sensor_type_name == "VARIABLE") {
112  input_sensor_type = InputSensorType::VARIABLE;
113  } else if (sensor_type_name == "FIXED") {
114  input_sensor_type = InputSensorType::FIXED;
115  } else if (sensor_type_name == "ALL") {
116  input_sensor_type = InputSensorType::ALL;
117  } else {
118  RCLCPP_ERROR(
119  logger_, "%s: Invalid input sensor type: %s. Defaulting to ALL.",
120  name_.c_str(), sensor_type_name.c_str());
121  }
122 
123  // Validate topic names list: it must be a (normally non-empty) list of strings
124  if (topic_names.empty()) {
125  RCLCPP_FATAL(
126  logger_, "Invalid topic names list: it must"
127  "be a non-empty list of strings");
128  return;
129  }
130 
131  // Traverse the topic names list subscribing to all of them with the same callback method
132  for (auto & topic_name : topic_names) {
133  topic_name = joinWithParentNamespace(topic_name);
134  if (input_sensor_type == InputSensorType::VARIABLE) {
135  processRangeMessageFunc_ = std::bind(
136  &RangeSensorLayer::processVariableRangeMsg, this,
137  std::placeholders::_1);
138  } else if (input_sensor_type == InputSensorType::FIXED) {
139  processRangeMessageFunc_ = std::bind(
140  &RangeSensorLayer::processFixedRangeMsg, this,
141  std::placeholders::_1);
142  } else if (input_sensor_type == InputSensorType::ALL) {
143  processRangeMessageFunc_ = std::bind(
144  &RangeSensorLayer::processRangeMsg, this,
145  std::placeholders::_1);
146  } else {
147  RCLCPP_ERROR(
148  logger_,
149  "%s: Invalid input sensor type: %s. Did you make a new type"
150  "and forgot to choose the subscriber for it?",
151  name_.c_str(), sensor_type_name.c_str());
152  }
153  range_subs_.push_back(
154  node->create_subscription<sensor_msgs::msg::Range>(
155  topic_name, rclcpp::SensorDataQoS(), std::bind(
156  &RangeSensorLayer::bufferIncomingRangeMsg, this,
157  std::placeholders::_1)));
158 
159  RCLCPP_INFO(
160  logger_, "RangeSensorLayer: subscribed to "
161  "topic %s", range_subs_.back()->get_topic_name());
162  }
163  global_frame_ = layered_costmap_->getGlobalFrameID();
164 }
165 
166 
167 double RangeSensorLayer::gamma(double theta)
168 {
169  if (fabs(theta) > max_angle_) {
170  return 0.0;
171  } else {
172  return 1 - pow(theta / max_angle_, 2);
173  }
174 }
175 
176 double RangeSensorLayer::delta(double phi)
177 {
178  return 1 - (1 + tanh(2 * (phi - phi_v_))) / 2;
179 }
180 
181 void RangeSensorLayer::get_deltas(double angle, double * dx, double * dy)
182 {
183  double ta = tan(angle);
184  if (ta == 0) {
185  *dx = 0;
186  } else {
187  *dx = resolution_ / ta;
188  }
189 
190  *dx = copysign(*dx, cos(angle));
191  *dy = copysign(resolution_, sin(angle));
192 }
193 
194 double RangeSensorLayer::sensor_model(double r, double phi, double theta)
195 {
196  double lbda = delta(phi) * gamma(theta);
197 
198  double delta = resolution_;
199 
200  if (phi >= 0.0 && phi < r - 2 * delta * r) {
201  return (1 - lbda) * (0.5);
202  } else if (phi < r - delta * r) {
203  return lbda * 0.5 * pow((phi - (r - 2 * delta * r)) / (delta * r), 2) +
204  (1 - lbda) * .5;
205  } else if (phi < r + delta * r) {
206  double J = (r - phi) / (delta * r);
207  return lbda * ((1 - (0.5) * pow(J, 2)) - 0.5) + 0.5;
208  } else {
209  return 0.5;
210  }
211 }
212 
213 void RangeSensorLayer::bufferIncomingRangeMsg(
214  const sensor_msgs::msg::Range::SharedPtr range_message)
215 {
216  range_message_mutex_.lock();
217  range_msgs_buffer_.push_back(*range_message);
218  range_message_mutex_.unlock();
219 }
220 
221 void RangeSensorLayer::updateCostmap()
222 {
223  std::list<sensor_msgs::msg::Range> range_msgs_buffer_copy;
224 
225  range_message_mutex_.lock();
226  range_msgs_buffer_copy = std::list<sensor_msgs::msg::Range>(range_msgs_buffer_);
227  range_msgs_buffer_.clear();
228  range_message_mutex_.unlock();
229 
230  for (auto & range_msgs_it : range_msgs_buffer_copy) {
231  processRangeMessageFunc_(range_msgs_it);
232  }
233 }
234 
235 void RangeSensorLayer::processRangeMsg(sensor_msgs::msg::Range & range_message)
236 {
237  if (range_message.min_range == range_message.max_range) {
238  processFixedRangeMsg(range_message);
239  } else {
240  processVariableRangeMsg(range_message);
241  }
242 }
243 
244 void RangeSensorLayer::processFixedRangeMsg(sensor_msgs::msg::Range & range_message)
245 {
246  if (!std::isinf(range_message.range)) {
247  RCLCPP_ERROR(
248  logger_,
249  "Fixed distance ranger (min_range == max_range) in frame %s sent invalid value. "
250  "Only -Inf (== object detected) and Inf (== no object detected) are valid.",
251  range_message.header.frame_id.c_str());
252  return;
253  }
254 
255  bool clear_sensor_cone = false;
256 
257  if (range_message.range > 0) { // +inf
258  if (!clear_on_max_reading_) {
259  return; // no clearing at all
260  }
261  clear_sensor_cone = true;
262  }
263 
264  range_message.range = range_message.min_range;
265 
266  updateCostmap(range_message, clear_sensor_cone);
267 }
268 
269 void RangeSensorLayer::processVariableRangeMsg(sensor_msgs::msg::Range & range_message)
270 {
271  if (range_message.range < range_message.min_range || range_message.range >
272  range_message.max_range)
273  {
274  return;
275  }
276 
277  bool clear_sensor_cone = false;
278 
279  if (range_message.range >= range_message.max_range && clear_on_max_reading_) {
280  clear_sensor_cone = true;
281  }
282 
283  updateCostmap(range_message, clear_sensor_cone);
284 }
285 
286 void RangeSensorLayer::updateCostmap(
287  sensor_msgs::msg::Range & range_message,
288  bool clear_sensor_cone)
289 {
290  max_angle_ = range_message.field_of_view / 2;
291 
292  geometry_msgs::msg::PointStamped in, out;
293  in.header.stamp = range_message.header.stamp;
294  in.header.frame_id = range_message.header.frame_id;
295 
296  if (!tf_->canTransform(
297  in.header.frame_id, global_frame_,
298  tf2_ros::fromMsg(in.header.stamp),
299  tf2_ros::fromRclcpp(transform_tolerance_)))
300  {
301  RCLCPP_INFO(
302  logger_, "Range sensor layer can't transform from %s to %s",
303  global_frame_.c_str(), in.header.frame_id.c_str());
304  return;
305  }
306 
307  tf_->transform(in, out, global_frame_, transform_tolerance_);
308 
309  double ox = out.point.x, oy = out.point.y;
310 
311  in.point.x = range_message.range;
312 
313  tf_->transform(in, out, global_frame_, transform_tolerance_);
314 
315  double tx = out.point.x, ty = out.point.y;
316 
317  // calculate target props
318  double dx = tx - ox, dy = ty - oy, theta = atan2(dy, dx), d = sqrt(dx * dx + dy * dy);
319 
320  // Integer Bounds of Update
321  int bx0, by0, bx1, by1;
322 
323  // Triangle that will be really updated; the other cells within bounds are ignored
324  // This triangle is formed by the origin and left and right sides of sonar cone
325  int Ox, Oy, Ax, Ay, Bx, By;
326 
327  // Bounds includes the origin
328  worldToMapNoBounds(ox, oy, Ox, Oy);
329  bx1 = bx0 = Ox;
330  by1 = by0 = Oy;
331  touch(ox, oy, &min_x_, &min_y_, &max_x_, &max_y_);
332 
333  // Update Map with Target Point
334  unsigned int aa, ab;
335  if (worldToMap(tx, ty, aa, ab)) {
336  setCost(aa, ab, 233);
337  touch(tx, ty, &min_x_, &min_y_, &max_x_, &max_y_);
338  }
339 
340  double mx, my;
341 
342  // Update left side of sonar cone
343  mx = ox + cos(theta - max_angle_) * d * 1.2;
344  my = oy + sin(theta - max_angle_) * d * 1.2;
345  worldToMapNoBounds(mx, my, Ax, Ay);
346  bx0 = std::min(bx0, Ax);
347  bx1 = std::max(bx1, Ax);
348  by0 = std::min(by0, Ay);
349  by1 = std::max(by1, Ay);
350  touch(mx, my, &min_x_, &min_y_, &max_x_, &max_y_);
351 
352  // Update right side of sonar cone
353  mx = ox + cos(theta + max_angle_) * d * 1.2;
354  my = oy + sin(theta + max_angle_) * d * 1.2;
355 
356  worldToMapNoBounds(mx, my, Bx, By);
357  bx0 = std::min(bx0, Bx);
358  bx1 = std::max(bx1, Bx);
359  by0 = std::min(by0, By);
360  by1 = std::max(by1, By);
361  touch(mx, my, &min_x_, &min_y_, &max_x_, &max_y_);
362 
363  // Limit Bounds to Grid
364  bx0 = std::max(0, bx0);
365  by0 = std::max(0, by0);
366  bx1 = std::min(static_cast<int>(size_x_), bx1);
367  by1 = std::min(static_cast<int>(size_y_), by1);
368 
369  for (unsigned int x = bx0; x <= (unsigned int)bx1; x++) {
370  for (unsigned int y = by0; y <= (unsigned int)by1; y++) {
371  bool update_xy_cell = true;
372 
373  // Unless inflate_cone_ is set to 100 %, we update cells only within the
374  // (partially inflated) sensor cone, projected on the costmap as a triangle.
375  // 0 % corresponds to just the triangle, but if your sensor fov is very
376  // narrow, the covered area can become zero due to cell discretization.
377  // See wiki description for more details
378  if (inflate_cone_ < 1.0) {
379  // Determine barycentric coordinates
380  int w0 = orient2d(Ax, Ay, Bx, By, x, y);
381  int w1 = orient2d(Bx, By, Ox, Oy, x, y);
382  int w2 = orient2d(Ox, Oy, Ax, Ay, x, y);
383 
384  // Barycentric coordinates inside area threshold; this is not mathematically
385  // sound at all, but it works!
386  float bcciath = -static_cast<float>(inflate_cone_) * area(Ax, Ay, Bx, By, Ox, Oy);
387  update_xy_cell = w0 >= bcciath && w1 >= bcciath && w2 >= bcciath;
388  }
389 
390  if (update_xy_cell) {
391  double wx, wy;
392  mapToWorld(x, y, wx, wy);
393  update_cell(ox, oy, theta, range_message.range, wx, wy, clear_sensor_cone);
394  }
395  }
396  }
397 
398  buffered_readings_++;
399  last_reading_time_ = clock_->now();
400 }
401 
402 void RangeSensorLayer::update_cell(
403  double ox, double oy, double ot, double r,
404  double nx, double ny, bool clear)
405 {
406  unsigned int x, y;
407  if (worldToMap(nx, ny, x, y)) {
408  double dx = nx - ox, dy = ny - oy;
409  double theta = atan2(dy, dx) - ot;
410  theta = angles::normalize_angle(theta);
411  double phi = sqrt(dx * dx + dy * dy);
412  double sensor = 0.0;
413  if (!clear) {
414  sensor = sensor_model(r, phi, theta);
415  }
416  double prior = to_prob(getCost(x, y));
417  double prob_occ = sensor * prior;
418  double prob_not = (1 - sensor) * (1 - prior);
419  double new_prob = prob_occ / (prob_occ + prob_not);
420 
421  RCLCPP_DEBUG(
422  logger_,
423  "%f %f | %f %f = %f", dx, dy, theta, phi, sensor);
424  RCLCPP_DEBUG(
425  logger_,
426  "%f | %f %f | %f", prior, prob_occ, prob_not, new_prob);
427  unsigned char c = to_cost(new_prob);
428  setCost(x, y, c);
429  }
430 }
431 
432 void RangeSensorLayer::resetRange()
433 {
434  min_x_ = min_y_ = std::numeric_limits<double>::max();
435  max_x_ = max_y_ = -std::numeric_limits<double>::max();
436 }
437 
438 void RangeSensorLayer::updateBounds(
439  double robot_x, double robot_y,
440  double robot_yaw, double * min_x, double * min_y,
441  double * max_x, double * max_y)
442 {
443  robot_yaw = 0 + robot_yaw; // Avoid error if variable not in use
444  if (layered_costmap_->isRolling()) {
445  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
446  }
447 
448  updateCostmap();
449 
450  *min_x = std::min(*min_x, min_x_);
451  *min_y = std::min(*min_y, min_y_);
452  *max_x = std::max(*max_x, max_x_);
453  *max_y = std::max(*max_y, max_y_);
454 
455  resetRange();
456 
457  if (!enabled_) {
458  current_ = true;
459  return;
460  }
461 
462  if (buffered_readings_ == 0) {
463  if (no_readings_timeout_ > 0.0 &&
464  (clock_->now() - last_reading_time_).seconds() >
465  no_readings_timeout_)
466  {
467  RCLCPP_WARN(
468  logger_,
469  "No range readings received for %.2f seconds, while expected at least every %.2f seconds.",
470  (clock_->now() - last_reading_time_).seconds(),
471  no_readings_timeout_);
472  current_ = false;
473  }
474  }
475 }
476 
477 void RangeSensorLayer::updateCosts(
478  nav2_costmap_2d::Costmap2D & master_grid,
479  int min_i, int min_j, int max_i, int max_j)
480 {
481  if (!enabled_) {
482  return;
483  }
484 
485  unsigned char * master_array = master_grid.getCharMap();
486  unsigned int span = master_grid.getSizeInCellsX();
487  unsigned char clear = to_cost(clear_threshold_), mark = to_cost(mark_threshold_);
488 
489  for (int j = min_j; j < max_j; j++) {
490  unsigned int it = j * span + min_i;
491  for (int i = min_i; i < max_i; i++) {
492  unsigned char prob = costmap_[it];
493  unsigned char current;
494  if (prob == nav2_costmap_2d::NO_INFORMATION) {
495  it++;
496  continue;
497  } else if (prob > mark) {
498  current = nav2_costmap_2d::LETHAL_OBSTACLE;
499  } else if (prob < clear) {
500  current = nav2_costmap_2d::FREE_SPACE;
501  } else {
502  it++;
503  continue;
504  }
505 
506  unsigned char old_cost = master_array[it];
507 
508  if (old_cost == NO_INFORMATION || old_cost < current) {
509  master_array[it] = current;
510  }
511  it++;
512  }
513  }
514 
515  buffered_readings_ = 0;
516 
517  // if not current due to reset, set current now after clearing
518  if (!current_ && was_reset_) {
519  was_reset_ = false;
520  current_ = true;
521  }
522 }
523 
524 void RangeSensorLayer::reset()
525 {
526  RCLCPP_DEBUG(logger_, "Resetting range sensor layer...");
527  deactivate();
528  resetMaps();
529  was_reset_ = true;
530  activate();
531 }
532 
533 void RangeSensorLayer::deactivate()
534 {
535  range_msgs_buffer_.clear();
536 }
537 
538 void RangeSensorLayer::activate()
539 {
540  range_msgs_buffer_.clear();
541 }
542 
543 } // 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 char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
Takes in IR/Sonar/similar point measurement sensors and populates in costmap.