From 175e23d6e782ca1037f36d6b0f66adb2267e3f5b Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 27 Dec 2022 17:51:45 +0900 Subject: [PATCH] fix(crosswalk): fix base path for stop point caluculation (#2584) Signed-off-by: satoshi-ota Signed-off-by: satoshi-ota --- .../src/scene_module/crosswalk/scene_crosswalk.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/src/scene_module/crosswalk/scene_crosswalk.cpp b/planning/behavior_velocity_planner/src/scene_module/crosswalk/scene_crosswalk.cpp index 2dabbdc537b99..6b71d8a5cf4a2 100644 --- a/planning/behavior_velocity_planner/src/scene_module/crosswalk/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/src/scene_module/crosswalk/scene_crosswalk.cpp @@ -446,7 +446,7 @@ boost::optional CrosswalkModule::findNearestStopPoint const auto stop_line_distance = exist_stopline_in_map ? 0.0 : planner_param_.stop_line_distance; const auto margin = stop_at_stop_line ? stop_line_distance + base_link2front : planner_param_.stop_margin + base_link2front; - const auto stop_pose = calcLongitudinalOffsetPose(sparse_resample_path.points, p_stop, -margin); + const auto stop_pose = calcLongitudinalOffsetPose(ego_path.points, p_stop, -margin); if (!stop_pose) { return {};