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