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)!: disable the exception behavior in the private areas #5229

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,6 +19,7 @@
# enable_front_car_decel_prediction: false # By default this feature is disabled
# assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning
timeout_private_area: 3.0 # [s] cancel stuck vehicle stop in private area
enable_private_area_stuck_disregard: false #In the intersections which labeled as "private area", the obstacle vehicles judged as "stuck" are neglected if this param is set as true.

collision_detection:
state_transit_margin_time: 1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
*/
ip.stuck_vehicle.timeout_private_area =
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.timeout_private_area");
ip.stuck_vehicle.enable_private_area_stuck_disregard =
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.enable_private_area_stuck_disregard");

ip.collision_detection.min_predicted_path_confidence =
getOrDeclareParameter<double>(node, ns + ".collision_detection.min_predicted_path_confidence");
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 better: Lines of Code in a Single File

The lines of code decreases from 1428 to 1421, 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.
//
// 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 @@ -96,10 +96,6 @@
occlusion_stop_state_machine_.setMarginTime(planner_param_.occlusion.stop_release_margin_time);
occlusion_stop_state_machine_.setState(StateMachine::State::GO);
}
{
stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area);
stuck_private_area_timeout_.setState(StateMachine::State::STOP);
}
{
temporal_stop_before_attention_state_machine_.setMarginTime(
planner_param_.occlusion.before_creep_stop_time);
Expand Down Expand Up @@ -918,16 +914,13 @@
const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets);
if (stuck_detected && stuck_stop_line_idx_opt) {
auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value();
const bool stopped_at_stuck_line = stoppedForDuration(
stuck_stop_line_idx, planner_param_.stuck_vehicle.timeout_private_area,
stuck_private_area_timeout_);
const bool timeout = (is_private_area_ && stopped_at_stuck_line);
if (!timeout) {
if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) {
if (
default_stop_line_idx_opt &&
fromEgoDist(stuck_stop_line_idx) < -planner_param_.common.stop_overshoot_margin) {
stuck_stop_line_idx = default_stop_line_idx_opt.value();
}
} else {
return IntersectionModule::StuckStop{
closest_idx, stuck_stop_line_idx, occlusion_peeking_stop_line_idx_opt};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class IntersectionModule : public SceneModuleInterface
bool enable_front_car_decel_prediction; //! flag for using above feature
*/
double timeout_private_area;
bool enable_private_area_stuck_disregard;
} stuck_vehicle;
struct CollisionDetection
{
Expand Down Expand Up @@ -253,7 +254,6 @@ class IntersectionModule : public SceneModuleInterface

// for stuck vehicle detection
const bool is_private_area_;
StateMachine stuck_private_area_timeout_;

// for RTC
const UUID occlusion_uuid_;
Expand Down
Loading