Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(intersection): initially ignore occlusion at intersection with tl, if tl info has never been available #6273

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,28 @@
const auto & intersection_lanelets = intersection_lanelets_.value();
const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention();

const bool is_amber_or_red =
// ==========================================================================================
// for the convenience of Psim user, this module ignores occlusion if there has not been any
// information published for the associated traffic light, and only runs collision checking on
// that intersection lane.
//
// this is because Psim-users/scenario-files do not set traffic light information perfectly
// most of the times, and they just set bare minimum traffic information only for traffic lights
// they are interested in or want to test.
//
// no_tl_info_ever variable is defined for that purpose. if there has been any
// information published for the associated traffic light in the real world through perception/V2I
// or in the simulation, then it should be kept in last_tl_valid_observation_ and this variable
// becomes false
// ==========================================================================================
const bool no_tl_info_ever = !last_tl_valid_observation_.has_value();
const bool is_amber_or_red_or_no_tl_info_ever =
(traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) ||
(traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED);
(traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED) || no_tl_info_ever;
// check occlusion on detection lane
auto occlusion_status =
(planner_param_.occlusion.enable && !occlusion_attention_lanelets.empty() && !is_amber_or_red)
(planner_param_.occlusion.enable && !occlusion_attention_lanelets.empty() &&
!is_amber_or_red_or_no_tl_info_ever)

Check warning on line 63 in planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::getOcclusionStatus increases in cyclomatic complexity from 11 to 12, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
? detectOcclusion(interpolated_path_info)
: OcclusionType::NOT_OCCLUDED;
occlusion_stop_state_machine_.setStateWithMarginTime(
Expand Down
Loading