3 #include <boost/algorithm/string.hpp> 4 #include <geometry_msgs/PointStamped.h> 19 RangeSensorLayer::RangeSensorLayer() {}
21 void RangeSensorLayer::onInitialize()
25 buffered_readings_ = 0;
27 default_value_ = to_cost(0.5);
34 const char* xml =
"<value><array><data><value>/sonar</value></data></array></value>";
36 std::string topics_ns;
39 nh.
param(
"ns", topics_ns, std::string());
40 nh.
param(
"topics", topic_names, topic_names);
43 std::string sensor_type_name;
44 nh.
param(
"input_sensor_type", sensor_type_name, std::string(
"ALL"));
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());
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;
57 ROS_ERROR(
"%s: Invalid input sensor type: %s", name_.c_str(), sensor_type_name.c_str());
63 ROS_ERROR(
"Invalid topic names list: it must be a non-empty list of strings");
67 if (topic_names.
size() < 1)
70 ROS_WARN(
"Empty topic names list: range sensor layer will have no effect on costmap");
74 for (
int i = 0; i < topic_names.
size(); i++)
78 ROS_WARN(
"Invalid topic names list: element %d is not a string, so it will be ignored", i);
82 std::string topic_name(topics_ns);
83 if ((topic_name.size() > 0) && (topic_name.at(topic_name.size() - 1) !=
'/'))
85 topic_name +=
static_cast<std::string
>(topic_names[i]);
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);
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());
100 range_subs_.push_back(nh.
subscribe<sensor_msgs::Range>(topic_name, 100,
101 boost::bind(&RangeSensorLayer::bufferIncomingRangeMsg,
102 this, _1, topic_name)));
104 ROS_INFO(
"RangeSensorLayer: subscribed to topic %s", range_subs_.back().getTopic().c_str());
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();
116 double RangeSensorLayer::gamma(
double theta)
118 if (fabs(theta) > max_angle_)
121 return 1 -
pow(theta / max_angle_, 2);
124 double RangeSensorLayer::delta(
double phi)
126 return 1 - (1 +
tanh(2 * (phi - phi_v_))) / 2;
129 void RangeSensorLayer::get_deltas(
double angle,
double *dx,
double *dy)
131 double ta =
tan(angle);
135 *dx = resolution_ / ta;
137 *dx = copysign(*dx,
cos(angle));
138 *dy = copysign(resolution_,
sin(angle));
141 double RangeSensorLayer::sensor_model(
double r,
double phi,
double theta)
143 double lbda = delta(phi) * gamma(theta);
145 double delta = resolution_;
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)
153 double J = (r - phi) / (delta * r);
154 return lbda * ((1 - (0.5) *
pow(J, 2)) - 0.5) + 0.5;
161 void RangeSensorLayer::reconfigureCB(range_sensor_layer::RangeSensorLayerConfig &config, uint32_t level)
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;
170 if (enabled_ != config.enabled)
172 enabled_ = config.enabled;
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)
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++)
185 while (buffer_it->second.size() > ranges_buffer_size_)
186 buffer_it->second.pop_front();
191 void RangeSensorLayer::bufferIncomingRangeMsg(
const sensor_msgs::RangeConstPtr& range_message,
192 const std::string& topic)
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();
201 void RangeSensorLayer::updateCostmap()
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++)
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();
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++)
214 processRangeMessageFunc_(*range_msgs_it);
219 void RangeSensorLayer::processRangeMsg(sensor_msgs::Range& range_message)
221 if (range_message.min_range == range_message.max_range)
222 processFixedRangeMsg(range_message);
224 processVariableRangeMsg(range_message);
227 void RangeSensorLayer::processFixedRangeMsg(sensor_msgs::Range& range_message)
229 if (!std::isinf(range_message.range))
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());
238 bool clear_sensor_cone =
false;
240 if (range_message.range > 0)
242 if (!clear_on_max_reading_)
245 clear_sensor_cone =
true;
248 range_message.range = range_message.min_range;
250 updateCostmap(range_message, clear_sensor_cone);
253 void RangeSensorLayer::processVariableRangeMsg(sensor_msgs::Range& range_message)
255 if (range_message.range < range_message.min_range || range_message.range > range_message.max_range)
258 bool clear_sensor_cone =
false;
260 if (range_message.range == range_message.max_range && clear_on_max_reading_)
261 clear_sensor_cone =
true;
263 updateCostmap(range_message, clear_sensor_cone);
266 void RangeSensorLayer::updateCostmap(sensor_msgs::Range& range_message,
bool clear_sensor_cone)
268 max_angle_ = range_message.field_of_view / 2;
270 geometry_msgs::PointStamped in, out;
271 in.header.stamp = range_message.header.stamp;
272 in.header.frame_id = range_message.header.frame_id;
277 global_frame_.c_str(), in.header.frame_id.c_str(),
278 in.header.stamp.toSec());
284 double ox = out.point.x, oy = out.point.y;
286 in.point.x = range_message.range;
290 double tx = out.point.x, ty = out.point.y;
293 double dx = tx - ox, dy = ty - oy, theta =
atan2(dy, dx),
d =
sqrt(dx * dx + dy * dy);
296 int bx0, by0, bx1, by1;
300 int Ox, Oy, Ax, Ay, Bx, By;
303 worldToMapNoBounds(ox, oy, Ox, Oy);
306 touch(ox, oy, &min_x_, &min_y_, &max_x_, &max_y_);
310 if (worldToMap(tx, ty, aa, ab))
312 setCost(aa, ab, 233);
313 touch(tx, ty, &min_x_, &min_y_, &max_x_, &max_y_);
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_);
329 mx = ox +
cos(theta + max_angle_) *
d * 1.2;
330 my = oy +
sin(theta + max_angle_) *
d * 1.2;
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_);
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);
345 for (
unsigned int x = bx0;
x <= (
unsigned int)bx1;
x++)
347 for (
unsigned int y = by0;
y <= (
unsigned int)by1;
y++)
349 bool update_xy_cell =
true;
355 if (inflate_cone_ < 1.0)
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);
363 float bcciath = -inflate_cone_ * area(Ax, Ay, Bx, By, Ox, Oy);
364 update_xy_cell = w0 >= bcciath && w1 >= bcciath && w2 >= bcciath;
370 mapToWorld(
x,
y, wx, wy);
371 update_cell(ox, oy, theta, range_message.range, wx, wy, clear_sensor_cone);
376 buffered_readings_++;
380 void RangeSensorLayer::update_cell(
double ox,
double oy,
double ot,
double r,
double nx,
double ny,
bool clear)
383 if (worldToMap(nx, ny, x, y))
385 double dx = nx - ox, dy = ny - oy;
386 double theta =
atan2(dy, dx) - ot;
388 double phi =
sqrt(dx * dx + dy * dy);
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);
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);
404 void RangeSensorLayer::resetRange()
406 min_x_ = min_y_ = std::numeric_limits<double>::max();
407 max_x_ = max_y_ = -std::numeric_limits<double>::max();
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)
413 if (layered_costmap_->isRolling())
414 updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
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_);
431 if (buffered_readings_ == 0)
433 if (no_readings_timeout_ > 0.0 &&
434 (
ros::Time::now() - last_reading_time_).toSec() > no_readings_timeout_)
437 "while expected at least every %.2f seconds.",
438 (
ros::Time::now() - last_reading_time_).toSec(), no_readings_timeout_);
449 unsigned char* master_array = master_grid.
getCharMap();
451 unsigned char clear = to_cost(clear_threshold_), mark = to_cost(mark_threshold_);
453 for (
int j = min_j; j < max_j; j++)
455 unsigned int it = j * span + min_i;
456 for (
int i = min_i; i < max_i; i++)
458 unsigned char prob = costmap_[it];
459 unsigned char current;
465 else if (prob > mark)
467 else if (prob < clear)
475 unsigned char old_cost = master_array[it];
477 if (old_cost == NO_INFORMATION || old_cost < current)
478 master_array[it] = current;
483 buffered_readings_ = 0;
487 void RangeSensorLayer::reset()
489 ROS_DEBUG(
"Reseting range sensor layer...");
496 void RangeSensorLayer::deactivate()
498 range_msgs_buffers_.clear();
501 void RangeSensorLayer::activate()
503 range_msgs_buffers_.clear();
#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())
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
Type const & getType() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const unsigned char FREE_SPACE
unsigned char * getCharMap() const
#define ROS_ERROR_THROTTLE(rate,...)
INLINE Rall1d< T, V, S > tanh(const Rall1d< T, V, S > &arg)
bool param(const std::string ¶m_name, T ¶m_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)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)