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

Merged
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,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.

terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
Expand Down Expand Up @@ -88,8 +88,8 @@
stop_obstacle_hold_time_threshold : 1.0 # maximum time for holding closest stop obstacle

# hysteresis for cruise and stop
obstacle_velocity_threshold_from_cruise_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
obstacle_velocity_threshold_from_stop_to_cruise : 3.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
obstacle_velocity_threshold_from_cruise_to_stop : 1.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]
obstacle_velocity_threshold_from_stop_to_cruise : 1.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]

# if crossing vehicle is determined as target obstacles or not
crossing_obstacle:
Expand Down
Loading