We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 435f368 commit bfcb320Copy full SHA for bfcb320
planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp
@@ -734,12 +734,11 @@ double getDistanceToCrosswalk(
734
boost::geometry::intersection(centerline, polygon, points_intersection);
735
736
for (const auto & point : points_intersection) {
737
- lanelet::ConstLanelets lanelets = {llt};
738
Pose pose_point;
739
pose_point.position.x = point.x();
740
pose_point.position.y = point.y();
741
const lanelet::ArcCoordinates & arc_crosswalk =
742
- lanelet::utils::getArcCoordinates(lanelets, pose_point);
+ lanelet::utils::getArcCoordinates({llt}, pose_point);
743
744
const double distance_to_crosswalk = arc_crosswalk.length;
745
if (distance_to_crosswalk < min_distance_to_crosswalk) {
0 commit comments