Skip to content

Commit d5e37b3

Browse files
committed
Revert "temp"
This reverts commit 80a271f.
1 parent 80a271f commit d5e37b3

File tree

1 file changed

+5
-13
lines changed

1 file changed

+5
-13
lines changed

planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp

+5-13
Original file line numberDiff line numberDiff line change
@@ -58,19 +58,11 @@ IntersectionModule::getOcclusionStatus(
5858
(traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) ||
5959
(traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED) || no_tl_info_ever;
6060
// check occlusion on detection lane
61-
auto occlusion_status = [&]() {
62-
if (!planner_param_.occlusion.enable || occlusion_attention_lanelets.empty()) {
63-
return OcclusionType::NOT_OCCLUDED;
64-
}
65-
if (!has_traffic_light_) {
66-
return detectOcclusion(interpolated_path_info);
67-
}
68-
// has_traffic_light_
69-
if (is_amber_or_red_or_no_tl_info_ever) {
70-
return OcclusionType::NOT_OCCLUDED;
71-
}
72-
return detectOcclusion(interpolated_path_info);
73-
}();
61+
auto occlusion_status =
62+
(planner_param_.occlusion.enable && !occlusion_attention_lanelets.empty() &&
63+
!is_amber_or_red_or_no_tl_info_ever)
64+
? detectOcclusion(interpolated_path_info)
65+
: OcclusionType::NOT_OCCLUDED;
7466
occlusion_stop_state_machine_.setStateWithMarginTime(
7567
occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP,
7668
logger_.get_child("occlusion_stop"), *clock_);

0 commit comments

Comments
 (0)