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

DO NOT MERGE: fix(intersection): consider braking distance for pass judge #950

Closed
Closed
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 @@ -1079,13 +1079,15 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
const bool keep_detection =
(vel_norm < planner_param_.collision_detection.keep_detection_vel_thr);
const bool was_safe = std::holds_alternative<IntersectionModule::Safe>(prev_decision_result_);
const bool disable_sudden_stop = true;
// if ego is over the pass judge line and not stopped
if (is_over_default_stop_line && !is_over_pass_judge_line && keep_detection) {
RCLCPP_DEBUG(
logger_, "is_over_default_stop_line && !is_over_pass_judge_line && keep_detection");
// do nothing
} else if (
(was_safe && is_over_default_stop_line && is_over_pass_judge_line && is_go_out_) ||
(was_safe && (is_over_default_stop_line || disable_sudden_stop) && is_over_pass_judge_line &&
is_go_out_) ||
is_permanent_go_) {
// is_go_out_: previous RTC approval
// activated_: current RTC approval
Expand Down
2 changes: 2 additions & 0 deletions planning/behavior_velocity_intersection_module/src/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,12 +415,14 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
intersection_stop_lines_temp.occlusion_peeking_stop_line =
intersection_stop_lines_temp.default_stop_line;
}
/*
if (
intersection_stop_lines_temp.occlusion_peeking_stop_line >
intersection_stop_lines_temp.pass_judge_line) {
intersection_stop_lines_temp.pass_judge_line =
intersection_stop_lines_temp.occlusion_peeking_stop_line;
}
*/

IntersectionStopLines intersection_stop_lines;
intersection_stop_lines.closest_idx = intersection_stop_lines_temp.closest_idx;
Expand Down
Loading