diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 5ec34ebbab6e3..83fc91409e275 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -428,7 +428,7 @@ BehaviorModuleOutput PlannerManager::getReferencePath( std::max(p.backward_path_length, p.backward_path_length + extra_margin); const auto lanelet_sequence = route_handler->getLaneletSequence( - root_lanelet_.value(), pose, backward_length, std::numeric_limits::max()); + root_lanelet_.value(), pose, backward_length, p.forward_path_length); lanelet::ConstLanelet closest_lane{}; if (lanelet::utils::query::getClosestLaneletWithConstrains(