From b4875b49ae01745236306a9e2b6131873f602166 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Fri, 22 Dec 2023 11:20:29 +0300 Subject: [PATCH] Change getLaneletSequence() function parameter with normal numbers because of the time consumption. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- planning/behavior_path_planner/src/planner_manager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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(