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(obstacle_cruise_planner): tune obstacle_cruise_planner for cruising front NPCs in dense urban ODD scenarios #1166

Conversation

ahmeddesokyebrahim
Copy link
Contributor

@ahmeddesokyebrahim ahmeddesokyebrahim commented Sep 12, 2024

Description

Fixes :

Related links

Parent Issue :

Tests performed

Before this PR

UC-NTR-005-0001

2024-09-12.21-04-35_before_UC-NTR-005-0001.mp4

UC-NTR-001-0008

2024-09-12.21-13-38_before_UC-NTR-001-0008.mp4

UC-VRU-002-0002_case1

2024-09-12.21-18-36_before_UC-VRU-002-0002_case1.mp4

UC-VRU-002-0002_case2

2024-09-12.21-20-08_before_UC-VRU-002-0002_case2.mp4

After this PR

UC-NTR-005-0001

2024-09-12.20-00-49_after_UC-NTR-005-0001.mp4

UC-NTR-001-0008

2024-09-12.20-07-11_after_UC-NTR-001-0008.mp4

UC-VRU-002-0002_case1

2024-09-12.20-13-30_after_UC-VRU-002-0002_case1.mp4

UC-VRU-002-0002_case2

2024-09-12.20-15-39_after_UC-VRU-002-0002_case2.mp4

Notes for reviewers

Interface changes

ROS Topic Changes

N.A

ROS Parameter Changes

Parameter Name Default Value Update Description
safe_distance_margin 4.0 m - Lowering the safe distance margin enabling less -ve acceleration and hence and less drop of ego vehicle velocity while slowing down for cruising a front overtaking NPC
obstacle_velocity_threshold_from_cruise_to_stop 1.0 m/s - Lowering the velocity threshod from cruise to stop for better handling some situations in dense urban ODD
- Lowering the this threshold below obstacle_velocity_threshold_from_stop_to_cruise to prevent chattering between cruise and stop
obstacle_velocity_threshold_from_stop_to_cruise 1.5 m/s - Lowering the the velocity threshold hysteresis from cruise to obstacle stop so that obstacle_cruise_planner is not performing high -ve acceleration once the VRU is overlapping with ego trajectory and allowing the ego vehicle to cruise the front VRU not always triggering obstacle stop for it

Effects on system behavior

  • Improving obstacle_cruise_planner so that it is handing overtaking then slowing down NPC in dense urban ODD scenarios will better -ve acceleration and velocity drop while slowing down.
  • Improving obstacle_cruise_planner behavior in cruising scenarios, mitigating any mitigate any unnecessary long safe distance ego and npc and satisfying and following RSS distance.
  • Enhancing the obstacle_cruise_planner to effectively handle scenarios where vulnerable road users (VRUs) suddenly maneuver and overlap with the ego vehicle's trajectory in dense urban operational design domains (ODDs) will improve deceleration and velocity adjustments, resulting in more human-like driving behavior.

Pre-review checklist for the PR author

The PR author must check the checkboxes below when creating the PR.

In-review checklist for the PR reviewers

The PR reviewers must check the checkboxes below before approval.

  • The PR follows the pull request guidelines.
  • The PR has been properly tested.
  • The PR has been reviewed by the code owners.

Post-review checklist for the PR author

The PR author must check the checkboxes below before merging.

  • There are no open discussions or they are tracked via tickets.
  • The PR is ready for merge.

After all checkboxes are checked, anyone who has write access can merge the PR.

…tance and velocity hysteresis thresholds from obstalce to stop and vice versa to handle front npc cruising scenarios in dense urban odd

Signed-off-by: Ahmed Ebrahim <[email protected]>
@brkay54
Copy link
Member

brkay54 commented Sep 20, 2024

I tested the scenarios in scenario-dev branch which includes this commit, and I can confirm that all scenarios related this improvement passed: Internal Link
cc @mitsudome-r

@@ -12,7 +12,7 @@
idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s]
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
safe_distance_margin : 6.0 # This is also used as a stop margin [m]
safe_distance_margin : 4.0 # This is also used as a stop margin [m]
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a TIER IV's opinion. For safety when the ego stops for the front vehicle, the distance between the ego and the front vehicle should be comparatively large like 6.0m, and we feel dangerous with 4.0m for autonomous driving.
Do you still think this value should be 4.0m?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for your comment @takayuki5168 -san.
I will try in the following to explain why we - as Dense Urban ODD Planning & Control team- think it would be ok to decrease this value.

  • Moderate Vehicle Speed: The maximum speed for this change is capped at 15 km/h, which is relatively low. At such speeds, the braking distance required is significantly shorter than at higher speeds.

  • Braking Feasibility: Under normal road conditions and with a smooth deceleration rate, a 4-meter stopping distance is more than sufficient for the vehicle to come to a full stop safely.

  • Efficient Perception-Reaction Time: Based on current knowledge, Autoware’s perception-reaction time is between 600-800 ms (correct us if we are wrong). Combined with the 2-second idling time used in the RSS equation, this allows ample time for the vehicle to detect, process, and execute a safe stop within the 4-meter margin.

  • Currently, with the 6-meter margin, the test cases applying RSS are consistently failing because Autoware is maintaining a greater distance from the vehicle ahead than necessary. This excessive gap is impacting the system's ability to function optimally in dense urban environments.

Given these factors, reducing the stopping distance from 6 meters to 4 meters is a well-supported adjustment. This allows for improved vehicle performance in dense urban environments without compromising safety.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The way we feel in the simulation and the real environment are totally different, but we, TIER IV don't have suitable evidence to set the parameter to 6, so we're fine with 4 for now.
Let me comment someday when we come across the dangerous case with the new parameter in the real environment, although internally at TIER IV we will keep 6 to avoid the additional verification.

brkay54 pushed a commit that referenced this pull request Sep 30, 2024
…tance and velocity hysteresis thresholds from obstalce to stop and vice versa to handle front npc cruising scenarios in dense urban odd

#1166
Signed-off-by: Ahmed Ebrahim <[email protected]>
@ahmeddesokyebrahim ahmeddesokyebrahim merged commit 6c0733a into autowarefoundation:main Sep 30, 2024
16 of 17 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants