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(detection_area)!: add retruction feature #9255

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 @@ -12,15 +12,16 @@ This module is activated when there is a detection area on the target lane.

### Module Parameters

| Parameter | Type | Description |
| ---------------------------------- | ------ | -------------------------------------------------------------------------------------------------- |
| `use_dead_line` | bool | [-] weather to use dead line or not |
| `use_pass_judge_line` | bool | [-] weather to use pass judge line or not |
| `state_clear_time` | double | [s] when the vehicle is stopping for certain time without incoming obstacle, move to STOPPED state |
| `stop_margin` | double | [m] a margin that the vehicle tries to stop before stop_line |
| `dead_line_margin` | double | [m] ignore threshold that vehicle behind is collide with ego vehicle or not |
| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section) |
| `distance_to_judge_over_stop_line` | double | [m] parameter for judging that the stop line has been crossed |
| Parameter | Type | Description |
| ----------------------------------- | ------ | -------------------------------------------------------------------------------------------------- |
| `use_dead_line` | bool | [-] weather to use dead line or not |
| `use_pass_judge_line` | bool | [-] weather to use pass judge line or not |
| `state_clear_time` | double | [s] when the vehicle is stopping for certain time without incoming obstacle, move to STOPPED state |
| `stop_margin` | double | [m] a margin that the vehicle tries to stop before stop_line |
| `dead_line_margin` | double | [m] ignore threshold that vehicle behind is collide with ego vehicle or not |
| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section) |
| `distance_to_judge_over_stop_line` | double | [m] parameter for judging that the stop line has been crossed |
| `suppress_pass_judge_when_stopping` | bool | [m] parameter for suppressing pass judge when stopping |

### Inner-workings / Algorithm

Expand All @@ -47,7 +48,9 @@ endif
:get clear stop state duration;

if (clear stop state duration is more than state_clear_time?) then (yes)
:set current state GO;
if (suppress_pass_judge_when_stopping is false or ego is moving) then (yes)
:set current state GO;
endif
:reset clear stop state duration;
stop
else (no)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,4 @@
hold_stop_margin_distance: 0.0
distance_to_judge_over_stop_line: 0.5
enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
suppress_pass_judge_when_stopping: false
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
getOrDeclareParameter<double>(node, ns + ".hold_stop_margin_distance");
planner_param_.distance_to_judge_over_stop_line =
getOrDeclareParameter<double>(node, ns + ".distance_to_judge_over_stop_line");
planner_param_.suppress_pass_judge_when_stopping =
getOrDeclareParameter<bool>(node, ns + ".suppress_pass_judge_when_stopping");
}

void DetectionAreaModuleManager::launchNewModules(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,9 +111,11 @@
// Check state
setSafe(detection_area::can_clear_stop_state(
last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time));
if (isActivated()) {
state_ = State::GO;
last_obstacle_found_time_ = {};
if (!planner_param_.suppress_pass_judge_when_stopping || !is_stopped) {
state_ = State::GO;
}

Check warning on line 118 in planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

DetectionAreaModule::modifyPathVelocity increases in cyclomatic complexity from 17 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.

Check notice on line 118 in planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

DetectionAreaModule::modifyPathVelocity increases from 3 to 4 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ class DetectionAreaModule : public SceneModuleInterface
double state_clear_time;
double hold_stop_margin_distance;
double distance_to_judge_over_stop_line;
bool suppress_pass_judge_when_stopping;
};

DetectionAreaModule(
Expand Down
Loading