diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 2f7c39f94604e..becb0440ae089 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -386,12 +386,12 @@ bool NormalLaneChange::hasFinishedLaneChange() const return false; } - const auto arc_length = lanelet::utils::getArcCoordinates(status_.target_lanes, current_pose); - const auto reach_target_lane = - std::abs(arc_length.distance) < lane_change_parameters_->finish_judge_lateral_threshold; - if (!reach_target_lane) { - return false; - } + // const auto arc_length = lanelet::utils::getArcCoordinates(status_.target_lanes, current_pose); + // const auto reach_target_lane = + // std::abs(arc_length.distance) < lane_change_parameters_->finish_judge_lateral_threshold; + // if (!reach_target_lane) { + // return false; + // } return true; }