Skip to content

Commit c41f69b

Browse files
author
随风而散
committed
fix bug FPE
1 parent 0211977 commit c41f69b

File tree

1 file changed

+6
-1
lines changed

1 file changed

+6
-1
lines changed

nav2_amcl/src/amcl_node.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -699,7 +699,12 @@ AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
699699
// If the robot has moved, update the filter
700700
if (lasers_update_[laser_index]) {
701701
updateFilter(laser_index, laser_scan, pose);
702-
702+
if(resample_interval_ == 0){
703+
RCLCPP_WARN(
704+
get_logger(), "You've set resample_interval to be zero,"
705+
" this isn't allowed so it will be set to default value to 1.");
706+
resample_interval_ = 1;
707+
}
703708
// Resample the particles
704709
if (!(++resample_count_ % resample_interval_)) {
705710
pf_update_resample(pf_);

0 commit comments

Comments
 (0)