36 #include <angles/angles.h>
43 #include "pluginlib/class_list_macros.hpp"
44 #include "geometry_msgs/msg/point_stamped.hpp"
45 #include "nav2_costmap_2d/range_sensor_layer.hpp"
49 using nav2_costmap_2d::LETHAL_OBSTACLE;
50 using nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
51 using nav2_costmap_2d::NO_INFORMATION;
53 using namespace std::literals::chrono_literals;
58 RangeSensorLayer::RangeSensorLayer() {}
60 void RangeSensorLayer::onInitialize()
64 buffered_readings_ = 0;
65 last_reading_time_ = clock_->now();
66 default_value_ = to_cost(0.5);
71 auto node = node_.lock();
73 throw std::runtime_error{
"Failed to lock node"};
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_);
91 double temp_tf_tol = 0.0;
92 node->get_parameter(
"transform_tolerance", temp_tf_tol);
93 transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
95 std::vector<std::string> topic_names{};
96 declareParameter(
"topics", rclcpp::ParameterValue(topic_names));
97 node->get_parameter(name_ +
"." +
"topics", topic_names);
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);
105 sensor_type_name.begin(), sensor_type_name.end(),
106 sensor_type_name.begin(), ::toupper);
108 logger_,
"%s: %s as input_sensor_type given",
109 name_.c_str(), sensor_type_name.c_str());
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;
119 logger_,
"%s: Invalid input sensor type: %s. Defaulting to ALL.",
120 name_.c_str(), sensor_type_name.c_str());
124 if (topic_names.empty()) {
126 logger_,
"Invalid topic names list: it must"
127 "be a non-empty list of strings");
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);
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());
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)));
160 logger_,
"RangeSensorLayer: subscribed to "
161 "topic %s", range_subs_.back()->get_topic_name());
163 global_frame_ = layered_costmap_->getGlobalFrameID();
167 double RangeSensorLayer::gamma(
double theta)
169 if (fabs(theta) > max_angle_) {
172 return 1 - pow(theta / max_angle_, 2);
176 double RangeSensorLayer::delta(
double phi)
178 return 1 - (1 + tanh(2 * (phi - phi_v_))) / 2;
181 void RangeSensorLayer::get_deltas(
double angle,
double * dx,
double * dy)
183 double ta = tan(angle);
187 *dx = resolution_ / ta;
190 *dx = copysign(*dx, cos(angle));
191 *dy = copysign(resolution_, sin(angle));
194 double RangeSensorLayer::sensor_model(
double r,
double phi,
double theta)
196 double lbda = delta(phi) * gamma(theta);
198 double delta = resolution_;
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) +
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;
213 void RangeSensorLayer::bufferIncomingRangeMsg(
214 const sensor_msgs::msg::Range::SharedPtr range_message)
216 range_message_mutex_.lock();
217 range_msgs_buffer_.push_back(*range_message);
218 range_message_mutex_.unlock();
221 void RangeSensorLayer::updateCostmap()
223 std::list<sensor_msgs::msg::Range> range_msgs_buffer_copy;
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();
230 for (
auto & range_msgs_it : range_msgs_buffer_copy) {
231 processRangeMessageFunc_(range_msgs_it);
235 void RangeSensorLayer::processRangeMsg(sensor_msgs::msg::Range & range_message)
237 if (range_message.min_range == range_message.max_range) {
238 processFixedRangeMsg(range_message);
240 processVariableRangeMsg(range_message);
244 void RangeSensorLayer::processFixedRangeMsg(sensor_msgs::msg::Range & range_message)
246 if (!std::isinf(range_message.range)) {
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());
255 bool clear_sensor_cone =
false;
257 if (range_message.range > 0) {
258 if (!clear_on_max_reading_) {
261 clear_sensor_cone =
true;
264 range_message.range = range_message.min_range;
266 updateCostmap(range_message, clear_sensor_cone);
269 void RangeSensorLayer::processVariableRangeMsg(sensor_msgs::msg::Range & range_message)
271 if (range_message.range < range_message.min_range || range_message.range >
272 range_message.max_range)
277 bool clear_sensor_cone =
false;
279 if (range_message.range >= range_message.max_range && clear_on_max_reading_) {
280 clear_sensor_cone =
true;
283 updateCostmap(range_message, clear_sensor_cone);
286 void RangeSensorLayer::updateCostmap(
287 sensor_msgs::msg::Range & range_message,
288 bool clear_sensor_cone)
290 max_angle_ = range_message.field_of_view / 2;
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;
296 if (!tf_->canTransform(
297 in.header.frame_id, global_frame_,
298 tf2_ros::fromMsg(in.header.stamp),
299 tf2_ros::fromRclcpp(transform_tolerance_)))
302 logger_,
"Range sensor layer can't transform from %s to %s",
303 global_frame_.c_str(), in.header.frame_id.c_str());
307 tf_->transform(in, out, global_frame_, transform_tolerance_);
309 double ox = out.point.x, oy = out.point.y;
311 in.point.x = range_message.range;
313 tf_->transform(in, out, global_frame_, transform_tolerance_);
315 double tx = out.point.x, ty = out.point.y;
318 double dx = tx - ox, dy = ty - oy, theta = atan2(dy, dx), d = sqrt(dx * dx + dy * dy);
321 int bx0, by0, bx1, by1;
325 int Ox, Oy, Ax, Ay, Bx, By;
328 worldToMapNoBounds(ox, oy, Ox, Oy);
331 touch(ox, oy, &min_x_, &min_y_, &max_x_, &max_y_);
335 if (worldToMap(tx, ty, aa, ab)) {
336 setCost(aa, ab, 233);
337 touch(tx, ty, &min_x_, &min_y_, &max_x_, &max_y_);
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_);
353 mx = ox + cos(theta + max_angle_) * d * 1.2;
354 my = oy + sin(theta + max_angle_) * d * 1.2;
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_);
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);
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;
378 if (inflate_cone_ < 1.0) {
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);
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;
390 if (update_xy_cell) {
392 mapToWorld(x, y, wx, wy);
393 update_cell(ox, oy, theta, range_message.range, wx, wy, clear_sensor_cone);
398 buffered_readings_++;
399 last_reading_time_ = clock_->now();
402 void RangeSensorLayer::update_cell(
403 double ox,
double oy,
double ot,
double r,
404 double nx,
double ny,
bool clear)
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);
414 sensor = sensor_model(r, phi, theta);
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);
423 "%f %f | %f %f = %f", dx, dy, theta, phi, sensor);
426 "%f | %f %f | %f", prior, prob_occ, prob_not, new_prob);
427 unsigned char c = to_cost(new_prob);
432 void RangeSensorLayer::resetRange()
434 min_x_ = min_y_ = std::numeric_limits<double>::max();
435 max_x_ = max_y_ = -std::numeric_limits<double>::max();
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)
443 robot_yaw = 0 + robot_yaw;
444 if (layered_costmap_->isRolling()) {
445 updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
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_);
462 if (buffered_readings_ == 0) {
463 if (no_readings_timeout_ > 0.0 &&
464 (clock_->now() - last_reading_time_).seconds() >
465 no_readings_timeout_)
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_);
477 void RangeSensorLayer::updateCosts(
479 int min_i,
int min_j,
int max_i,
int max_j)
485 unsigned char * master_array = master_grid.
getCharMap();
487 unsigned char clear = to_cost(clear_threshold_), mark = to_cost(mark_threshold_);
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) {
497 }
else if (prob > mark) {
498 current = nav2_costmap_2d::LETHAL_OBSTACLE;
499 }
else if (prob < clear) {
500 current = nav2_costmap_2d::FREE_SPACE;
506 unsigned char old_cost = master_array[it];
508 if (old_cost == NO_INFORMATION || old_cost < current) {
509 master_array[it] = current;
515 buffered_readings_ = 0;
518 if (!current_ && was_reset_) {
524 void RangeSensorLayer::reset()
526 RCLCPP_DEBUG(logger_,
"Resetting range sensor layer...");
533 void RangeSensorLayer::deactivate()
535 range_msgs_buffer_.clear();
538 void RangeSensorLayer::activate()
540 range_msgs_buffer_.clear();
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Abstract class for layered costmap plugin implementations.
Takes in IR/Sonar/similar point measurement sensors and populates in costmap.