Difference between revisions of "Projects:2018s1-181 BMW Autonomous Vehicle"

From Projects
Jump to: navigation, search
 
(36 intermediate revisions by 2 users not shown)
Line 1: Line 1:
'''Students:'''
+
==Students==
 +
Corey Miller (Electrical and Sustainable Energy)
  
Corey Miller
+
Kaifeng Ren (Electrical and Electronic)
  
Kaifeng Ren
+
Muhammad Sufyaan Bin Mohd Faiz (Electrical and Electronic)
  
Muhammad Sufyaan Bin Mohd Faiz
+
Ovini Amaya Perera (Electrical and Electronic)
  
Ovini Amaya Perera
+
Yiduo Yin (Electrical and Electronic)
  
Yiduo Yin
+
==Supervisors==
 +
Associate Professor Nesimi Ertugral
  
 +
Mr. Robert Dollinger
  
'''Supervisors:'''
+
==Project Description==
 +
With autonomous vehicles being the future of transportation, research and development into autonomous vehicle systems are necessary to ensure passenger safety meets the required standards. This project is one in a series of autonomous driving algorithm projects by the University of Adelaide supported by BMW with the end goal to produce a fully autonomous vehicle system. This project focuses on developing an autonomous driving algorithm that will be used to adjust the steering wheel of a BMW research vehicle. A model predictive controller will be designed and developed in MATLAB and SIMULINK that will track the vehicles position and adjust the steering wheel angle such that the vehicle can follow a provided reference path.
  
Assosciate Professor Nesimi Ertugral
+
The design of this controller consists of a reference path, the MPC and a vehicle model (modelling the lateral dynamics of the vehicle).
  
Mr Robert Dollinger
+
==Vehicle Model==
 +
[[File:BicycleModel.png|200px|thumb|right|Bicycle model to describe the lateral dynamics of a vehicle.]]
  
 +
The vehicle model used for the system will be summarized using state space representation: modelling the physical vehicle as a set of input, output and state variables (variables that change over time depending on the input variables at a specific instance). The benefits that state space representation has over other modelling techniques is that it allows input data from multiple sources to be used simultaneously in the same model to estimate a single dynamic vehicle parameter and provides a convenient way to analyses multiple inputs and outputs. Comparing this to the frequency domain, state-space representation is not limited to systems with linear components and zero initial conditions and is more efficient than having to write input × output number of Laplace transforms to describe the system.
  
'''Project Description:'''
+
[[File:SSM.PNG|200px|thumb|right|State space model used to represent the vehicle models lateral dynamics]]
  
In 2016, we have received a research vehicle from BMW and started to develop automated driving algorithms in 2017. This year we will focus on integration of automated driving functions. A test bench to validate and develop a hardware in the loop system for electric steering was also developed. This year, the setup requires improvements to withstand the high steering forces from the EPS (Electric Power Steering) rack. The test bench will also be used to test and validate various sensors, and they will be implemented, tested and validated in the test vehicle. The primary research focus will be given to enhancement of the vehicle control algorithm, including Model Predictive Control (MPC). An existing vehicle model will be used for offline implementation to test the performance of the controller and compare the performance. The three major steps involved in this project are:
+
To model the vehicle in state space representation, a linear single-track model (also known as the bicycle model) was used to describe the lateral dynamics of the vehicle. The bicycle model simplifies the dynamics of a vehicle by taking the front and rear axles and treating them as singular wheels. This simplifies the lateral dynamics of the vehicle by reducing the degrees of freedom from having 4 wheels to 2 wheels, hence fewer equations are required to describe the vehicle model.  
  
• Introduction to the already existing control and integration of Hardware in the loop test bench with existing control algorithms. A validated vehicle model will be used to simulate driving behaviour.
+
[[File:Parameters.PNG|200px|thumb|right|]]
 
• Integration of a position determination algorithm and integration of sensors in the vehicle and testing the algorithm in the real vehicle. The the algorithm will be enhanced using additional vehicle information
 
  
• Development of a MPC controller for vehicle control with integration inside the vehicle. o Analysis of the performance of the controller o Comparison to PID controller
+
The state vector used in the vehicle model consisted of the vehicle slip angle (β), yaw (ψ), yaw rate and the lateral position (y). This allowed for the calculations of the vehicles longitudinal and lateral positions and yaw at each timestep with respect to a steering angle input (𝛿).The parameters for the state space model can be seen in the calculated parameters table.
  
 +
[[File:VM.PNG|400px|thumb|center|Developed Simulink vehicle model based off the above state space representation]]
  
MPC algorithm we are going to develop in our project.
+
The developed simulink vehicle model based off this state space model can be broken into 3 seperate sections. Section 1 takes all the relevant parameters from the matlab script file and loads them into the model to be used. Section 2 calculates the state vector and Section 3 uses the parameters inside the state vector to calculate the longitudinal and lateral position of the vehicle.
[[File:]]
+
 
 +
==Model Predictive Controller==
 +
The model predictive controller subsystem takes the lateral position of the vehicle model as an input and compares it against the reference path's lateral position of where the vehicle be. Based off the deviation from where the vehicle is and where it should be, the MPC adjusts the steering wheel angle of the vehicle, turning the wheels to head the vehicle to follow the reference path. What makes model predictive control able to control a vehicle to follow reference path more accurately than other control strategies is its ability to "predict the future". During each timestep (in this projects case 20ms) the lateral position deviation problem is optimized over finite set of timesteps. This is known as the prediction horizon - how far the MPC sees into the future. For each of these future timesteps, the MPC calculates the required steering angle to optimize the deviation problem. The MPC then only executes finite range of these timestep steering angle commands. This is known as the control horizon - how long the MPC executes 1 optimization problem. The reason a control horizon does not execute all the prediction horizon estimated steering angles is that a contingency may occur (such as an object entering the vehicles path) that the optimization problem did not account for. Therefore at each timestep, a new optimization problem is solved with only the first few steps being sent to the steering wheel.
 +
 
 +
When designing the MPC submodule in MPC toolbox in MATLAB, a prediction horizon of 20 samples (0.4 seconds into the future) was used as it provided the MPC a clear understanding of the path ahead while maintaining fast processing speed. A control horizon of 1 sample was used as the performance of the module was not improved from increasing the control horizon.
 +
For passenger comfort, constraints were set on the steering angle output of the MPC that was being sent to the vehicle. This constraints included reducing how far the steering angle could turn from -25 degrees to +25 degrees, allowing for wide turns. The rate of how quickly the steering wheel turn was also constrained to 25 degrees per second, allowing for a smooth transition into a turn without the steering wheel rapidly changing the direction of the vehicle.
 +
 
 +
The diagram belows shows the fully connected MPC system with an input longitudinal velocity and reference path (consisting of a lateral position at each timestep) and outputting the lateral position and steering angle of the vehicle.
 +
 
 +
[[File:MPC.PNG|400px|thumb|center|Developed Simulink MPC Model]]
 +
 
 +
==Simulation Results==
 +
To test the performance of the MPC and vehicle model, the system was placed into 3 different scenarios that simulated real world traffic conditions. These scenarios were designed using Driving Scenario Designer MATLAB Application. All simulations were performed with a constant longitudinal velocity of 5m/s.
 +
Simulation 1 involved the vehicle performing a lane change maneuver in a double-laned road. 
 +
 
 +
[[File:Scenario1.jpg|300px|thumb|center|Scenario 1: Double lane change maneuver]]
 +
 
 +
From this simulation it can be seen that the vehicle was capable of following the reference path smoothly with minor steering angle adjustments. The maximum position deviation is approximately 1.5m, which can be improved upon with a more complex MPC and vehicle model.
 +
 
 +
[[File:Scenario2.jpg|300px|thumb|center|Scenario 2: Intersection right turn]]
 +
 
 +
Scenario 2 saw the vehicle perform a right turn at a adelaide intersection. From the simulation it can be seen that the vehicle deviates from the reference path again by approximately 1.5m. As clipping isnt observed in the steering angle plot, this is not a result of the turn being too tight, but from the vehicle model and MPC not being as complex due to the simplified vehicle dynamics.
 +
 
 +
[[File:Scenario3.jpg|300px|thumb|center|Scenario 3: Roundabout 3rd exit]]
 +
 
 +
Scenario 3 saw the vehicle entering and taking the 3rd exit when leaving a roundabout. This presents the biggest flaw in the current project model as the MPC cannot accomodate for changes in the longitudinal direction (changing in x-direction) such as a U-turn for example. As the mpc only tracks the lateral (y-position) of the vehicle, the vehicle begins drastically going off-course at the 3rd exit as the x-position decreases. It can also be seen that the vehicle is unable to perform such a tight turn as the steering angle is clipping its maximum range.
 +
 
 +
==Future Work==
 +
The MPC controller that was developed could only acquire satisfactory performance results when the speed is 18km/h (5m/s). In some cases, there will be approximately 1.5 meter deviation between the lateral position of the vehicle and the reference path. This deviation is a result of the vehicle model using simplified lateral vehicle dynamics. An example of how the dynamics could be improved comes from the front and rear tire forces. For small slip angles, the forces on the tire is assumed to be constant, hence the front and rear cornering stiffnesses are assumed constant. The tire forces on a vehicle are actually non-linear and hence a parameter estimator would be required to more accurately model this nonlinear vehicle dynamics. This parameter estimated could also be used as an input to the MPC along with the yaw of the vehicle to give the MPC more options in how to best optimise the steering angle output.
 +
 
 +
As explained above, a vehicles dynamics change with increasing speed, and hence is non-linear. This means that the linear MPC designed in this project will only be accurate for a certain range of speeds. In order to improve the performance of the controller, an adaptive MPC is required. This adaptive MPC would contain multiple MPC settings for multiple speed ranges. The adaptive MPC is then able to determine which model should be implemented at any given time for a specific vehicle speed.
 +
 
 +
As mentioned above, a coordinate manipulator submodule is required. This submodule would be responsible for detecting changes in the x-position and translating the coordinate system to allow the vehicle to perform U-turns.
 +
 
 +
==Conclusion==
 +
The aim of this project was to develop a model predictive controller capable of following a predetermined reference path. The controller system was designed using a vehicle model that described the linear lateral dynamics of the vehicle based off the simplified bicycle model. The MPC was constricted to having a steering angle output between -25 degrees and +25 degrees and a rate of change of steering angle of 25 degrees per second for passenger comfort. The simulation scenarios were designed to simulate real driving scenarios that the vehicle would encounter on the road. The controller was able to perform a double lane change maneuver effectively at 5m/s, making the controller suitable for lane-keeping assistance. However the controller was not able to follow a turning road to an acceptable standard as seen in Scenario 2 and 3. This could be due to the linear lateral dynamics of the vehicle not being accurate enough to describe the vehicles dynamics, meaning a nonlinear vehicle model or parameter-estimate is required or that the turn was too sharp for the vehicle to perform given its steering wheel constraints. In Scenario 3 it was seen that the MPC is unable to accomodate for changes in the longitudinal direction (change in x-direction) meaning that a coordinate transformation submodule is required when redesigning the controller. The next step in developing this MPC is the implementation of an adaptive model predictive controller, allowing for the controller to optimize the steering angle problem over a range of speeds instead of just 5m/s.

Latest revision as of 10:28, 22 October 2018

Students

Corey Miller (Electrical and Sustainable Energy)

Kaifeng Ren (Electrical and Electronic)

Muhammad Sufyaan Bin Mohd Faiz (Electrical and Electronic)

Ovini Amaya Perera (Electrical and Electronic)

Yiduo Yin (Electrical and Electronic)

Supervisors

Associate Professor Nesimi Ertugral

Mr. Robert Dollinger

Project Description

With autonomous vehicles being the future of transportation, research and development into autonomous vehicle systems are necessary to ensure passenger safety meets the required standards. This project is one in a series of autonomous driving algorithm projects by the University of Adelaide supported by BMW with the end goal to produce a fully autonomous vehicle system. This project focuses on developing an autonomous driving algorithm that will be used to adjust the steering wheel of a BMW research vehicle. A model predictive controller will be designed and developed in MATLAB and SIMULINK that will track the vehicles position and adjust the steering wheel angle such that the vehicle can follow a provided reference path.

The design of this controller consists of a reference path, the MPC and a vehicle model (modelling the lateral dynamics of the vehicle).

Vehicle Model

Bicycle model to describe the lateral dynamics of a vehicle.

The vehicle model used for the system will be summarized using state space representation: modelling the physical vehicle as a set of input, output and state variables (variables that change over time depending on the input variables at a specific instance). The benefits that state space representation has over other modelling techniques is that it allows input data from multiple sources to be used simultaneously in the same model to estimate a single dynamic vehicle parameter and provides a convenient way to analyses multiple inputs and outputs. Comparing this to the frequency domain, state-space representation is not limited to systems with linear components and zero initial conditions and is more efficient than having to write input × output number of Laplace transforms to describe the system.

State space model used to represent the vehicle models lateral dynamics

To model the vehicle in state space representation, a linear single-track model (also known as the bicycle model) was used to describe the lateral dynamics of the vehicle. The bicycle model simplifies the dynamics of a vehicle by taking the front and rear axles and treating them as singular wheels. This simplifies the lateral dynamics of the vehicle by reducing the degrees of freedom from having 4 wheels to 2 wheels, hence fewer equations are required to describe the vehicle model.

Parameters.PNG

The state vector used in the vehicle model consisted of the vehicle slip angle (β), yaw (ψ), yaw rate and the lateral position (y). This allowed for the calculations of the vehicles longitudinal and lateral positions and yaw at each timestep with respect to a steering angle input (𝛿).The parameters for the state space model can be seen in the calculated parameters table.

Developed Simulink vehicle model based off the above state space representation

The developed simulink vehicle model based off this state space model can be broken into 3 seperate sections. Section 1 takes all the relevant parameters from the matlab script file and loads them into the model to be used. Section 2 calculates the state vector and Section 3 uses the parameters inside the state vector to calculate the longitudinal and lateral position of the vehicle.

Model Predictive Controller

The model predictive controller subsystem takes the lateral position of the vehicle model as an input and compares it against the reference path's lateral position of where the vehicle be. Based off the deviation from where the vehicle is and where it should be, the MPC adjusts the steering wheel angle of the vehicle, turning the wheels to head the vehicle to follow the reference path. What makes model predictive control able to control a vehicle to follow reference path more accurately than other control strategies is its ability to "predict the future". During each timestep (in this projects case 20ms) the lateral position deviation problem is optimized over finite set of timesteps. This is known as the prediction horizon - how far the MPC sees into the future. For each of these future timesteps, the MPC calculates the required steering angle to optimize the deviation problem. The MPC then only executes finite range of these timestep steering angle commands. This is known as the control horizon - how long the MPC executes 1 optimization problem. The reason a control horizon does not execute all the prediction horizon estimated steering angles is that a contingency may occur (such as an object entering the vehicles path) that the optimization problem did not account for. Therefore at each timestep, a new optimization problem is solved with only the first few steps being sent to the steering wheel.

When designing the MPC submodule in MPC toolbox in MATLAB, a prediction horizon of 20 samples (0.4 seconds into the future) was used as it provided the MPC a clear understanding of the path ahead while maintaining fast processing speed. A control horizon of 1 sample was used as the performance of the module was not improved from increasing the control horizon. For passenger comfort, constraints were set on the steering angle output of the MPC that was being sent to the vehicle. This constraints included reducing how far the steering angle could turn from -25 degrees to +25 degrees, allowing for wide turns. The rate of how quickly the steering wheel turn was also constrained to 25 degrees per second, allowing for a smooth transition into a turn without the steering wheel rapidly changing the direction of the vehicle.

The diagram belows shows the fully connected MPC system with an input longitudinal velocity and reference path (consisting of a lateral position at each timestep) and outputting the lateral position and steering angle of the vehicle.

Developed Simulink MPC Model

Simulation Results

To test the performance of the MPC and vehicle model, the system was placed into 3 different scenarios that simulated real world traffic conditions. These scenarios were designed using Driving Scenario Designer MATLAB Application. All simulations were performed with a constant longitudinal velocity of 5m/s. Simulation 1 involved the vehicle performing a lane change maneuver in a double-laned road.

Scenario 1: Double lane change maneuver

From this simulation it can be seen that the vehicle was capable of following the reference path smoothly with minor steering angle adjustments. The maximum position deviation is approximately 1.5m, which can be improved upon with a more complex MPC and vehicle model.

Scenario 2: Intersection right turn

Scenario 2 saw the vehicle perform a right turn at a adelaide intersection. From the simulation it can be seen that the vehicle deviates from the reference path again by approximately 1.5m. As clipping isnt observed in the steering angle plot, this is not a result of the turn being too tight, but from the vehicle model and MPC not being as complex due to the simplified vehicle dynamics.

Scenario 3: Roundabout 3rd exit

Scenario 3 saw the vehicle entering and taking the 3rd exit when leaving a roundabout. This presents the biggest flaw in the current project model as the MPC cannot accomodate for changes in the longitudinal direction (changing in x-direction) such as a U-turn for example. As the mpc only tracks the lateral (y-position) of the vehicle, the vehicle begins drastically going off-course at the 3rd exit as the x-position decreases. It can also be seen that the vehicle is unable to perform such a tight turn as the steering angle is clipping its maximum range.

Future Work

The MPC controller that was developed could only acquire satisfactory performance results when the speed is 18km/h (5m/s). In some cases, there will be approximately 1.5 meter deviation between the lateral position of the vehicle and the reference path. This deviation is a result of the vehicle model using simplified lateral vehicle dynamics. An example of how the dynamics could be improved comes from the front and rear tire forces. For small slip angles, the forces on the tire is assumed to be constant, hence the front and rear cornering stiffnesses are assumed constant. The tire forces on a vehicle are actually non-linear and hence a parameter estimator would be required to more accurately model this nonlinear vehicle dynamics. This parameter estimated could also be used as an input to the MPC along with the yaw of the vehicle to give the MPC more options in how to best optimise the steering angle output.

As explained above, a vehicles dynamics change with increasing speed, and hence is non-linear. This means that the linear MPC designed in this project will only be accurate for a certain range of speeds. In order to improve the performance of the controller, an adaptive MPC is required. This adaptive MPC would contain multiple MPC settings for multiple speed ranges. The adaptive MPC is then able to determine which model should be implemented at any given time for a specific vehicle speed.

As mentioned above, a coordinate manipulator submodule is required. This submodule would be responsible for detecting changes in the x-position and translating the coordinate system to allow the vehicle to perform U-turns.

Conclusion

The aim of this project was to develop a model predictive controller capable of following a predetermined reference path. The controller system was designed using a vehicle model that described the linear lateral dynamics of the vehicle based off the simplified bicycle model. The MPC was constricted to having a steering angle output between -25 degrees and +25 degrees and a rate of change of steering angle of 25 degrees per second for passenger comfort. The simulation scenarios were designed to simulate real driving scenarios that the vehicle would encounter on the road. The controller was able to perform a double lane change maneuver effectively at 5m/s, making the controller suitable for lane-keeping assistance. However the controller was not able to follow a turning road to an acceptable standard as seen in Scenario 2 and 3. This could be due to the linear lateral dynamics of the vehicle not being accurate enough to describe the vehicles dynamics, meaning a nonlinear vehicle model or parameter-estimate is required or that the turn was too sharp for the vehicle to perform given its steering wheel constraints. In Scenario 3 it was seen that the MPC is unable to accomodate for changes in the longitudinal direction (change in x-direction) meaning that a coordinate transformation submodule is required when redesigning the controller. The next step in developing this MPC is the implementation of an adaptive model predictive controller, allowing for the controller to optimize the steering angle problem over a range of speeds instead of just 5m/s.