Skip to content

Commit

Permalink
fix(autoware_behavior_path_planner_common): fix shadowArgument warnin…
Browse files Browse the repository at this point in the history
…g in getDistanceToCrosswalk (autowarefoundation#7665)

Signed-off-by: Koichi Imai <[email protected]>
  • Loading branch information
Koichi98 authored Jun 25, 2024
1 parent 435f368 commit bfcb320
Showing 1 changed file with 1 addition and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit bfcb320

Please sign in to comment.