Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
1b94bee
removed redundant osc2 files
david-gasinski Jan 11, 2026
7c83653
removed redunant openscenario class
david-gasinski Jan 11, 2026
3990ca7
added loop to spawn ego for redunancy
david-gasinski Jan 11, 2026
57b56c3
bug fix; exit loop on successful ego spawn
david-gasinski Jan 11, 2026
f1bfbd3
fixed bug with autoware double restarting
david-gasinski Jan 11, 2026
bc504e3
updated JOSS paper
david-gasinski Jan 13, 2026
51aa4d0
Research Impact Statement updated
donghwan-shin Jan 13, 2026
5543156
updated JOSS paper to meet new reqs
david-gasinski Jan 15, 2026
b662bf7
merge
david-gasinski Jan 15, 2026
9cdc429
added route visualisation in CARLA
david-gasinski Jan 24, 2026
e1d29a1
fixed incorrect call to draw_line()
david-gasinski Jan 24, 2026
8aef6af
fixed passing tuple instead of carla.Transform
david-gasinski Jan 24, 2026
51abce8
fixed bug with incorrect call to draw_point()
david-gasinski Jan 24, 2026
a5d7a40
typo
david-gasinski Jan 24, 2026
09fea0d
adjust route visualiser line color to not interfere with traffic ligh…
david-gasinski Jan 24, 2026
15fd354
Update README with GPU compatibility details
david-gasinski Jan 28, 2026
9f3ceab
added code to force sensors to tick in carla at the same rate as auto…
david-gasinski Jan 31, 2026
6865c2e
Merge branch '110-joss-submission' of github.com:Intelligent-Testing-…
david-gasinski Jan 31, 2026
23ed32d
Merge branch 'main' into 110-joss-submission
david-gasinski Jan 31, 2026
ec16637
updated time ratio to track 1 / fixed_delta ticks
david-gasinski Jan 31, 2026
92a5c71
Merge branch '110-joss-submission' of github.com:Intelligent-Testing-…
david-gasinski Jan 31, 2026
a9657cd
push
david-gasinski Jan 31, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ Running CAWSR
CAWSR can both be ran `locally` or `distributed`. Due to the high-spec requirements, it is recommended to run distributed if you do not meet the following minimum specs:
- At least **10GB** VRAM and a modern GPU (2080 ti or newer)
- We currently supports 20 and 30 series GPUs. Compatibility with the 40 series is current WIP.

- At least **32GB** RAM
- A modern Intel or AMD CPU with at least 8 cores.

Expand Down
31 changes: 25 additions & 6 deletions cawsr.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
from srunner.scenarioconfigs.route_scenario_configuration import (
RouteScenarioConfiguration,
)
from srunner.tools.route_visualisation import visualise_route
from srunner.tools import route_manipulation
from srunner.objects.ego_vehicle import EgoVehicle
from srunner.tools.log import LogUtil
Expand Down Expand Up @@ -161,11 +162,24 @@ def run_scenario(
# update the world
CarlaDataProvider.set_world(self.carla_world)

logger.info("Spawning ego...")
ego = EgoVehicle(env_config)
actor = ego.spawn()
self.ego_vehicles.append(actor)
logger.info(f"Spawned ego with id: {actor.id}")
# attempt to spawn the ego 3 times for redundancy
max_attempts = 3
for attempt in range(max_attempts):
try:
logger.info("Spawning ego...")
ego = EgoVehicle(env_config)
actor = ego.spawn()
self.ego_vehicles.append(actor)
logger.info(f"Spawned ego with id: {actor.id}")
break # exit loop if successful
except Exception as e:
logger.error(f"Failed to spawn ego on attempt {attempt + 1}: {e}")
if attempt == max_attempts - 1:
logger.error(
"Failed to spawn ego: Terminating scenario. This is most likely an issue with CARLA"
)
raise
time.sleep(2)

# client must tick to spawn actors
self._tick_carla()
Expand Down Expand Up @@ -194,6 +208,9 @@ def run_scenario(
)
route_config.agent.set_global_plan(gps_route, route) # set agent route

# visualise the route in CARLA
visualise_route([waypoint[0] for waypoint in route])

ego.prepare_ego(route[0][0]) # set location to first waypoint

# allow the agent X ticks to initialize sensors and set the route
Expand Down Expand Up @@ -420,6 +437,7 @@ def _cawsr_process(
else:
seed = 0

env_config.iteration = run
scenario_process = multiprocessing.Process(
target=self.run_scenario, # need to catch connection exception
args=(
Expand All @@ -446,11 +464,12 @@ def _cawsr_process(
self.results_manager.cleanup_xml()

# copy over the recording from CARLA container
time.sleep(1) # ensure file is written
time.sleep(1) # ensure file is finished writing
CARLAManager.fetch_file(
"/home/carla/recording.log",
self.results_manager.last_scenario,
)
time.sleep(1) # allow some time for docker to copy it over

# fetch execution status of the scenario (failure or success)
status = result["status"]
Expand Down
26 changes: 22 additions & 4 deletions paper.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ bibliography: paper.bib

# Summary

`CAWSR` (**C**ARLA-**A**uto**W**are-**S**cenario **R**unner) facilitates the simulation-based testing of the open-source autonomous driving system, Autoware, within CARLA, the state-of-the-art open-source driving simulator. Building on existing tools, this project introduces a research-oriented testing framework for the execution of complex driving scenarios, as well as supporting implementation of a wide range of verification strategies.
`CAWSR` (**C**ARLA-**A**uto**W**are-**S**cenario **R**unner) facilitates the simulation-based testing of the open-source autonomous driving system, Autoware, within CARLA, the state-of-the-art open-source driving simulator. Building on existing tools, this project introduces a research-oriented testing framework for the execution of complex driving scenarios, as well as supporting the implementation of a wide range of verification strategies.

# Statement of Need

Expand Down Expand Up @@ -67,10 +67,23 @@ This facilitates a wide range of verification strategies based on common metrics
Lastly, it is worth noting that simulators can often introduce unintended nondeterminism, which leads to inconsistent test results [@9793395; @osikowicz2025empirically].
Therefore, `CAWSR` is designed to minimise such nondeterminism throughout the evaluation pipeline.

# Research Impact

# Tool Overview
`CAWSR` provides a significant research impact by bridging the gap between the widely-used CARLA simulator and the industry-grade Autoware ADS.
It addresses a critical bottleneck in the ADS testing research community by offering a modern replacement for the outdated Apollo/LGSVL workflow, which has lacked official support since 2022.

`CAWSR` is a fully synchronous testing framework that directly integrates the CARLA simulator, Scenario Runner (as the scenario executor), and Autoware (as the System Under Test) to facilitate autonomous driving testing research. The tool is distributed as a containerized deployment using Docker and currently supports two modes of operation:
It enhances research reproducibility by implementing a fully synchronous evaluation pipeline that minimises unintended nondeterminism in simulation-based testing.
To ensure community readiness and ease of use, it is distributed as a Docker container.

Furthermore, by adopting CARLA Leaderboard metrics, `CAWSR` enables researchers to directly compare Autoware with other state-of-the-art driving agents in the CARLA environment.
It provides an essential foundation for the systematic evaluation of various testing approaches for ADS.



# Software Design
<!-- I've renamed the "Tool Overview" section since it fits quite well here, and added a few justifications.-->

`CAWSR` is a fully synchronous testing framework that directly integrates the CARLA simulator, Scenario Runner (as the scenario executor), and Autoware (as the System Under Test) to facilitate autonomous driving testing research. The tool is distributed as a containerized deployment using Docker to manage complex dependencies and simplify the setup process. Currently, two modes of operation are supported:

1. *Scenario Generation Mode:* Enables the dynamic generation and execution of scenarios (e.g. iterative scenario generation) provided by a user-defined algorithm. This is particularly useful for assessing the performance of new simulation-based ADS testing techniques.
2. *Benchmark Mode:* Allows the execution of a predefined set of scenario definitions provided by the user. This is useful for standardised evaluations and comparisons between different driving agents.
Expand All @@ -85,7 +98,8 @@ The evaluation pipeline is engineered to be fully synchronous, minimising uninte

- JSON Parser: Translates the *scenario_definition* (see \autoref{fig:scenario_domain}) into a Behavior Tree (BT). It utilises Scenario Runner's *Atomic Behaviours* and *Atomic Conditions* as modular primitives to define discrete actions (e.g., spawning pedestrians) and logic triggers.

- ScenarioManager: Orchestrates the simulation loop by evaluating the BT to update actor states and triggering CARLA simulation ticks. Execution terminates based on CARLA Leaderboard criteria [@carla_leaderboard], as summarised in \autoref{tab:termination_criteria}. Post-execution, the module calculates the Driving Score (DS) according to the official leaderboard metrics.
<!-- David: Citing SR for added transparency, since this class is natively part of it -->
- ScenarioManager [@carla_scenario_runner_2025]: Orchestrates the simulation loop by evaluating the BT to update actor states and triggering CARLA simulation ticks. Execution terminates based on CARLA Leaderboard criteria [@carla_leaderboard], as summarised in \autoref{tab:termination_criteria}. Post-execution, the module calculates the Driving Score (DS) according to the official leaderboard metrics.

- Agent and CarlaBridge: The Agent manages the ROS2 connection to Autoware. At each timestep, the CarlaBridge [@carlaautowarebridge] transforms CARLA snapshots and sensor data into the Autoware coordinate system. Autoware processes these inputs to issue control commands, which the Agent then applies to the ego vehicle.

Expand All @@ -106,6 +120,10 @@ This model is based on the format introduced by Scenario Runner, facilitating su
To summarise, `CAWSR` provides ADS testing research community an easy to use Autoware evaluation pipeline.
We hope that this work can facilitate the evaluation of new testing approaches on a state of the art driving system.

# AI Usage Disclosure

<!-- David: I used AI to help explain concepts some concepts and generate short code snippets to get me started (mostly about ROS2 and networking). Is this the correct way to phrase it? -->
Generative AI tools were used in this work solely to support high-level research concepts and structural ideas. All software implementation, including the source code, architecture, and deployment scripts, was authored entirely by the researchers without AI assistance.

# Acknowledgements

Expand Down
Binary file modified paper.pdf
Binary file not shown.
9 changes: 6 additions & 3 deletions srunner/autoagents/autoware_agent.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
from srunner.autoagents.autoware_carla_interface.carla_autoware import (
InitializeInterface,
)
from srunner.tools.CARLA_manager import CARLAManager

import threading
import rclpy
Expand Down Expand Up @@ -46,6 +47,7 @@ def setup(self, config: EnvironmentConfig) -> None:
rclpy.init(args=None)

self.config = config
self.tick_delta = CARLAManager.FIXED_DELTA_SECONDS

# initialise autoware state object
self.autoware_state = autoware_state.AutowareState("ego_vehicle", None)
Expand All @@ -56,7 +58,9 @@ def setup(self, config: EnvironmentConfig) -> None:
self.carla_interface = InitializeInterface(self.config, self._node)

self.state_node = state_node.StateNode(self.autoware_state, self._node_state)
self.state_node.reset_autoware(self.config.town, self.config.ego_name)
if config.iteration == 1:
# only reset autoware on the first run
self.state_node.reset_autoware(self.config.town, self.config.ego_name)

self.route_node = route_node.RouteNode(self.autoware_state, self._node_state)
self.autoware_node = autoware_node.AutowareNode(
Expand Down Expand Up @@ -92,7 +96,6 @@ def set_route(self) -> None:
self.goal_pose_world = self._global_plan_world_coord[-1]
self.waypoints_world = self._global_plan_world_coord[:-1]

# autoware cannot handle many waypoints, becomes unreliable
n_waypoints = len(self.waypoints_world)
segment_size = int(n_waypoints / 3)

Expand Down Expand Up @@ -172,7 +175,7 @@ def run_step_init(self) -> bool:
def run_step(self) -> None:
"""Tick method containing all logic based on autoware state"""
self.counter += 1
if self.counter % 20 == 0:
if self.counter % int(1 / self.tick_delta) == 0:
logger.info(
f"Ticked 1 second game-time, actual tick is {(time.perf_counter_ns() - self.last_tick) / 1e6}ms"
)
Expand Down
28 changes: 18 additions & 10 deletions srunner/autoagents/autoware_carla_interface/carla_ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
from geometry_msgs.msg import Pose
from geometry_msgs.msg import PoseWithCovarianceStamped
import numpy
import datetime
import pathlib
from rosgraph_msgs.msg import Clock
from sensor_msgs.msg import CameraInfo
Expand Down Expand Up @@ -54,6 +53,8 @@
SensorInterface,
)

from srunner.tools.CARLA_manager import CARLAManager


class carla_ros2_interface(object):
def __init__(self, node):
Expand All @@ -80,9 +81,11 @@ def __init__(self, node):
"pose": 2,
}
self.publish_prev_times = {
sensor: datetime.datetime.now() for sensor in self.sensor_frequencies
sensor: GameTime.get_time() for sensor in self.sensor_frequencies
}

self.delta = CARLAManager.FIXED_DELTA_SECONDS # delta in seconds

self.ros2_node = node

self.clock_publisher = self.ros2_node.create_publisher(Clock, "/clock", 10)
Expand Down Expand Up @@ -137,6 +140,11 @@ def __init__(self, node):
self.pub_camera_info = self.ros2_node.create_publisher(
CameraInfo, "/sensing/camera/traffic_light/camera_info", 1
)

# self.pub_camera_yolo_info = self.ros2_node.create_publisher(
# CameraInfo, "/sensing/camera/0/camera_info", 1
# )

elif sensor["type"] == "sensor.lidar.ray_cast":
if sensor["id"] in self.sensor_frequencies:
self.pub_lidar[sensor["id"]] = self.ros2_node.create_publisher(
Expand Down Expand Up @@ -165,9 +173,9 @@ def __call__(self):
return control

def checkFrequency(self, sensor):
time_delta = (
datetime.datetime.now() - self.publish_prev_times[sensor]
).microseconds / 1000000.0
# implement frequency check based on game time
time_delta = GameTime.get_time() - self.publish_prev_times[sensor]

if 1.0 / time_delta >= self.sensor_frequencies[sensor]:
return True
return False
Expand All @@ -185,7 +193,7 @@ def lidar(self, carla_lidar_measurement, id_):
"""Transform the received lidar measurement into a ROS point cloud message."""
if self.checkFrequency(id_):
return
self.publish_prev_times[id_] = datetime.datetime.now()
self.publish_prev_times[id_] = GameTime.get_time()

header = self.get_msg_header(frame_id="velodyne_top_changed")
fields = [
Expand Down Expand Up @@ -258,7 +266,7 @@ def pose(self):
"""Transform odometry data to Pose and publish Pose with Covariance message."""
if self.checkFrequency("pose"):
return
self.publish_prev_times["pose"] = datetime.datetime.now()
self.publish_prev_times["pose"] = GameTime.get_time()

header = self.get_msg_header(frame_id="map")
out_pose_with_cov = PoseWithCovarianceStamped()
Expand Down Expand Up @@ -335,7 +343,7 @@ def camera(self, carla_camera_data):

if self.checkFrequency("camera"):
return
self.publish_prev_times["camera"] = datetime.datetime.now()
self.publish_prev_times["camera"] = GameTime.get_time()

image_data_array = numpy.ndarray(
shape=(carla_camera_data.height, carla_camera_data.width, 4),
Expand All @@ -356,7 +364,7 @@ def imu(self, carla_imu_measurement):
"""Transform a received imu measurement into a ROS Imu message and publish Imu message."""
if self.checkFrequency("imu"):
return
self.publish_prev_times["imu"] = datetime.datetime.now()
self.publish_prev_times["imu"] = GameTime.get_time()

imu_msg = Imu()
imu_msg.header = self.get_msg_header(frame_id="tamagawa/imu_link_changed")
Expand Down Expand Up @@ -416,7 +424,7 @@ def ego_status(self):
if self.checkFrequency("status"):
return

self.publish_prev_times["status"] = datetime.datetime.now()
self.publish_prev_times["status"] = GameTime.get_time()

# convert velocity from cartesian to ego frame
trans_mat = numpy.array(self.ego_actor.get_transform().get_matrix()).reshape(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@

from srunner.scenariomanager.carla_data_provider import CarlaDataProvider

logger = logging.getLogger("scenario-runner")


# Sensor Wrapper for Agent
class SensorReceivedNoData(Exception):
Expand Down Expand Up @@ -54,7 +56,7 @@ def __call__(self, data):
elif isinstance(data, GenericMeasurement):
self._parse_pseudo_sensor(data, self._tag)
else:
logging.error("No callback method for this sensor.")
logger.error("No callback method for this sensor.")

# Parsing CARLA physical Sensors
def _parse_image_cb(self, image, tag):
Expand Down Expand Up @@ -216,6 +218,13 @@ def setup_sensors(self, vehicle, debug_mode=False):
yaw=sensor_spec["spawn_point"]["yaw"] + 0.0364,
)

bp.set_attribute(
"sensor_tick", str(round(1.0 / sensor_spec["publish_frequency"], 2))
)
logger.info(
f"Sensor {sensor_spec['id']} tick rate set to {str(round(1.0 / sensor_spec['publish_frequency'], 2))}"
)

# create sensor
sensor_transform = carla.Transform(sensor_location, sensor_rotation)
sensor = CarlaDataProvider.get_world().spawn_actor(
Expand Down
12 changes: 8 additions & 4 deletions srunner/autoagents/autoware_carla_interface/objects/sensors.json
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@
},
"image_size_x": 1920,
"image_size_y": 1080,
"fov": 90.0
"fov": 90.0,
"publish_frequency": 11.0
},
{
"type": "sensor.lidar.ray_cast",
Expand All @@ -32,7 +33,8 @@
"upper_fov": 10.0,
"lower_fov": -30.0,
"rotation_frequency": 20,
"noise_stddev": 0.0
"noise_stddev": 0.0,
"publish_frequency": 11.0
},
{
"type": "sensor.other.gnss",
Expand All @@ -44,7 +46,8 @@
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
}
},
"publish_frequency": 2.0
},
{
"type": "sensor.other.imu",
Expand All @@ -56,7 +59,8 @@
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
}
},
"publish_frequency": 50.0
}
]
}
1 change: 1 addition & 0 deletions srunner/scenarioconfigs/environment_configuration.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,3 +26,4 @@ def __init__(self) -> None:
self.ego_spawn: carla.Transform | None = None
self.sensor_config: list[DefaultSensor] = []
self.route_id: int = 0
self.iteration: int = 0
Loading
Loading