diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index c215eacfa5c7e..0415b9cd71062 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -294,7 +294,7 @@ VelocityPlanningResult OutOfLaneModule::plan( ego_data.trajectory_points, 0LU, previous_slowdown_pose_->position); return prev_arc_length < arc_length; } - return slowdown_pose && previous_slowdown_pose_; + return !slowdown_pose && previous_slowdown_pose_; }(); if (should_use_previous_pose) { // if the trajectory changed the prev point is no longer on the trajectory so we project it