Skip to content

Commit

Permalink
Merge pull request #1608 from tier4/fix/traffic_light_utils_nullopt
Browse files Browse the repository at this point in the history
fix(traffic_light_utils): prevent accessing nullopt (autowarefoundation#9163)
  • Loading branch information
shmpwk authored Oct 28, 2024
2 parents 3c27a1f + b0a5c36 commit 9219335
Showing 1 changed file with 8 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,13 @@ double getDistanceToNextTrafficLight(
lanelet::utils::to2D(lanelet_point).basicPoint());

for (const auto & element : current_lanelet.regulatoryElementsAs<lanelet::TrafficLight>()) {
lanelet::ConstLineString3d lanelet_stop_lines = element->stopLine().value();
const auto lanelet_stop_lines = element->stopLine();

if (!lanelet_stop_lines.has_value()) continue;

const auto to_stop_line = lanelet::geometry::toArcCoordinates(
lanelet::utils::to2D(current_lanelet.centerline()),
lanelet::utils::to2D(lanelet_stop_lines).front().basicPoint());
lanelet::utils::to2D(lanelet_stop_lines.value()).front().basicPoint());

const auto distance_object_to_stop_line = to_stop_line.length - to_object.length;

Expand All @@ -61,11 +63,13 @@ double getDistanceToNextTrafficLight(
}

for (const auto & element : llt.regulatoryElementsAs<lanelet::TrafficLight>()) {
lanelet::ConstLineString3d lanelet_stop_lines = element->stopLine().value();
const auto lanelet_stop_lines = element->stopLine();

if (!lanelet_stop_lines.has_value()) continue;

const auto to_stop_line = lanelet::geometry::toArcCoordinates(
lanelet::utils::to2D(llt.centerline()),
lanelet::utils::to2D(lanelet_stop_lines).front().basicPoint());
lanelet::utils::to2D(lanelet_stop_lines.value()).front().basicPoint());

return distance + to_stop_line.length - to_object.length;
}
Expand Down

0 comments on commit 9219335

Please sign in to comment.