Carla simulation results of Zeus controller as following:
Fig.1 Zeus Controller's Carla simulation results
Fig.2 Comparison diagram of ego vehicle trajectory and reference trajectory
Combining Fig.1 and Fig.2, the ego vehicle controlled by the Zeus controller basically drives along the target trajectory. There is only a significant error in the section where the curvature of the target trajectory changes greatly, but it is still within the allowable range. The following are the specific error values.
Fig.3 Zeus controller error
Fig.4 Reference trajectory curvature
Combining Fig.3 and Fig.4, simulation conclusions are as following:
(1) On road segments with a curvature of less than
(2) On road segments with a curvature greater than
Tab.1 Average Errors of Coordinate Transformation
| distance error(m) | yaw_angle error( |
curvature error( |
velocity error(m/s) | acceleration error(%) |
|---|---|---|---|---|
| 0.2 | 7.4 | 0 | 58.3 |
Above Table 1 presents the average errors (across 12 test cases) of the Cartesian coordinate values
Install carla ROS Bridge in Ubuntu environment, and then clone the repository to the "carla-ros-bridge/catkin_ws/src/ros-bridge" directory.
- carla_sensor_result: Python ROS node, used to obtain information in the Carla simulator, including ego vehicle's state, obstacle information, etc.
- zeus_common: C++ ROS package, implemented some class and function definitions shared by planner and controller modules, including the representation of ego vehicle and object, coordinate system transformation, etc.
- zeus_library: C++ static library, which is the functions' implementation of zeus_common.
- zeus_config: It stores some configuration files to facilitate the reading of ROS nodes, which can avoid multiple compilations during debugging and test.
- zeus_launch: launch files for each module.
- zeus_display: C++ ROS node, used to receive and publish relevant information to display in rviz.
- zeus_calibration: C++ ROS node, used to calibrate velocity and acceleration in different threshold and brake, make threshold-brake table for longitudinal control. The calibration results are stored in this directory "zeus/zeus_controller/data/pid_control".
- zeus_controller: C++ ROS node, including LQR controller based on vehicle dynamics for lateral control, and PID controller based on segmented control strategy for longitudinal control
- scenario_files: .xosc files, scenario files used in simulation.
In order to be closer to real-world vehicle operating environment, this project employs C++ code programming and utilizes ROS for inter process communication, relying on Carla simulator to complete verification. The overall architecture and data flow diagram of the project are illustrated in Fig.5.The Carla simulator operates the scenario file to provide simulation environment, while the library named carla-ros-bridge connects the Carla simulation environment with ROS nodes.
The carla_sensor_result node simulates sensor acquisition of the ego vehicle state and surrounding environment information, publishing these as ROS messages. The zeus_controller node, serving as the core module of this project, subscribes ego vehicle state, processes it through the LQR Controller and PID Controller, and publishes control signals including throttle, brake, and steer. Upon subscribing these control signals, the carla-ros-bridge updates the ego vehicle pose within Carla, thereby completing the control loop.
To enhance the zeus_controller's responsiveness, certain computations -- such as the LQR feedback matrix K and throttle-brake calibration table -- are precomputed offline. During real-time operation, these values are retrived via table lookups. Additionally, commonly used functions shared between controller and planner -- such as coordinate transformations between Frenet and Cartesian -- are implemented as static libraries in zeus_library directory to enable multi-module accessibility. Please refer to Fig.5 for more details.
Fig.5 Zeus Project Architecture
roslaunch carla_ros_bridge carla_ros_bridge.launch
python scenario_runner.py --openscenario /home/saxijing/carla-ros-bridge/catkin_ws/data/reference_point/zeus_calibration_06.xosc
roslaunch carla_sensor_result carla_sensor_result.launch
rosrun zeus_calibration calibrater>calibration.txt
roslaunch zeus_launch controller.launch>launch_out.txt
catkin_make -DCATKIN_WHITELIST_PACKAGES="zeus_controller"
rivz(optional):
rosrun zeus_display displayLane
rosrun tf static_transform_publisher 0 0 0 0 0 0 map world 10
LQR test scenario: zeus_control_test07flat.xosc
Threshold -brake calibration/PID test scenario: zeus_calibration_06.xosc
Overoll test and display: zeus_control_test01.xosc




