diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp index 0c793c9f5798e..22c4480162609 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -73,6 +73,8 @@ std::optional calculate_slowdown_point( const std::optional prev_slowdown_point, PlannerParam params) { params.extra_front_offset += params.dist_buffer; + params.extra_right_offset += params.dist_buffer; + params.extra_left_offset += params.dist_buffer; const auto base_footprint = make_base_footprint(params); // search for the first slowdown decision for which a stop point can be inserted