Skip to content

Commit 7e05b98

Browse files
committed
handle division by zero
Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
1 parent 0707fcd commit 7e05b98

File tree

1 file changed

+9
-0
lines changed

1 file changed

+9
-0
lines changed

planning/behavior_velocity_run_out_module/src/dynamic_obstacle.cpp

+9
Original file line numberDiff line numberDiff line change
@@ -324,6 +324,15 @@ std::vector<geometry_msgs::msg::Pose> createPathToPredictionTime(
324324
// Calculate the number of poses to include based on the prediction time and the time step between
325325
// poses
326326
const double time_step_seconds = convertDurationToDouble(predicted_path.time_step);
327+
if (time_step_seconds < std::numeric_limits<double>::epsilon()) {
328+
// Handle the case where time_step_seconds is zero or too close to zero
329+
RCLCPP_WARN_STREAM(
330+
rclcpp::get_logger("run_out: createPathToPredictionTime"),
331+
"time_step of the path is too close to zero. Use the input path");
332+
const std::vector<geometry_msgs::msg::Pose> input_path(
333+
predicted_path.path.begin(), predicted_path.path.end());
334+
return input_path;
335+
}
327336
const size_t poses_to_include =
328337
std::min(static_cast<size_t>(prediction_time / time_step_seconds), predicted_path.path.size());
329338

0 commit comments

Comments
 (0)