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

fix(intersection): judge pass judge at intersection without tl with occlusion detection #6207

Merged
Show file tree
Hide file tree
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 @@ -19,23 +19,23 @@ namespace behavior_velocity_planner::intersection
std::string formatDecisionResult(const DecisionResult & decision_result)
{
if (std::holds_alternative<InternalError>(decision_result)) {
const auto state = std::get<InternalError>(decision_result);
const auto & state = std::get<InternalError>(decision_result);
return "InternalError because " + state.error;
}
if (std::holds_alternative<OverPassJudge>(decision_result)) {
const auto state = std::get<OverPassJudge>(decision_result);
const auto & state = std::get<OverPassJudge>(decision_result);
return "OverPassJudge:\nsafety_report:" + state.safety_report + "\nevasive_report:\n" +
state.evasive_report;
}
if (std::holds_alternative<StuckStop>(decision_result)) {
return "StuckStop";
}
if (std::holds_alternative<YieldStuckStop>(decision_result)) {
const auto state = std::get<YieldStuckStop>(decision_result);
const auto & state = std::get<YieldStuckStop>(decision_result);
return "YieldStuckStop:\nsafety_report:" + state.safety_report;
}
if (std::holds_alternative<NonOccludedCollisionStop>(decision_result)) {
const auto state = std::get<NonOccludedCollisionStop>(decision_result);
const auto & state = std::get<NonOccludedCollisionStop>(decision_result);
return "NonOccludedCollisionStop\nsafety_report:" + state.safety_report;
}
if (std::holds_alternative<FirstWaitBeforeOcclusion>(decision_result)) {
Expand All @@ -45,18 +45,18 @@ std::string formatDecisionResult(const DecisionResult & decision_result)
return "PeekingTowardOcclusion";
}
if (std::holds_alternative<OccludedCollisionStop>(decision_result)) {
const auto state = std::get<OccludedCollisionStop>(decision_result);
const auto & state = std::get<OccludedCollisionStop>(decision_result);
return "OccludedCollisionStop\nsafety_report:" + state.safety_report;
}
if (std::holds_alternative<OccludedAbsenceTrafficLight>(decision_result)) {
const auto state = std::get<OccludedAbsenceTrafficLight>(decision_result);
const auto & state = std::get<OccludedAbsenceTrafficLight>(decision_result);
return "OccludedAbsenceTrafficLight\nsafety_report:" + state.safety_report;
}
if (std::holds_alternative<Safe>(decision_result)) {
return "Safe";
}
if (std::holds_alternative<FullyPrioritized>(decision_result)) {
const auto state = std::get<FullyPrioritized>(decision_result);
const auto & state = std::get<FullyPrioritized>(decision_result);
return "FullyPrioritized\nsafety_report:" + state.safety_report;
}
return "";
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1088 to 1108, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.55 to 4.64, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -354,8 +354,18 @@
: false;
if (!has_traffic_light_) {
if (fromEgoDist(occlusion_wo_tl_pass_judge_line_idx) < 0) {
return intersection::InternalError{
"already passed maximum peeking line in the absence of traffic light"};
if (has_collision) {
const auto closest_idx = intersection_stoplines.closest_idx;

Check warning on line 358 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L358

Added line #L358 was not covered by tests
const std::string evasive_diag = generateEgoRiskEvasiveDiagnosis(
*path, closest_idx, time_distance_array, too_late_detect_objects, misjudge_objects);
return intersection::OverPassJudge{
"already passed maximum peeking line in the absence of traffic light.\n" +
safety_report,
evasive_diag};
}
return intersection::OverPassJudge{
"already passed maximum peeking line in the absence of traffic light safely",
"no evasive action required"};
}
return intersection::OccludedAbsenceTrafficLight{
is_occlusion_cleared_with_margin,
Expand All @@ -364,7 +374,7 @@
closest_idx,
first_attention_stopline_idx,
occlusion_wo_tl_pass_judge_line_idx,
safety_report};
safety_diag};

Check warning on line 377 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::modifyPathVelocityDetail increases in cyclomatic complexity from 44 to 45, 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.

Check warning on line 377 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

IntersectionModule::modifyPathVelocityDetail has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
}

// ==========================================================================================
Expand Down Expand Up @@ -1251,7 +1261,22 @@
return first_pass_judge_line_idx;
}();

const bool was_safe = std::holds_alternative<intersection::Safe>(prev_decision_result_);
// ==========================================================================================
// at intersection without traffic light, this module ignores occlusion even if occlusion is
// detected for real, so if collision is not detected in that context, that should be interpreted
// as "was_safe"
// ==========================================================================================
const bool was_safe = [&]() {
if (std::holds_alternative<intersection::Safe>(prev_decision_result_)) {
return true;
}
if (std::holds_alternative<intersection::OccludedAbsenceTrafficLight>(prev_decision_result_)) {
const auto & state =
std::get<intersection::OccludedAbsenceTrafficLight>(prev_decision_result_);
return !state.collision_detected;

Check warning on line 1276 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1276

Added line #L1276 was not covered by tests
}
return false;
}();

Check warning on line 1279 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::isOverPassJudgeLinesStatus increases in cyclomatic complexity from 22 to 24, 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.

const bool is_over_1st_pass_judge_line =
util::isOverTargetIndex(path, closest_idx, current_pose, pass_judge_line_idx);
Expand Down
Loading