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


range_sensor_layer
Author(s): David!!
autogenerated on Mon Feb 28 2022 22:55:28