From bfcb3200897d922b42ea058c5624702d970eb098 Mon Sep 17 00:00:00 2001 From: Koichi98 <45482193+Koichi98@users.noreply.github.com> Date: Tue, 25 Jun 2024 09:17:06 +0900 Subject: [PATCH] fix(autoware_behavior_path_planner_common): fix shadowArgument warning in getDistanceToCrosswalk (#7665) Signed-off-by: Koichi Imai --- .../autoware_behavior_path_planner_common/src/utils/utils.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index 55a6c6ff39d30..4ab1ef0d1fc23 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -734,12 +734,11 @@ double getDistanceToCrosswalk( boost::geometry::intersection(centerline, polygon, points_intersection); for (const auto & point : points_intersection) { - lanelet::ConstLanelets lanelets = {llt}; Pose pose_point; pose_point.position.x = point.x(); pose_point.position.y = point.y(); const lanelet::ArcCoordinates & arc_crosswalk = - lanelet::utils::getArcCoordinates(lanelets, pose_point); + lanelet::utils::getArcCoordinates({llt}, pose_point); const double distance_to_crosswalk = arc_crosswalk.length; if (distance_to_crosswalk < min_distance_to_crosswalk) {