guardstrikelab / carla_apollo_bridge

This project aims to provide a data and control bridge for the communication between the latest version of Apollo and Carla.
Apache License 2.0
336 stars 100 forks source link

[Bug Report] Reporting several bugs that will affect the vehicular control #159

Open PhilWallace opened 1 year ago

PhilWallace commented 1 year ago

Hello there. Many thanks for the effort on this project. I’ve been testing the control module of Apollo via this co-simulation bridge, and discovered several bugs that would affect the performance of vehicle in simulation.

—-----------------------------------------------------------------------------------------------------------------------

Bug 01: Vehicle physics are not properly set in simulation.

Currently, the bridge code spawns the ego vehicle but does not set the properties of the vehicle. Setting these properties can make the control performance better. Specifically, following code can be added after the ego vehicle is spawned, and before the control command is executed:

def modify_vehicle_physics(self, actor):
    try:
        actor.set_simulate_physics(True)
        physics_control = actor.get_physics_control()
        physics_control.use_sweep_wheel_collision = True
        physics_control.damping_rate_zero_throttle_clutch_engaged = 0.35
        actor.apply_physics_control(physics_control)
    except Exception:
        pass

This function (derived from another bridge project: https://github.com/MaisJamal/carla_apollo_bridge/blob/f6d803aae82c296a5bb9de6ef0a7f66908f16aba/examples/manual_control_13.py#L667C5-L682C17) will enable the physics feature of the vehicle, and adjust some parameters. However, this is just a temporal fix and I believe there are room for improvement on the car physics.

Reference about the Carla car physics: https://carla.readthedocs.io/en/latest/tuto_G_control_vehicle_physics/

—-----------------------------------------------------------------------------------------------------------------------

Bug 02: Buggy configuration of the control module.

The control module of Apollo will read the configuration file and load it to initialize the controller. Specifically, by default it will load this file:

https://github.com/ApolloAuto/apollo/blob/master/modules/control/conf/control_conf.pb.txt

However, this configuration is buggy from the following aspects:

(a). There are contradictions in tire mass. The default value provided in https://github.com/ApolloAuto/apollo/blob/master/modules/control/conf/control_conf.pb.txt is 520: image

However, another file indicates that this value is 530 for the vehicle (Lincoln2017MKZ) to be simulated: image

Further investigation is needed to determine which value is correct, and to get more accurate vehicle parameters for simulation.

—-----------------------------------------------------------------------------------------------------------------------

The “calibration_table” in the config file is essential in control module. It will translate the desired acceleration (output of the control calculation module) to the actual vehicle action on vehicle (throttle or brake). This table is consist of various triplets containing three values: speed, acceleration, and command: image

For example, the above triplet indicate that, when the speed of the vehicle is 0 m/s, to produce a -1.43m2/s acceleration, a command of -35% on brake is given to the actuator.

There are the following bugs on this config file:

(b). It is obvious that the sign of the control command and acceleration should be the same (e.g., If I want acceleration, I will need to step on the throttle). However, some configurations do not follow this rule. For example, in the following config, a command of -17% on brake is given, when the vehicle needs an acceleration of 0.38 m/s: image

Vice versa, some de-accelerations are translated into stepping on throttle: image

(c). Another obvious fact is that under the same speed, if I want a greater acceleration, then I will surely need to give a more bigger control on throttle. However, the config file does not follow this correlation. For example, in the following part: image

If I want an acceleration of 2.89 m2/s, a command of 70% on throttle is needed. However, If I want an acceleration of 2.9 m2/s (greater than 2.89 m2/s), I will only need 70% on throttle, which is obviously intuitive and incorrect. Many other similar cases are in this config file.

(d). I found that the acceleration commands given in this “calibration_table” are overall too low to produce a prompt acceleration. I raised the overall value of the command values, and the control performance gets better.

(e). There are Abrupt changes in the control signals for acceleration (throttle) and deceleration (brake), due to the very unsmooth transition of the control command in this table.

I tried to modify this config file to solve the above inconsistencies, and the control performance gets better. I will share my modified config file later. By the way, another bridge project has also provided the customized config file: https://github.com/MaisJamal/carla_apollo_bridge/blob/f6d803aae82c296a5bb9de6ef0a7f66908f16aba/apollo_control/control_conf.pb.txt

—-----------------------------------------------------------------------------------------------------------------------

Apollo provides two methods for controlling: PID+LQR, or the MPC control. These codes are under https://github.com/ApolloAuto/apollo/tree/master/modules/control/controller . The function of these controller code is to output the control command (i.e., acceleration and steering angle), based on the input trajectory (which is the output of the Planning module), and the current vehicle state.

Bug 03: Steering control is filtered twice.

In the MPC control code (https://github.com/ApolloAuto/apollo/blob/master/modules/control/controller/mpc_controller.cc), the output steering command will be filtered twice when FLAGS_set_steer_limit == True: image

As shown above, both line 450 and 454 are filtering the steer_angle signal. Line 450 should be deleted.

Bug 04: Filters for controller input error are initialized but not used.

In the MPC control code (https://github.com/ApolloAuto/apollo/blob/master/modules/control/controller/mpc_controller.cc), two filters for lateral and heading error is set, but never used (line 165 and line 167): image

In comparison, these filters were set and used in lat_controller.cc (line 811): image

I think such inconsistency on the implementation of the filtering process is a bug.

Bug 05: Regarding the trajectory point to follow, inconsistent points were chosen for the calculation of lateral and longitudinal error.

The logic of the control module is to first select a point on the planned trajectory, and then calculate the distance (i.e., error) between the current vehicle state and the state on this planned point. However, in the MPC control code (https://github.com/ApolloAuto/apollo/blob/master/modules/control/controller/mpc_controller.cc), there is an inconsistency problem on the selection of the trajectory point to follow. Specifically, when calculating the lateral error, the “nearest point by position” is selected: image

However, when calculating the longitudinal error, the “nearest point by time” is selected: image

Generally, the “nearest point by position” and “nearest point by time” are not the same point. Due to such inconsistent selection, the MPC controller will keep calculating the control output based on a NON-EXISTING trajectory point.

It would be recommended to unified the selected of the queried point (e.g., calculating the lateral and longitudinal error both based on the “nearest point by time”).

Bug 06: Inconsistency between the controller frequency (100hz) and the state update frequency (20hz).

By default, the control module (PID+LQR, and MPC) is running with the frequency around 100hz (update the control command every 0.01s). However, the state of the vehicle is updated with the frequency of only 20hz (update every 0.05s): image

As a result, other modules will fail to provide timely state data for control module. In this case, the control module will keep calculating and output control commands based on the outdated state. Regarding the difference on frequency, there are about 80% control commands are the outdated control command that should not be implemented.

Possible fix is to modify the code to output the control command ONLY WHEN the state is updated, otherwise the controller will output the previous command.

This bug exists in both the PID+LQR controller and the MPC controller.

Bug 07: Trajectory point is queried based on in-program running time, instead of the state update time.

Taking MPC controller for example, the query point is selected based on the current running time (line 683): image

However, this “current_controltime” is not the actual of the current vehicle state. Particularly, the vehicle state provider “injector->vehicle_state()” contains the correct corresponding timestamp of the current state, and this timestamp should be used as the input of the line 685.

This bug exists in both the PID+LQR controller and the MPC controller.

Bug 08: The controller output is added with redundant feedback, which violates the MPC design (i.e., optimization process and predictive nature).

In the MPC control code, the acceleration is consist of two parts: image

“acc_feedback” is the acceleration calculated by the MPC algorithm, and “debug->acceleration_reference()” is the expected acceleration that the controller aims to achieve.

In the closed-loop control like PID, it is correct to directly use “debug->acceleration_reference()” and then rely on the closed-loop mechanism to adjust the control process. However, such solution should not be implemented to the MPC control: In MPC control, the control command is a calculated value based on the finely-tuned MPC algorithm, with the predictive nature and optimization process. In this case, “debug->acceleration_reference()” is not needed, and “acc_feedback” should be the final result (of course this relies on a finely-tuned MPC, which could be a challenge).

Similar problem exists in the steering control command (solely using “steer_angle_feedback” should be sufficient): image

Bug 09: Planned trajectory goes off-road.

Control module relies on the planning trajectory, so it is critical to ensure the correctness of the trajectory. However, it is found that the trajectory can often go-off road, making the vehicle hit the road curb: image

I tried to tune the parameters of the planning module but it doesn’t work. Maybe some additional codes should be added to the planning module to prevent this situation.

Related issue: https://github.com/ApolloAuto/apollo/issues/15091

Bug 10: Unrealistic planning.

The planning trajectory, particularly the planned speed can be very unsmooth and the vehicle cannot follow the trajectory well. This issue will also affect the performance of the control module.

Details on this issue: https://github.com/ApolloAuto/apollo/issues/14985

Bug 11: Abrupt changes exist in the planned trajectory points.

I have plotted the following figures to present the actual trajectory (red dot line) and the planned trajectory (blue solid line) that was queried during the calculation process in the control module: image

In another word, the blue line is the input to the control module. However, it is observed that sudden changes frequently appear in the process. This is because the output of the trajectory is constantly changing based on the current vehicle state, but it is not well smoothed and then fed to the control module.

Such sudden changes also appear in other states (i.e., heading angle, velocity and acceleration):

image

—-----------------------------------------------------------------------------------------------------------------------

Thanks for reading this report. I have personally tried to fix these bugs and have made some progress. However, the control module is still farm form perfect (or to say, farm from being adequate)...

I've noticed that very few previous ADAS + Simulator has good control performance. Particularly, Apollo + LGSVL simulation does not activate control module at all, and LGSVL is already abandoned. Autoware + Carla simulation also have similar control problems. Openpilot + Carla has flaw but it might have the best performance among all.

I hope this report will help this project. : )

XiaoFei9704 commented 1 year ago

Thank you so much for your work and this bug report. We are still investing in the development and maintenance of this project, and your effort will help us a lot. We'll analyze these problems one by one in the near future and try to solve them. Each progress will be updated here, and thanks again!

PhilWallace commented 11 months ago

Thank you so much for your work and this bug report. We are still investing in the development and maintenance of this project, and your effort will help us a lot. We'll analyze these problems one by one in the near future and try to solve them. Each progress will be updated here, and thanks again!

Hello. I saw that in a recent demo, the car can move smoothly. May I ask what fixes have been implemented? Many thanks!

I opened a new issue to discuss this question: https://github.com/guardstrikelab/carla_apollo_bridge/issues/172