range_sensor_layer.cpp
Go to the documentation of this file.
1 // Copyright 2018 David V. Lu!!
3 #include <boost/algorithm/string.hpp>
4 #include <geometry_msgs/PointStamped.h>
6 #include <angles/angles.h>
7 #include <algorithm>
8 #include <list>
9 #include <limits>
10 #include <string>
11 
13 
14 using costmap_2d::NO_INFORMATION;
15 
16 namespace range_sensor_layer
17 {
18 
19 RangeSensorLayer::RangeSensorLayer() {}
20 
21 void RangeSensorLayer::onInitialize()
22 {
23  ros::NodeHandle nh("~/" + name_);
24  current_ = true;
25  buffered_readings_ = 0;
26  last_reading_time_ = ros::Time::now();
27  default_value_ = to_cost(0.5);
28 
29  matchSize();
30  resetRange();
31 
32  // Default topic names list contains a single topic: /sonar
33  // We use the XmlRpcValue constructor that takes a XML string and reading start offset
34  const char* xml = "<value><array><data><value>/sonar</value></data></array></value>";
35  int zero_offset = 0;
36  std::string topics_ns;
37  XmlRpc::XmlRpcValue topic_names(xml, &zero_offset);
38 
39  nh.param("ns", topics_ns, std::string());
40  nh.param("topics", topic_names, topic_names);
41 
42  InputSensorType input_sensor_type = ALL;
43  std::string sensor_type_name;
44  nh.param("input_sensor_type", sensor_type_name, std::string("ALL"));
45 
46  boost::to_upper(sensor_type_name);
47  ROS_INFO("%s: %s as input_sensor_type given", name_.c_str(), sensor_type_name.c_str());
48 
49  if (sensor_type_name == "VARIABLE")
50  input_sensor_type = VARIABLE;
51  else if (sensor_type_name == "FIXED")
52  input_sensor_type = FIXED;
53  else if (sensor_type_name == "ALL")
54  input_sensor_type = ALL;
55  else
56  {
57  ROS_ERROR("%s: Invalid input sensor type: %s", name_.c_str(), sensor_type_name.c_str());
58  }
59 
60  // Validate topic names list: it must be a (normally non-empty) list of strings
61  if ((topic_names.valid() == false) || (topic_names.getType() != XmlRpc::XmlRpcValue::TypeArray))
62  {
63  ROS_ERROR("Invalid topic names list: it must be a non-empty list of strings");
64  return;
65  }
66 
67  if (topic_names.size() < 1)
68  {
69  // This could be an error, but I keep it as it can be useful for debug
70  ROS_WARN("Empty topic names list: range sensor layer will have no effect on costmap");
71  }
72 
73  // Traverse the topic names list subscribing to all of them with the same callback method
74  for (int i = 0; i < topic_names.size(); i++)
75  {
76  if (topic_names[i].getType() != XmlRpc::XmlRpcValue::TypeString)
77  {
78  ROS_WARN("Invalid topic names list: element %d is not a string, so it will be ignored", i);
79  }
80  else
81  {
82  std::string topic_name(topics_ns);
83  if ((topic_name.size() > 0) && (topic_name.at(topic_name.size() - 1) != '/'))
84  topic_name += "/";
85  topic_name += static_cast<std::string>(topic_names[i]);
86 
87  if (input_sensor_type == VARIABLE)
88  processRangeMessageFunc_ = boost::bind(&RangeSensorLayer::processVariableRangeMsg, this, _1);
89  else if (input_sensor_type == FIXED)
90  processRangeMessageFunc_ = boost::bind(&RangeSensorLayer::processFixedRangeMsg, this, _1);
91  else if (input_sensor_type == ALL)
92  processRangeMessageFunc_ = boost::bind(&RangeSensorLayer::processRangeMsg, this, _1);
93  else
94  {
95  ROS_ERROR(
96  "%s: Invalid input sensor type: %s. Did you make a new type and forgot to choose the subscriber for it?",
97  name_.c_str(), sensor_type_name.c_str());
98  }
99 
100  range_subs_.push_back(nh.subscribe<sensor_msgs::Range>(topic_name, 100,
101  boost::bind(&RangeSensorLayer::bufferIncomingRangeMsg,
102  this, _1, topic_name)));
103 
104  ROS_INFO("RangeSensorLayer: subscribed to topic %s", range_subs_.back().getTopic().c_str());
105  }
106  }
107 
108  dsrv_ = new dynamic_reconfigure::Server<range_sensor_layer::RangeSensorLayerConfig>(nh);
109  dynamic_reconfigure::Server<range_sensor_layer::RangeSensorLayerConfig>::CallbackType cb =
110  boost::bind(&RangeSensorLayer::reconfigureCB, this, _1, _2);
111  dsrv_->setCallback(cb);
112  global_frame_ = layered_costmap_->getGlobalFrameID();
113 }
114 
115 
116 double RangeSensorLayer::gamma(double theta)
117 {
118  if (fabs(theta) > max_angle_)
119  return 0.0;
120  else
121  return 1 - pow(theta / max_angle_, 2);
122 }
123 
124 double RangeSensorLayer::delta(double phi)
125 {
126  return 1 - (1 + tanh(2 * (phi - phi_v_))) / 2;
127 }
128 
129 void RangeSensorLayer::get_deltas(double angle, double *dx, double *dy)
130 {
131  double ta = tan(angle);
132  if (ta == 0)
133  *dx = 0;
134  else
135  *dx = resolution_ / ta;
136 
137  *dx = copysign(*dx, cos(angle));
138  *dy = copysign(resolution_, sin(angle));
139 }
140 
141 double RangeSensorLayer::sensor_model(double r, double phi, double theta)
142 {
143  double lbda = delta(phi) * gamma(theta);
144 
145  double delta = resolution_;
146 
147  if (phi >= 0.0 && phi < r - 2 * delta * r)
148  return (1 - lbda) * (0.5);
149  else if (phi < r - delta * r)
150  return lbda * 0.5 * pow((phi - (r - 2 * delta * r)) / (delta * r), 2) + (1 - lbda) * .5;
151  else if (phi < r + delta * r)
152  {
153  double J = (r - phi) / (delta * r);
154  return lbda * ((1 - (0.5) * pow(J, 2)) - 0.5) + 0.5;
155  }
156  else
157  return 0.5;
158 }
159 
160 
161 void RangeSensorLayer::reconfigureCB(range_sensor_layer::RangeSensorLayerConfig &config, uint32_t level)
162 {
163  phi_v_ = config.phi;
164  inflate_cone_ = config.inflate_cone;
165  no_readings_timeout_ = config.no_readings_timeout;
166  clear_threshold_ = config.clear_threshold;
167  mark_threshold_ = config.mark_threshold;
168  clear_on_max_reading_ = config.clear_on_max_reading;
169 
170  if (enabled_ != config.enabled)
171  {
172  enabled_ = config.enabled;
173  current_ = false;
174  }
175 
176  // If the buffer size is going down, clear out old values
177  unsigned int old_buffer_size = ranges_buffer_size_;
178  ranges_buffer_size_ = config.ranges_buffer_size;
179  if (ranges_buffer_size_ < old_buffer_size)
180  {
181  boost::mutex::scoped_lock lock(range_message_mutex_);
182  std::unordered_map<std::string, std::list<sensor_msgs::Range>>::iterator buffer_it;
183  for (buffer_it = range_msgs_buffers_.begin(); buffer_it != range_msgs_buffers_.end(); buffer_it++)
184  {
185  while (buffer_it->second.size() > ranges_buffer_size_)
186  buffer_it->second.pop_front();
187  }
188  }
189 }
190 
191 void RangeSensorLayer::bufferIncomingRangeMsg(const sensor_msgs::RangeConstPtr& range_message,
192  const std::string& topic)
193 {
194  boost::mutex::scoped_lock lock(range_message_mutex_);
195  std::list<sensor_msgs::Range>& topic_buffer = range_msgs_buffers_[topic];
196  topic_buffer.push_back(*range_message);
197  if (topic_buffer.size() > ranges_buffer_size_)
198  topic_buffer.pop_front();
199 }
200 
201 void RangeSensorLayer::updateCostmap()
202 {
203  std::unordered_map<std::string, std::list<sensor_msgs::Range>>::iterator buffer_it;
204  for (buffer_it = range_msgs_buffers_.begin(); buffer_it != range_msgs_buffers_.end(); buffer_it++)
205  {
206  range_message_mutex_.lock();
207  std::list<sensor_msgs::Range> range_msgs_buffer_copy = std::list<sensor_msgs::Range>(buffer_it->second);
208  buffer_it->second.clear();
209  range_message_mutex_.unlock();
210 
211  for (std::list<sensor_msgs::Range>::iterator range_msgs_it = range_msgs_buffer_copy.begin();
212  range_msgs_it != range_msgs_buffer_copy.end(); range_msgs_it++)
213  {
214  processRangeMessageFunc_(*range_msgs_it);
215  }
216  }
217 }
218 
219 void RangeSensorLayer::processRangeMsg(sensor_msgs::Range& range_message)
220 {
221  if (range_message.min_range == range_message.max_range)
222  processFixedRangeMsg(range_message);
223  else
224  processVariableRangeMsg(range_message);
225 }
226 
227 void RangeSensorLayer::processFixedRangeMsg(sensor_msgs::Range& range_message)
228 {
229  if (!std::isinf(range_message.range))
230  {
231  ROS_ERROR_THROTTLE(1.0,
232  "Fixed distance ranger (min_range == max_range) in frame %s sent invalid value. "
233  "Only -Inf (== object detected) and Inf (== no object detected) are valid.",
234  range_message.header.frame_id.c_str());
235  return;
236  }
237 
238  bool clear_sensor_cone = false;
239 
240  if (range_message.range > 0) // +inf
241  {
242  if (!clear_on_max_reading_)
243  return; // no clearing at all
244 
245  clear_sensor_cone = true;
246  }
247 
248  range_message.range = range_message.min_range;
249 
250  updateCostmap(range_message, clear_sensor_cone);
251 }
252 
253 void RangeSensorLayer::processVariableRangeMsg(sensor_msgs::Range& range_message)
254 {
255  if (range_message.range < range_message.min_range || range_message.range > range_message.max_range)
256  return;
257 
258  bool clear_sensor_cone = false;
259 
260  if (range_message.range == range_message.max_range && clear_on_max_reading_)
261  clear_sensor_cone = true;
262 
263  updateCostmap(range_message, clear_sensor_cone);
264 }
265 
266 void RangeSensorLayer::updateCostmap(sensor_msgs::Range& range_message, bool clear_sensor_cone)
267 {
268  max_angle_ = range_message.field_of_view / 2;
269 
270  geometry_msgs::PointStamped in, out;
271  in.header.stamp = range_message.header.stamp;
272  in.header.frame_id = range_message.header.frame_id;
273 
274  if (!tf_->waitForTransform(global_frame_, in.header.frame_id, in.header.stamp, ros::Duration(0.1)))
275  {
276  ROS_ERROR_THROTTLE(1.0, "Range sensor layer can't transform from %s to %s at %f",
277  global_frame_.c_str(), in.header.frame_id.c_str(),
278  in.header.stamp.toSec());
279  return;
280  }
281 
282  tf_->transformPoint(global_frame_, in, out);
283 
284  double ox = out.point.x, oy = out.point.y;
285 
286  in.point.x = range_message.range;
287 
288  tf_->transformPoint(global_frame_, in, out);
289 
290  double tx = out.point.x, ty = out.point.y;
291 
292  // calculate target props
293  double dx = tx - ox, dy = ty - oy, theta = atan2(dy, dx), d = sqrt(dx * dx + dy * dy);
294 
295  // Integer Bounds of Update
296  int bx0, by0, bx1, by1;
297 
298  // Triangle that will be really updated; the other cells within bounds are ignored
299  // This triangle is formed by the origin and left and right sides of sonar cone
300  int Ox, Oy, Ax, Ay, Bx, By;
301 
302  // Bounds includes the origin
303  worldToMapNoBounds(ox, oy, Ox, Oy);
304  bx1 = bx0 = Ox;
305  by1 = by0 = Oy;
306  touch(ox, oy, &min_x_, &min_y_, &max_x_, &max_y_);
307 
308  // Update Map with Target Point
309  unsigned int aa, ab;
310  if (worldToMap(tx, ty, aa, ab))
311  {
312  setCost(aa, ab, 233);
313  touch(tx, ty, &min_x_, &min_y_, &max_x_, &max_y_);
314  }
315 
316  double mx, my;
317 
318  // Update left side of sonar cone
319  mx = ox + cos(theta - max_angle_) * d * 1.2;
320  my = oy + sin(theta - max_angle_) * d * 1.2;
321  worldToMapNoBounds(mx, my, Ax, Ay);
322  bx0 = std::min(bx0, Ax);
323  bx1 = std::max(bx1, Ax);
324  by0 = std::min(by0, Ay);
325  by1 = std::max(by1, Ay);
326  touch(mx, my, &min_x_, &min_y_, &max_x_, &max_y_);
327 
328  // Update right side of sonar cone
329  mx = ox + cos(theta + max_angle_) * d * 1.2;
330  my = oy + sin(theta + max_angle_) * d * 1.2;
331 
332  worldToMapNoBounds(mx, my, Bx, By);
333  bx0 = std::min(bx0, Bx);
334  bx1 = std::max(bx1, Bx);
335  by0 = std::min(by0, By);
336  by1 = std::max(by1, By);
337  touch(mx, my, &min_x_, &min_y_, &max_x_, &max_y_);
338 
339  // Limit Bounds to Grid
340  bx0 = std::max(0, bx0);
341  by0 = std::max(0, by0);
342  bx1 = std::min(static_cast<int>(size_x_), bx1);
343  by1 = std::min(static_cast<int>(size_y_), by1);
344 
345  for (unsigned int x = bx0; x <= (unsigned int)bx1; x++)
346  {
347  for (unsigned int y = by0; y <= (unsigned int)by1; y++)
348  {
349  bool update_xy_cell = true;
350 
351  // Unless inflate_cone_ is set to 100 %, we update cells only within the (partially inflated) sensor cone,
352  // projected on the costmap as a triangle. 0 % corresponds to just the triangle, but if your sensor fov is
353  // very narrow, the covered area can become zero due to cell discretization. See wiki description for more
354  // details
355  if (inflate_cone_ < 1.0)
356  {
357  // Determine barycentric coordinates
358  int w0 = orient2d(Ax, Ay, Bx, By, x, y);
359  int w1 = orient2d(Bx, By, Ox, Oy, x, y);
360  int w2 = orient2d(Ox, Oy, Ax, Ay, x, y);
361 
362  // Barycentric coordinates inside area threshold; this is not mathematically sound at all, but it works!
363  float bcciath = -inflate_cone_ * area(Ax, Ay, Bx, By, Ox, Oy);
364  update_xy_cell = w0 >= bcciath && w1 >= bcciath && w2 >= bcciath;
365  }
366 
367  if (update_xy_cell)
368  {
369  double wx, wy;
370  mapToWorld(x, y, wx, wy);
371  update_cell(ox, oy, theta, range_message.range, wx, wy, clear_sensor_cone);
372  }
373  }
374  }
375 
376  buffered_readings_++;
377  last_reading_time_ = ros::Time::now();
378 }
379 
380 void RangeSensorLayer::update_cell(double ox, double oy, double ot, double r, double nx, double ny, bool clear)
381 {
382  unsigned int x, y;
383  if (worldToMap(nx, ny, x, y))
384  {
385  double dx = nx - ox, dy = ny - oy;
386  double theta = atan2(dy, dx) - ot;
387  theta = angles::normalize_angle(theta);
388  double phi = sqrt(dx * dx + dy * dy);
389  double sensor = 0.0;
390  if (!clear)
391  sensor = sensor_model(r, phi, theta);
392  double prior = to_prob(getCost(x, y));
393  double prob_occ = sensor * prior;
394  double prob_not = (1 - sensor) * (1 - prior);
395  double new_prob = prob_occ / (prob_occ + prob_not);
396 
397  ROS_DEBUG("%f %f | %f %f = %f", dx, dy, theta, phi, sensor);
398  ROS_DEBUG("%f | %f %f | %f", prior, prob_occ, prob_not, new_prob);
399  unsigned char c = to_cost(new_prob);
400  setCost(x, y, c);
401  }
402 }
403 
404 void RangeSensorLayer::resetRange()
405 {
406  min_x_ = min_y_ = std::numeric_limits<double>::max();
407  max_x_ = max_y_ = -std::numeric_limits<double>::max();
408 }
409 
410 void RangeSensorLayer::updateBounds(double robot_x, double robot_y, double robot_yaw,
411  double* min_x, double* min_y, double* max_x, double* max_y)
412 {
413  if (layered_costmap_->isRolling())
414  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
415 
416  updateCostmap();
417 
418  *min_x = std::min(*min_x, min_x_);
419  *min_y = std::min(*min_y, min_y_);
420  *max_x = std::max(*max_x, max_x_);
421  *max_y = std::max(*max_y, max_y_);
422 
423  resetRange();
424 
425  if (!enabled_)
426  {
427  current_ = true;
428  return;
429  }
430 
431  if (buffered_readings_ == 0)
432  {
433  if (no_readings_timeout_ > 0.0 &&
434  (ros::Time::now() - last_reading_time_).toSec() > no_readings_timeout_)
435  {
436  ROS_WARN_THROTTLE(2.0, "No range readings received for %.2f seconds, " \
437  "while expected at least every %.2f seconds.",
438  (ros::Time::now() - last_reading_time_).toSec(), no_readings_timeout_);
439  current_ = false;
440  }
441  }
442 }
443 
444 void RangeSensorLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
445 {
446  if (!enabled_)
447  return;
448 
449  unsigned char* master_array = master_grid.getCharMap();
450  unsigned int span = master_grid.getSizeInCellsX();
451  unsigned char clear = to_cost(clear_threshold_), mark = to_cost(mark_threshold_);
452 
453  for (int j = min_j; j < max_j; j++)
454  {
455  unsigned int it = j * span + min_i;
456  for (int i = min_i; i < max_i; i++)
457  {
458  unsigned char prob = costmap_[it];
459  unsigned char current;
460  if (prob == costmap_2d::NO_INFORMATION)
461  {
462  it++;
463  continue;
464  }
465  else if (prob > mark)
466  current = costmap_2d::LETHAL_OBSTACLE;
467  else if (prob < clear)
468  current = costmap_2d::FREE_SPACE;
469  else
470  {
471  it++;
472  continue;
473  }
474 
475  unsigned char old_cost = master_array[it];
476 
477  if (old_cost == NO_INFORMATION || old_cost < current)
478  master_array[it] = current;
479  it++;
480  }
481  }
482 
483  buffered_readings_ = 0;
484  current_ = true;
485 }
486 
487 void RangeSensorLayer::reset()
488 {
489  ROS_DEBUG("Reseting range sensor layer...");
490  deactivate();
491  resetMaps();
492  current_ = true;
493  activate();
494 }
495 
496 void RangeSensorLayer::deactivate()
497 {
498  range_msgs_buffers_.clear();
499 }
500 
501 void RangeSensorLayer::activate()
502 {
503  range_msgs_buffers_.clear();
504 }
505 
506 } // namespace range_sensor_layer
d
#define ROS_WARN_THROTTLE(rate,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int size() const
bool valid() const
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
tf::TransformListener * tf_
Type const & getType() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const unsigned char FREE_SPACE
#define ROS_WARN(...)
unsigned char * getCharMap() const
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
#define ROS_ERROR_THROTTLE(rate,...)
INLINE Rall1d< T, V, S > tanh(const Rall1d< T, V, S > &arg)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
unsigned int getSizeInCellsX() const
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
static Time now()
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
#define ROS_ERROR(...)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
#define ROS_DEBUG(...)


range_sensor_layer
Author(s): David!!
autogenerated on Thu Mar 4 2021 04:02:55