First Place Solution in Spring 2023 Simulation Racing Series
Written by Aaron Xie, this paper describes his team’s experience and thought process for their first place solution in the Spring 2023 Simulation Racing Series Competition with teammate Tristan Needham.
The code for the solution can be found here: https://github.com/vanconywhale/ROARSpring2023
A video of the solution doing a full runthrough of the map (without shortcuts) can be found below.
Table of Contents
Introduction
In the ROAR Spring 2023 simulation competition, an updated version of the Berkeley major map was used. It now contained invisible barriers that prevented the vehicle from leaving the paved track, and some parts (including the “sudden jump in the road” mentioned in my previous report) appear to have been smoothed out to create a more comfortable driving experience. For this competition, I decided to build off of my previous solution, modifying the agent to fit the new map’s parameters and finetuning its controller.
Strategy
The Berkeley major map contains two distinct regions: downtown Berkeley and the hills above Berkeley. Downtown mostly contains straightaways and sharp 90 degree turns, while the hills contain more winded roads that climb up and down. Thus, I decided to create two separate throttle controllers for the two regions. In the first region, the controller would account for sharp turns, and in the second region, the controller would account for sharp turns and wide turns that still require the vehicle to slow down in order to pass the route safely.
Design
For the downtown region (region 1), the controller is designed to drive at full throttle when it is
safe to do so. Otherwise, it will brake:
if self.region == 1
if sharp_error < 0.68 or current_speed <= 90:
throttle = 1
brake = 90
else:
throttle = -1
brake = 1
Two factors determine the safety of the car. “sharp_error” measures the latitudinal error between
the car and a far lookahead waypoint. If the error is too high, it indicates that there is a sharp turn ahead. If the car is also under a certain speed (90 in this case), it is also slow enough to full throttle as well regardless of the shape of the track.
For the hills region (region 2), more constraints on the throttle controller are added to provide
the car a speedy but also safe drive:
elif sharp_error >= 0.67 and current_speed > 70:
throttle = 0
brake = 0.4
elif wide_error > 0.09 and current_speed > 92: # wide turn
throttle = max(0, 1 - 6*pow(wide_error + current_speed*0.003, 6))
brake = 0
else:
throttle = 1
brake = 0
The first condition, similar to the controller in region 1, accounts for sharp, narrow turns that occasionally do occur in the hills. The second condition variably reduces the throttle using a power function based on the car’s latitudinal lookahead error and its current speed.
Manual transmission was also used to maximize speed. This formula from Daniel Chuang’s previous winning (and open-sourced!) solution was employed to set the gear:
gear = max(1, (int)((current_speed - 2*pitch) / 60))
Testing
The specific values for the error and speed limits in the throttle controllers above were optimized from manually test-running the agent through the respective regions. In the hills region (region 2), there were some rare unusual turns that the throttle controller couldn’t account for, resulting in the car crashing. To resolve these extraordinary spots, a waypoint was recorded for each one of these spots. Once the vehicle was close enough to the spot, the controller would force the car to brake for a very small amount of time, slowing it down enough to make the turn safely:
waypoint = self.waypoint_queue_brake[0] # 5012 is weird bump spot
dist = self.agent.vehicle.transform.location.distance(waypoint.location)
if dist <= 5:
self.brake_counter = 1
# print(self.waypoint_queue_brake[0])
self.waypoint_queue_brake.pop(0)
if self.brake_counter > 0:
throttle = -1
brake = 1
self.brake_counter +=1
if self.brake_counter >= 4:
self.brake_counter = 0
In addition to optimizing the parameters for the throttle controllers, the PID and lookahead configuration values were modified for the vehicle to follow the track more closely. Specifically, the PID values were raised at lower speeds, making the vehicle more responsive to turns, and the lookahead values were generally reduced to prevent the vehicle from “clipping”, or trying to make a turn too early and hitting the edge of the track.
Conclusion
I would like to thank my school teammate Tristan Needham for taking interest in the ROAR racing competition and suggesting ideas to improve our previous solutions. I would also like to thank Dr. Yang and the entire research team at ROAR for introducing me to autonomous driving, supporting me along the way in discovering this unique field of artificial intelligence, and providing me the opportunity to both become a high school ambassador for ROAR and experience the Indy Autonomous Challenge in-person.
In the future, I plan to contribute to ROAR’s initiatives by helping develop its simulation projects
and competitions!