Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Check for range_max of laserscan in updateFilter to avoid a implicit overflow crash. #3276

Merged
merged 3 commits into from
Nov 10, 2022
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -808,6 +808,15 @@ bool AmclNode::updateFilter(
get_logger(), "Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min,
angle_increment);

// Check the validity of range_max, must > 0.0
if (laser_scan->range_max <= 0.0) {
RCLCPP_WARN(
get_logger(), "wrong range_max of laser_scan data: %f. The message could be malformed."
" Ignore this message and stop updating.",
laser_scan->range_max);
return false;
}

// Apply range min/max thresholds, if the user supplied them
if (laser_max_range_ > 0.0) {
ldata.range_max = std::min(laser_scan->range_max, static_cast<float>(laser_max_range_));
Expand Down