@@ -940,12 +940,11 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
940
940
return true ;
941
941
}
942
942
943
- static bool isGreenSolidOn (
944
- lanelet::ConstLanelet lane, const std::map<int , TrafficSignalStamped> & tl_infos)
943
+ bool IntersectionModule::isGreenSolidOn (lanelet::ConstLanelet lane)
945
944
{
946
945
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
947
946
948
- std::optional<int > tl_id = std::nullopt;
947
+ std::optional<lanelet::Id > tl_id = std::nullopt;
949
948
for (auto && tl_reg_elem : lane.regulatoryElementsAs <lanelet::TrafficLight>()) {
950
949
tl_id = tl_reg_elem->id ();
951
950
break ;
@@ -954,12 +953,13 @@ static bool isGreenSolidOn(
954
953
// this lane has no traffic light
955
954
return false ;
956
955
}
957
- const auto tl_info_it = tl_infos.find (tl_id.value ());
958
- if (tl_info_it == tl_infos.end ()) {
956
+ const auto tl_info_opt = planner_data_->getTrafficSignal (
957
+ tl_id.value (), true /* traffic light module keeps last observation*/ );
958
+ if (!tl_info_opt) {
959
959
// the info of this traffic light is not available
960
960
return false ;
961
961
}
962
- const auto & tl_info = tl_info_it-> second ;
962
+ const auto & tl_info = tl_info_opt. value () ;
963
963
for (auto && tl_light : tl_info.signal .elements ) {
964
964
if (
965
965
tl_light.color == TrafficSignalElement::GREEN &&
@@ -1004,8 +1004,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
1004
1004
1005
1005
// at the very first time of regisTration of this module, the path may not be conflicting with the
1006
1006
// attention area, so update() is called to update the internal data as well as traffic light info
1007
- const auto traffic_prioritized_level =
1008
- getTrafficPrioritizedLevel (assigned_lanelet, planner_data_->traffic_light_id_map );
1007
+ const auto traffic_prioritized_level = getTrafficPrioritizedLevel (assigned_lanelet);
1009
1008
const bool is_prioritized =
1010
1009
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED;
1011
1010
intersection_lanelets.update (is_prioritized, interpolated_path_info, footprint, baselink2front);
@@ -1259,8 +1258,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
1259
1258
// If there are any vehicles on the attention area when ego entered the intersection on green
1260
1259
// light, do pseudo collision detection because the vehicles are very slow and no collisions may
1261
1260
// be detected. check if ego vehicle entered assigned lanelet
1262
- const bool is_green_solid_on =
1263
- isGreenSolidOn (assigned_lanelet, planner_data_->traffic_light_id_map );
1261
+ const bool is_green_solid_on = isGreenSolidOn (assigned_lanelet);
1264
1262
if (is_green_solid_on) {
1265
1263
if (!initial_green_light_observed_time_) {
1266
1264
const auto assigned_lane_begin_point = assigned_lanelet.centerline ().front ();
@@ -1413,12 +1411,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
1413
1411
}
1414
1412
}
1415
1413
1416
- TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel (
1417
- lanelet::ConstLanelet lane, const std::map<int , TrafficSignalStamped> & tl_infos)
1414
+ TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel (lanelet::ConstLanelet lane)
1418
1415
{
1419
1416
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;
1420
1417
1421
- std::optional<int > tl_id = std::nullopt;
1418
+ std::optional<lanelet::Id > tl_id = std::nullopt;
1422
1419
for (auto && tl_reg_elem : lane.regulatoryElementsAs <lanelet::TrafficLight>()) {
1423
1420
tl_id = tl_reg_elem->id ();
1424
1421
break ;
@@ -1427,12 +1424,12 @@ TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(
1427
1424
// this lane has no traffic light
1428
1425
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
1429
1426
}
1430
- const auto tl_info_it = tl_infos. find (tl_id. value ());
1431
- if (tl_info_it == tl_infos. end ()) {
1432
- // the info of this traffic light is not available
1427
+ const auto tl_info_opt = planner_data_-> getTrafficSignal (
1428
+ tl_id. value (), true /* traffic light module keeps last observation */ );
1429
+ if (!tl_info_opt) {
1433
1430
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
1434
1431
}
1435
- const auto & tl_info = tl_info_it-> second ;
1432
+ const auto & tl_info = tl_info_opt. value () ;
1436
1433
bool has_amber_signal{false };
1437
1434
for (auto && tl_light : tl_info.signal .elements ) {
1438
1435
if (tl_light.color == TrafficSignalElement::AMBER) {
0 commit comments