Skip to content

Commit

Permalink
feat(intersection_occlusion): treat traffic light color as RED initially
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
  • Loading branch information
soblin committed Feb 2, 2024
1 parent 2b1a33f commit a927cd5
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@
object_time_margin_to_collision_point: 4.0

occlusion:
enable: false
enable: true
occlusion_attention_area_length: 70.0
free_space_max: 43
occupied_min: 58
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,28 @@ IntersectionModule::getOcclusionStatus(
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
// oftenwise, and they just set bare minimum traffic information only for traffic lights they

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

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (oftenwise)
// 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

0 comments on commit a927cd5

Please sign in to comment.