Skip to content

Commit bfcb320

Browse files
authored
fix(autoware_behavior_path_planner_common): fix shadowArgument warning in getDistanceToCrosswalk (#7665)
Signed-off-by: Koichi Imai <kotty.0704@gmail.com>
1 parent 435f368 commit bfcb320

File tree

1 file changed

+1
-2
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils

1 file changed

+1
-2
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -734,12 +734,11 @@ double getDistanceToCrosswalk(
734734
boost::geometry::intersection(centerline, polygon, points_intersection);
735735

736736
for (const auto & point : points_intersection) {
737-
lanelet::ConstLanelets lanelets = {llt};
738737
Pose pose_point;
739738
pose_point.position.x = point.x();
740739
pose_point.position.y = point.y();
741740
const lanelet::ArcCoordinates & arc_crosswalk =
742-
lanelet::utils::getArcCoordinates(lanelets, pose_point);
741+
lanelet::utils::getArcCoordinates({llt}, pose_point);
743742

744743
const double distance_to_crosswalk = arc_crosswalk.length;
745744
if (distance_to_crosswalk < min_distance_to_crosswalk) {

0 commit comments

Comments
 (0)