Test Results of the Autonomous Emergency Braking (AEB) Module in Real Life #5020
Replies: 3 comments 4 replies
-
@ismetatabay thank you for showing these tests in a very comprehensive and detailed way. I would like to suggest increasing the time horizon for MPC path prediction before directly increasing the the emergency stop’s target acceleration, the reason is that, with very high emergency stop accelerations, vehicles behind the ego might not react on time and hit the rear of the ego. Also, 2.5 seconds time horizon might not be enough to effectively brake and prevent a collision at higher speeds. In simulations, I have found 4.5 seconds to be a good value for the time horizon for MPC path prediction. I would also recommend not increasing the IMU prediction time horizon too much because this path tends to not be very accurate when the ego is taking a curve and you might have predicted paths that don't really represent what the ego vehicle will do. [See video example of Large IMU path time horizon] cap-.2024-05-17-12-09-54.mp4I would also recommend you make sure the "a_ego_min" param of the AEB module matches the emergency stop’s target acceleration value. I look forward to seeing the rest of your tests! |
Beta Was this translation helpful? Give feedback.
-
@ismetatabay Thank you very much for sharing these tests. I look forward to the document being finished and getting some rosbag data if possible. Regarding the test; 2.1.9 Test - 9: Autonomous Drive on Route B at a Velocity of 30 km/h. Other thing I wanted to mention is that, RSS distance is calculated using a reaction time "t" (default 1 second) and an extra margin "m" (default 2 meters). So the RSS distance would have been calculated as rss = Ve * t + m + (Ve^2) / 2ae. Where Ve is ego velocity (3.61 m/s ~ 13 kmph) and ae is the minimum acceleration (that you set to - 5 m/ss) So rss would be rss = 3.61 m/s * 1(s) + 2m + (3.61^2) / 10 = 3.61 + 2m + 1.3m ~ 6.9m Note: I did not include the front vehicle's speed in the calculation, but just to give you an idea where most of the rss distance value comes from. Please look at the README part talking about rss distance for more info. Seeing that the vehicle in front was located 5.86m in front of ego, it makes sense the emergency brakes activated, I would advice to reduce the reaction time and the margin instead of increasing the a_ego_min so much (you can do that by changing the "longitudinal_offset" and "t_response" params) if you want to decrease the rss_distance value. Other thing I wanted to ask is if you are using the pacmod interface? The pacmod_interface uses a default emergency acceleration (regardless of what parameters you set for the mrm_emergency_stop_operator), So, I am wondering if you felt or not the change in deceleration when you changed the mrm param value for emergency brake? If you want to use the mrm_emergency_stop_operator's emergency brake values, you need to set "use_external_emergency_brake" to true on the pacmod interface params |
Beta Was this translation helpful? Give feedback.
-
Hello @danielsanchezaran, thank you for your detailed explanations of the situation. We will check the NPC speed during overtakes and upload the bag files soon if you'd like to review them as well. Decreasing the RSS distance is possible, as you mentioned, by adjusting the response time and offset parameters. However, I'm not sure if Test 8 will succeed after this update. I know that the AEB module operates around a velocity of 15 km/h, but I would like to use it at 30 km/h, as 15 km/h is too slow for city driving. We will test the decreased longitudinal offset and response time parameters and try some overtake scenarios again. By the way, we are not using Pacmod; we are using our interface for driving. We noticed a difference between -2.5 and -5.0, which made it feel like an emergency stop after this update. Thank you again for detailed answer 💯 |
Beta Was this translation helpful? Give feedback.
-
Test Results of the Autonomous Emergency Braking (AEB) Module in Real Life
1. Introduction
Purpose and Scope of Testing: This report presents the Autonomous Emergency Brake (AEB) Module Performance results at the YTU Test Environment (see 1.1 Test Environment for Route information). The tests have been conducted with Leo Drive’s Autonomous Vehicles and Obstacles, as seen in the image below.
We used soft & light obstacle during our tests instead of real NPC vehicles because we wanted to test AEB in obstacle stop tests when localization is lost. To do this, we enabled the use of the IMU path, as the MPC prediction isn’t calculated while driving out of the lane. In the image below, this situation is demonstrated: green rectangles indicate the footprints of the MPC prediction, and blue rectangles indicate the IMU prediction path. MPC cannot calculate the predicted path if unexpected events occur like lost localization.
To conduct tests, the motion_planner module (either
obstacle_cruise_planner
orobstacle_stop_planner
, our vehicle usesobstacle_cruise_planner
) is also disabled to prevent obstacle stops with motion planning modules. With this update, vehicles can only be stopped by the AEB module when encountering static obstacles on the path.1.1 Test Environment
Route A
This route runs between the starting point and the ending point marked on the map image below. An obstacle has been placed on the route to test the vehicle's AEB functions at different speeds and with various parameters. The route is approximately 0.2 km long.
Route B
This route is approximately 1.54 km long. General driving is conducted on this route to test the parameters changed for the vehicle's AEB functions. This route was chosen considering the vehicle and pedestrian traffic within the campus.
2. Test Results
Before starting the AEB module tests, we tested Autonomous Driving on Route B with the
use_imu_path
set to True to ensure IMU noise doesn’t produce a false positive emergency in normal autonomous driving. We used the SBG Ellipse D’s internal IMU as described in autowarefoundation/autoware.universe#8114 in our test vehicle, and the driving was completed without any emergencies. Additionally, we enabled thesurround_obstacle_checker
module (only for the front) to hold the vehicle after it stops for an obstacle.2.1.1 Test - 1: 10 km/h Obstacle Stop Test with Default Parameters
The test was conducted with the default parameters of
autonomous_emergency_braking
andmrm_emergency_stop
. However, the vehicle hit the obstacle because the predicted paths were too short in this case. When the object was detected in the predicted path, the distance was already shorter than the RSS distance, triggering the emergency.Additionally, the default
mrm_emergency_stop
module'starget_acceleration
parameter is set to -2.5 with a target jerk of -1.5. Our vehicle can follow this emergency stop request, but it is not sufficient to avoid a collision. Therefore, we increased the prediction time horizon values for both MPC and IMU to extend the prediction length. We might consider incorporating this update into the default parameters.2.1.2 Test - 2: 10 km/h Obstacle Stop Test with Extended Increased Time Horizon
mpc_prediction_time_horizon:2.0
&imu_prediction_time_horizon:2.0
We set the
mpc_prediction_time_horizon
andimu_prediction_time_horizon
parameters to 2.0, and the ego vehicle was able to stop at 10 km/h velocity.With the increased prediction time horizon of the IMU and MPC, the emergency was activated approximately 1.5 meters earlier (from 3.50 to 5.27 meters), allowing our vehicle to stop as demonstrated in the image below.
2.1.3 Test - 3: 15 km/h Obstacle Stop Test with Last Parameters
Test 3 yielded results similar to Test 2, with the vehicle stopping in front of a static obstacle at a velocity of 15 km/h.
2.1.4 Test - 4: 20 km/h Obstacle Stop Test with Last Parameters
The obstacle was hit again at a 20 km/h velocity. The distance between the ego vehicle and the obstacle was around 7 meters when the emergency was triggered. However, the default emergency stop acceleration of -2.5 m/s² did not provide the feel of an emergency brake. To address this, we increased the emergency stop’s target acceleration from -2.5 to -5.0 m/s² at Test 5.
2.1.5 Test - 5: 20 km/h Obstacle Stop Test with Increased Emergency Stop Acceleration
Test 4 demonstrated that the distance between the ego vehicle and the obstacle was approximately 7 meters when the collision was detected. Since our velocity was 20 km/h (equivalent to ~5.55 m/s), we decided to set the target acceleration and jerk of the
mrm_emergency_stop_operator
parameters to -2.5 m/s² and -5.0 m/s², respectively.With this update, the vehicle can stop before the obstacle without hitting it, as seen in the following image.
2.1.6 Test - 6: 25 km/h Obstacle Stop Test with Last Parameters
The obstacle was hit again at a velocity of 20 km/h. To overcome this issue, we increased the prediction time horizon values to 2.5 for MPC and IMU predictions after Test 6.
2.1.7 Test - 7: 25 km/h Obstacle Stop Test with Increased Time Horizon to 2.5
By increasing the time horizon values to 2.5, the ego vehicle can stop before an obstacle at a velocity of 25 km/h.
However, the distance between the vehicle and the obstacle is greater than in the previous tests. This situation demonstrated that the RSS distance is calculated to be more than the actual value. After realizing this, we set the
a_ego_min
acceleration parameter value from -3.0 to -5.0, as in themrm_emergency_stop_operator
parameter file, before starting Test 8.2.1.8 Test - 8: 30 km/h Obstacle Stop Test with
a_ego_min
= -5.0 m/s²a_ego_min
is set to -5.0 m/s².After setting the actual emergency value of the ego vehicle to the a_ego_min parameter from AEB, the vehicle was able to stop before the obstacle without being too far away.
Leo.Drive.s.AV.AEB.Test.-.2024_07_18.mp4
2.1.9 Test - 9: Autonomous Drive on Route B at a Velocity of 30 km/h
After tuning the AEB for a maximum velocity profile of 30 km/h, we enabled the
obstacle_cruise_planner
as the motion planner to test the latest tune on Route B during regular autonomous driving. However, the vehicle triggered an emergency while driving at 13 km/h because the calculated RSS distance was shorter than the actual distance between the EGO vehicle and the NPC vehicle. We had already set thea_ego_min parameter
to -5.0, which shortens the RSS distance, but it wasn't enough to prevent the unnecessary emergency trigger.2.1.10 Test - 10: Autonomous Drive on Route B at a Velocity of 30 km/h with Suggested Parameters
a_ego_min
is set to -4.0 m/s²,t_response
is set to 0.5 s,longitudinal_offset
is set to 1.0 m andmpc_prediction_time_horizon
is set to 3.5 s.With this test, we updated the parameters according to Daniel-san's suggestions as follows:
With this parameter update, we performed a test similar to Test 9, and the vehicle didn't trigger an emergency due to the AEB package. However, these parameters will be tested with the Test 8 ROS 2 bag file.
2.1.11 Test - 11: 30 km/h Obstacle Stop Test with Suggested Parameters
These parameters promote a decrease in the RSS distance while additionally increasing the predicted path of the MPC. However, since in test 8 with the previous parameters the vehicle stopped too close to the obstacle, with the new RSS distance, the vehicle hit the object despite the increased MPC prediction range.
Tests after the discussions in the Planning & Control WG Meeting on 2024/08/01
2.1.12 Test - 12: Autonomous Drive on Route B at a Velocity of 30 km/h (cut-in scenario)
New Default Parameters
With the following PR, some of the default values of AEB are updated, and we applied similar cut-in tests to observe performance.
During this test, the AEB module triggers an emergency due to overtaking by the NPC vehicle. When the emergency is triggered, the NPC vehicle is approximately 10 meters away (Video 1), while the calculated RSS distance is 10-15 meters. Thus, even though the NPC vehicle is 10 meters away, the ego vehicle will still trigger an emergency due to the RSS distance
2.1.13 Test - 13: 20 km/h Obstacle Stop Test with New Default Parameters
This test demonstrated that, with the default parameters, the AEB can stop the ego vehicle when it encounters an obstacle at a velocity of 20 km/h. However, with the initial default parameters before this PR, the ego vehicle was unable to stop for an obstacle at a velocity of 10 km/h.
2.1.14 Test - 14: 30 km/h Obstacle Stop Test with New Default Parameters
Using the default parameters, the ego vehicle collided with the obstacle at a velocity of 30 km/h.
Conclusion
The tests demonstrate that the AEB package works as expected if we update the default value of
mpc_prediction_time_horizon
as Daniel-san suggested. However, due to the RSS distance calculation, an emergency can be triggered when the ego vehicle is overtaken by an NPC. In this situation, it is challenging to find a balance between stopping for a static obstacle at 30 km/h and handling the overtaking scenario.Possible Upgrades
Beta Was this translation helpful? Give feedback.
All reactions