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): more precise pass judge handling considering occlusion detection and 1st/2nd attention lane #6047

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
86 changes: 59 additions & 27 deletions planning/behavior_velocity_intersection_module/README.md

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
max_accel: -2.8
max_jerk: -5.0
delay_response_time: 0.5
enable_pass_judge_before_default_stopline: false

stuck_vehicle:
turn_direction:
Expand All @@ -36,7 +37,6 @@
consider_wrong_direction_vehicle: false
collision_detection_hold_time: 0.5
min_predicted_path_confidence: 0.05
keep_detection_velocity_threshold: 0.833
velocity_profile:
use_upstream: true
minimum_upstream_velocity: 0.01
Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
20 changes: 16 additions & 4 deletions planning/behavior_velocity_intersection_module/src/debug.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check warning on line 1 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Overall Code Complexity

This module has a mean cyclomatic complexity of 4.50 across 8 functions. The mean complexity threshold is 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 @@ -90,7 +90,7 @@
marker_line.type = visualization_msgs::msg::Marker::LINE_STRIP;
marker_line.action = visualization_msgs::msg::Marker::ADD;
marker_line.pose.orientation = createMarkerOrientation(0, 0, 0, 1.0);
marker_line.scale = createMarkerScale(0.1, 0.0, 0.0);
marker_line.scale = createMarkerScale(0.2, 0.0, 0.0);

Check warning on line 93 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_intersection_module/src/debug.cpp#L93

Added line #L93 was not covered by tests
marker_line.color = createMarkerColor(r, g, b, 0.999);

const double yaw = tf2::getYaw(pose.orientation);
Expand Down Expand Up @@ -283,11 +283,23 @@
&debug_marker_array, now);
*/

if (debug_data_.pass_judge_wall_pose) {
if (debug_data_.first_pass_judge_wall_pose) {
const double r = debug_data_.passed_first_pass_judge ? 1.0 : 0.0;
const double g = debug_data_.passed_first_pass_judge ? 0.0 : 1.0;
appendMarkerArray(
createPoseMarkerArray(
debug_data_.pass_judge_wall_pose.value(), "pass_judge_wall_pose", module_id_, 0.7, 0.85,
0.9),
debug_data_.first_pass_judge_wall_pose.value(), "first_pass_judge_wall_pose", module_id_, r,
g, 0.0),
&debug_marker_array, now);
}

if (debug_data_.second_pass_judge_wall_pose) {
const double r = debug_data_.passed_second_pass_judge ? 1.0 : 0.0;
const double g = debug_data_.passed_second_pass_judge ? 0.0 : 1.0;
appendMarkerArray(
createPoseMarkerArray(
debug_data_.second_pass_judge_wall_pose.value(), "second_pass_judge_wall_pose", module_id_,
r, g, 0.0),

Check warning on line 302 in planning/behavior_velocity_intersection_module/src/debug.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

IntersectionModule::createDebugMarkerArray increases in cyclomatic complexity from 14 to 19, 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.
&debug_marker_array, now);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
ip.common.max_jerk = getOrDeclareParameter<double>(node, ns + ".common.max_jerk");
ip.common.delay_response_time =
getOrDeclareParameter<double>(node, ns + ".common.delay_response_time");
ip.common.enable_pass_judge_before_default_stopline =
getOrDeclareParameter<bool>(node, ns + ".common.enable_pass_judge_before_default_stopline");

ip.stuck_vehicle.turn_direction.left =
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.turn_direction.left");
Expand Down Expand Up @@ -92,8 +94,6 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
getOrDeclareParameter<double>(node, ns + ".collision_detection.collision_detection_hold_time");
ip.collision_detection.min_predicted_path_confidence =
getOrDeclareParameter<double>(node, ns + ".collision_detection.min_predicted_path_confidence");
ip.collision_detection.keep_detection_velocity_threshold = getOrDeclareParameter<double>(
node, ns + ".collision_detection.keep_detection_velocity_threshold");
ip.collision_detection.velocity_profile.use_upstream =
getOrDeclareParameter<bool>(node, ns + ".collision_detection.velocity_profile.use_upstream");
ip.collision_detection.velocity_profile.minimum_upstream_velocity = getOrDeclareParameter<double>(
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 2917 to 2937, 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 9.62 to 9.76, 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 @@ -1041,7 +1041,8 @@
const auto default_stopline_idx_opt = intersection_stoplines.default_stopline;
const auto first_attention_stopline_idx_opt = intersection_stoplines.first_attention_stopline;
const auto occlusion_peeking_stopline_idx_opt = intersection_stoplines.occlusion_peeking_stopline;
const auto default_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line;
const auto first_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line;
const auto second_pass_judge_line_idx = intersection_stoplines.second_pass_judge_line;

Check warning on line 1045 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#L1044-L1045

Added lines #L1044 - L1045 were not covered by tests
const auto occlusion_wo_tl_pass_judge_line_idx =
intersection_stoplines.occlusion_wo_tl_pass_judge_line;

Expand Down Expand Up @@ -1221,44 +1222,76 @@
prev_occlusion_status_ = occlusion_status;
}

// TODO(Mamoru Sobue): this part needs more formal handling
const size_t pass_judge_line_idx = [=]() {
const size_t pass_judge_line_idx = [&]() {

Check warning on line 1225 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#L1225

Added line #L1225 was not covered by tests
if (enable_occlusion_detection_) {
// if occlusion detection is enabled, pass_judge position is beyond the boundary of first
// attention area
if (has_traffic_light_) {
return occlusion_stopline_idx;
// if ego passed the first_pass_judge_line while it is peeking to occlusion, then its
// position is occlusion_stopline_idx. Otherwise it is first_pass_judge_line
if (passed_1st_judge_line_while_peeking_) {
return occlusion_stopline_idx;

Check warning on line 1231 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#L1231

Added line #L1231 was not covered by tests
}
const bool is_over_first_pass_judge_line =
util::isOverTargetIndex(*path, closest_idx, current_pose, first_pass_judge_line_idx);

Check warning on line 1234 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#L1234

Added line #L1234 was not covered by tests
if (is_occlusion_state && is_over_first_pass_judge_line) {
passed_1st_judge_line_while_peeking_ = true;
return occlusion_stopline_idx;

Check warning on line 1237 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#L1236-L1237

Added lines #L1236 - L1237 were not covered by tests
} else {
return first_pass_judge_line_idx;

Check warning on line 1239 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#L1239

Added line #L1239 was not covered by tests
}
} else if (is_occlusion_state) {
// if there is no traffic light and occlusion is detected, pass_judge position is beyond
// the boundary of first attention area
return occlusion_wo_tl_pass_judge_line_idx;
} else {
// if there is no traffic light and occlusion is not detected, pass_judge position is
// default
return default_pass_judge_line_idx;
return first_pass_judge_line_idx;

Check warning on line 1248 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#L1248

Added line #L1248 was not covered by tests
}
}
return default_pass_judge_line_idx;
return first_pass_judge_line_idx;

Check warning on line 1251 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#L1251

Added line #L1251 was not covered by tests
}();
debug_data_.pass_judge_wall_pose =
planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path);
const bool is_over_pass_judge_line =
util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx);
const double vel_norm = std::hypot(
planner_data_->current_velocity->twist.linear.x,
planner_data_->current_velocity->twist.linear.y);
const bool keep_detection =
(vel_norm < planner_param_.collision_detection.keep_detection_velocity_threshold);

const bool was_safe = std::holds_alternative<IntersectionModule::Safe>(prev_decision_result_);
// if ego is over the pass judge line and not stopped
if (is_over_default_stopline && !is_over_pass_judge_line && keep_detection) {
RCLCPP_DEBUG(logger_, "is_over_default_stopline && !is_over_pass_judge_line && keep_detection");
// do nothing
} else if (
(was_safe && is_over_default_stopline && is_over_pass_judge_line && is_go_out_) ||

const bool is_over_1st_pass_judge_line =
util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx);
if (is_over_1st_pass_judge_line && was_safe && !safely_passed_1st_judge_line_time_) {
safely_passed_1st_judge_line_time_ = clock_->now();
}
debug_data_.first_pass_judge_wall_pose =
planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path);
debug_data_.passed_first_pass_judge = safely_passed_1st_judge_line_time_.has_value();

Check warning on line 1263 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#L1263

Added line #L1263 was not covered by tests
const bool is_over_2nd_pass_judge_line =
util::isOverTargetIndex(*path, closest_idx, current_pose, second_pass_judge_line_idx);
if (is_over_2nd_pass_judge_line && was_safe && !safely_passed_2nd_judge_line_time_) {
safely_passed_2nd_judge_line_time_ = clock_->now();
}
debug_data_.second_pass_judge_wall_pose =
planning_utils::getAheadPose(second_pass_judge_line_idx, baselink2front, *path);
debug_data_.passed_second_pass_judge = safely_passed_2nd_judge_line_time_.has_value();

Check warning on line 1271 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#L1271

Added line #L1271 was not covered by tests

if (
((is_over_default_stopline ||

Check warning on line 1274 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#L1274

Added line #L1274 was not covered by tests
planner_param_.common.enable_pass_judge_before_default_stopline) &&
is_over_2nd_pass_judge_line && was_safe) ||

Check warning on line 1276 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 Conditional

IntersectionModule::modifyPathVelocityDetail increases from 3 complex conditionals with 8 branches to 4 complex conditionals with 10 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
is_permanent_go_) {
// is_go_out_: previous RTC approval
// activated_: current RTC approval
/*
* This body is active if ego is
* - over the default stopline AND
* - over the 1st && 2nd pass judge line AND
* - previously safe
* ,
* which means ego can stop even if it is over the 1st pass judge line but
* - before default stopline OR
* - before the 2nd pass judge line OR
* - or previously unsafe
* .
* In order for ego to continue peeking or collision detection when occlusion is detected after
* ego passed the 1st pass judge line, it needs to be
* - before the default stopline OR
* - before the 2nd pass judge line OR
* - previously unsafe
*/
is_permanent_go_ = true;
return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"};
}
Expand Down Expand Up @@ -1309,10 +1342,14 @@
: (planner_param_.collision_detection.collision_detection_hold_time -
collision_state_machine_.getDuration());

// TODO(Mamoru Sobue): if ego is over 1st/2nd pass judge line and collision is expected at 1st/2nd
// pass judge line respectively, ego should go
const auto second_attention_stopline_idx = intersection_stoplines.second_attention_stopline;
const auto last_intersection_stopline_candidate_idx =
second_attention_stopline_idx ? second_attention_stopline_idx.value() : occlusion_stopline_idx;
const bool has_collision = checkCollision(
*path, &target_objects, path_lanelets, closest_idx,
std::min<size_t>(occlusion_stopline_idx, path->points.size() - 1), time_to_restart,
traffic_prioritized_level);
*path, &target_objects, path_lanelets, closest_idx, last_intersection_stopline_candidate_idx,
time_to_restart, traffic_prioritized_level);

Check notice on line 1352 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 91 to 98, 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.
collision_state_machine_.setStateWithMarginTime(
has_collision ? StateMachine::State::STOP : StateMachine::State::GO,
logger_.get_child("collision state_machine"), *clock_);
Expand Down Expand Up @@ -1808,16 +1845,19 @@
second_attention_area, interpolated_path_info, local_footprint, baselink2front);
if (first_footprint_inside_2nd_attention_ip_opt) {
second_attention_stopline_ip_int = first_footprint_inside_2nd_attention_ip_opt.value();
second_attention_stopline_valid = true;
}
}
const auto second_attention_stopline_ip =
second_attention_stopline_ip_int >= 0 ? static_cast<size_t>(second_attention_stopline_ip_int)
: 0;

// (8) second pass judge lie position on interpolated path
int second_pass_judge_ip_int = second_attention_stopline_ip_int - std::ceil(braking_dist / ds);
// (8) second pass judge line position on interpolated path. It is the same as first pass judge
// line if second_attention_lane is null
int second_pass_judge_ip_int = occlusion_wo_tl_pass_judge_line_ip;
const auto second_pass_judge_line_ip =
static_cast<size_t>(std::max<int>(second_pass_judge_ip_int, 0));
second_attention_area_opt ? static_cast<size_t>(std::max<int>(second_pass_judge_ip_int, 0))
: first_pass_judge_line_ip;

Check notice on line 1860 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::generateIntersectionStopLines increases in cyclomatic complexity from 25 to 26, 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 1860 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#L1860

Added line #L1860 was not covered by tests

struct IntersectionStopLinesTemp
{
Expand Down Expand Up @@ -2803,8 +2843,6 @@
return std::nullopt;
}
}();
const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value();
const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0);

for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) {
const auto & p1 = smoothed_reference_path.points.at(i);
Expand All @@ -2818,7 +2856,7 @@
(p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0;
const double passing_velocity = [=]() {
if (use_upstream_velocity) {
if (has_upstream_stopline && i > upstream_stopline_ind) {
if (upstream_stopline_idx_opt && i > upstream_stopline_idx_opt.value()) {
return minimum_upstream_velocity;
}
return std::max<double>(average_velocity, minimum_ego_velocity);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,10 @@ struct DebugData
std::optional<geometry_msgs::msg::Pose> collision_stop_wall_pose{std::nullopt};
std::optional<geometry_msgs::msg::Pose> occlusion_stop_wall_pose{std::nullopt};
std::optional<geometry_msgs::msg::Pose> occlusion_first_stop_wall_pose{std::nullopt};
std::optional<geometry_msgs::msg::Pose> pass_judge_wall_pose{std::nullopt};
std::optional<geometry_msgs::msg::Pose> first_pass_judge_wall_pose{std::nullopt};
bool passed_first_pass_judge{false};
bool passed_second_pass_judge{false};
std::optional<geometry_msgs::msg::Pose> second_pass_judge_wall_pose{std::nullopt};
std::optional<std::vector<lanelet::CompoundPolygon3d>> attention_area{std::nullopt};
std::optional<std::vector<lanelet::CompoundPolygon3d>> occlusion_attention_area{std::nullopt};
std::optional<lanelet::CompoundPolygon3d> ego_lane{std::nullopt};
Expand Down Expand Up @@ -256,8 +259,8 @@ struct IntersectionStopLines
size_t first_pass_judge_line{0};

/**
* second_pass_judge_line is before second_attention_stopline by the braking distance. if its
* value is calculated negative, it is 0
* second_pass_judge_line is before second_attention_stopline by the braking distance. if
* second_attention_lane is null, it is same as first_pass_judge_line
*/
size_t second_pass_judge_line{0};

Expand Down Expand Up @@ -344,6 +347,7 @@ class IntersectionModule : public SceneModuleInterface
double max_accel;
double max_jerk;
double delay_response_time;
bool enable_pass_judge_before_default_stopline;
} common;

struct TurnDirection
Expand Down Expand Up @@ -373,7 +377,6 @@ class IntersectionModule : public SceneModuleInterface
bool consider_wrong_direction_vehicle;
double collision_detection_hold_time;
double min_predicted_path_confidence;
double keep_detection_velocity_threshold;
struct VelocityProfile
{
bool use_upstream;
Expand Down Expand Up @@ -606,7 +609,7 @@ class IntersectionModule : public SceneModuleInterface

private:
rclcpp::Node & node_;
const int64_t lane_id_;
const lanelet::Id lane_id_;
const std::set<lanelet::Id> associative_ids_;
const std::string turn_direction_;
const bool has_traffic_light_;
Expand All @@ -621,6 +624,9 @@ class IntersectionModule : public SceneModuleInterface
bool is_permanent_go_{false};
DecisionResult prev_decision_result_{Indecisive{""}};
OcclusionType prev_occlusion_status_;
bool passed_1st_judge_line_while_peeking_{false};
std::optional<rclcpp::Time> safely_passed_1st_judge_line_time_{std::nullopt};
std::optional<rclcpp::Time> safely_passed_2nd_judge_line_time_{std::nullopt};

// for occlusion detection
const bool enable_occlusion_detection_;
Expand Down
Loading