Followings are the demo videos showing the performance of improved controller.
Demo: turn left - 90-degree sharp left turn, Town01
Demo: turn right - 90-degree sharp right turn, Town01
The above demo is using the tuned MPC controller with turning ratio (in bridge) tuned. This is the default co-simulation control performance that this project aims to provide.
To achieve the above performance, turning ratio is set as the following:
self.right_turn_ratio = 0.7
self.left_turn_ratio = 0.85
The MPC controller parameters:
matrix_q: 3.0
matrix_q: 0.0
matrix_q: 18.45
matrix_q: 0.0
matrix_q: 30.0
matrix_q: 10.0
matrix_r: 3.25
matrix_r: 1.75
First, you should set up the co-simulation environment according to the setup doc: Getting Started.
Then, replace the following files in Apollo 8.0 with the modified files provided in this repo:
modules/control/conf/control_conf.pb.txt
modules/control/controller/mpc_controller.cc
modules/control/controller/mpc_controller.h
Compared with original Apollo 8.0 code (Apollo 8.0), the modified control code made the following improvements:
modules/control/conf/control_conf.pb.txt
The above file is the key configuration file for setting up the controller, including the relation of how the acceleration can be transformed to throttle or brake signal. However, the original configuration has several bugs including the too low acceleration, incorrect acc-to-throttle mapping, etc.
modules/control/controller/mpc_controller.cc
modules/control/controller/mpc_controller.h
The above file is the implementation of the Model Predicted Control (MPC) in Apollo, which is an advanced controller. Several bugs have been discovered in the original MPC controller, and they were fixed in this repo. These bugs include the inconsistent choice of planning point, lack of look-ahead time for planning query, redundant feedback on final control signal, etc.
If you are interested, the following page can be helpful for understanding the Apollo controller (It is Apollo 9.0, but key ideas are identical to 8.0).
Apollo Control Module Introduction
Following are the detailed report of discoverd bugs:
Due to the complexity of this co-simulation (e.g, complexity of the Apollo ADS, complex dynamics in Carla), the current controller is still far from being perfect. If you find the controller unsatisfying, you are encouraged to tune the controller as well. Following are some suggestions:
-
Directly tune the percentage of the steering signal that is actually applied by Carla. By default, the left turn and right turn signal is tuned with 70% and 85% weight, respectively (the default steer signal tends to overshoot at turns).
-
Modify the configuration file (control_conf.pb.txt) based on your experimental results.
-
Try different controllers: change active_controllers in control_conf.pb.txt from MPC_CONTROLLER to LAT_CONTROLLER, LON_CONTROLLER, then Apollo will apply MPC controller instead.
-
Modify the controller code (e.g., fixing more bugs which you find). These codes include lat_controller.cc, lon_controller.cc, mpc_controller.cc
It is very challenging to get a good controller in co-simulation. The Apollo code can be buggy, not to mention the implementation problems and new challenes brought by Carla. It would be very helpful for the community if you can also contribute to this co-simulation project.