Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
54 changes: 39 additions & 15 deletions simulator/autoware_carla_interface/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -114,21 +114,22 @@ Ego vehicle commands from Autoware are processed through the `autoware_raw_vehic

All the key parameters can be configured in `autoware_carla_interface.launch.xml`.

| Name | Type | Default Value | Description |
| ------------------------ | ------ | --------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `host` | string | "localhost" | Hostname for the CARLA server |
| `port` | int | "2000" | Port number for the CARLA server |
| `timeout` | int | 20 | Timeout for the CARLA client |
| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle |
| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) |
| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] |
| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA |
| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) |
| `use_traffic_manager` | bool | False | Boolean flag to set traffic manager in CARLA |
| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` |
| `sensor_kit_name` | string | "carla_sensor_kit_description" | Name of the sensor kit package to use for sensor configuration. Should be the \*\_description package containing config/sensor_kit_calibration.yaml |
| `sensor_mapping_file` | string | "$(find-pkg-share autoware_carla_interface)/config/sensor_mapping.yaml" | Path to sensor mapping YAML configuration file |
| `config_file` | string | "$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `autoware_raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. |
| Name | Type | Default Value | Description |
| --------------------------------- | ------ | --------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `host` | string | "localhost" | Hostname for the CARLA server |
| `port` | int | "2000" | Port number for the CARLA server |
| `timeout` | int | 20 | Timeout for the CARLA client |
| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle |
| `vehicle_type` | string | "vehicle.toyota.prius" | Blueprint ID of the vehicle to spawn. The Blueprint ID of vehicles can be found in [CARLA Blueprint ID](https://carla.readthedocs.io/en/latest/catalogue_vehicles/) |
| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] |
| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA |
| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) |
| `use_traffic_manager` | bool | False | Boolean flag to set traffic manager in CARLA |
| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` |
| `sensor_kit_name` | string | "carla_sensor_kit_description" | Name of the sensor kit package to use for sensor configuration. Should be the \*\_description package containing config/sensor_kit_calibration.yaml |
| `use_light_weight_sensor_mapping` | bool | False | If True, uses `sensor_mapping_light_weight.yaml` instead of the default `sensor_mapping.yaml` to reduce simulator load. See [Sensor Mapping (CARLA-specific)](#2-sensor-mapping-carla-specific) for details. |
| `sensor_mapping_file` | string | "$(find-pkg-share autoware_carla_interface)/config/sensor_mapping.yaml" | Path to sensor mapping YAML configuration file. When `use_light_weight_sensor_mapping` is True, this defaults to `config/sensor_mapping_light_weight.yaml`. |
| `config_file` | string | "$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml" | Control mapping file to be used in `autoware_raw_vehicle_cmd_converter`. Current control are calibrated based on `vehicle.toyota.prius` Blueprints ID in CARLA. Changing the vehicle type may need a recalibration. |

### Sensor Configuration

Expand Down Expand Up @@ -183,6 +184,29 @@ sensor_mappings:

For CARLA sensor parameters, see [CARLA Sensor Reference](https://carla.readthedocs.io/en/latest/ref_sensors/).

##### Light-Weight Sensor Mapping

For machines with limited GPU/CPU resources, an alternative `config/sensor_mapping_light_weight.yaml` is provided to reduce simulator load. Compared to the default mapping, it:

- Uses a **single front camera** (`CAM_FRONT`) instead of the 6-camera 360-degree setup, with a wider FOV (120°) and lower resolution (1080x720) to roughly cover the area in front of the vehicle.
- Lowers sensor frequencies (e.g., LiDAR/camera at 10 Hz instead of 11 Hz).
- Keeps the same LiDAR, IMU, and GNSS configuration as the default mapping.

When enabled via `use_light_weight_sensor_mapping:=True`, the launch file also skips the `image_transport` republish nodes for the disabled cameras and the `multi_camera_combiner` node automatically.

Example usage:

```bash
ros2 launch autoware_launch e2e_simulator.launch.xml \
map_path:=$HOME/autoware_map/Town01 \
vehicle_model:=sample_vehicle \
sensor_model:=carla_sensor_kit \
simulator_type:=carla \
use_light_weight_sensor_mapping:=True
```

Note that with this configuration, features that depend on the surround cameras (such as the multi-camera RViz view) are unavailable.

### World Loading

The `carla_ros.py` sets up the CARLA world:
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
# Light-weight sensor mapping configuration for Autoware to CARLA
# Reduced-load variant of sensor_mapping.yaml for machines with limited GPU/CPU resources:
# - Single front camera (CAM_FRONT) with 120 deg FOV at 1080x720, instead of the 6-camera 360 deg setup
# - Same LiDAR, IMU, and GNSS configuration as sensor_mapping.yaml
# Enable via the `use_light_weight_sensor_mapping` launch argument.

# Default sensor kit to use (must be the _description package containing config/sensor_kit_calibration.yaml)
default_sensor_kit_name: carla_sensor_kit_description

sensor_mappings:
# LiDAR sensor
velodyne_top_base_link:
carla_type: sensor.lidar.ray_cast
id: top
ros_config:
frame_id: velodyne_top
topic_base: /sensing/lidar/top
topic_suffix: /pointcloud_before_sync
frequency_hz: 10
qos_profile: best_effort
parameters:
range: 100
channels: 64
points_per_second: 300000
upper_fov: 10.0
lower_fov: -30.0
rotation_frequency: 20
noise_stddev: 0.0

CAM_FRONT/camera_link:
carla_type: sensor.camera.rgb
id: CAM_FRONT
ros_config:
frame_id: CAM_FRONT/camera_optical_link
topic_image: /sensing/camera/CAM_FRONT/image_raw
topic_info: /sensing/camera/CAM_FRONT/camera_info
frequency_hz: 10
qos_profile: reliable
parameters:
image_size_x: 1080
image_size_y: 720
fov: 120.0

# IMU sensor
tamagawa/imu_link:
carla_type: sensor.other.imu
id: imu
ros_config:
frame_id: tamagawa/imu_link
topic: /sensing/imu/tamagawa/imu_raw
frequency_hz: 50
qos_profile: reliable
parameters:
noise_accel_stddev_x: 0.0
noise_accel_stddev_y: 0.0
noise_accel_stddev_z: 0.0
noise_gyro_stddev_x: 0.0
noise_gyro_stddev_y: 0.0
noise_gyro_stddev_z: 0.0

# GNSS sensor
gnss_link:
carla_type: sensor.other.gnss
id: gnss
ros_config:
frame_id: map
topic: /sensing/gnss/pose_with_covariance
frequency_hz: 2
qos_profile: reliable
parameters:
noise_alt_stddev: 0.0
noise_lat_stddev: 0.0
noise_lon_stddev: 0.0
noise_alt_bias: 0.0
noise_lat_bias: 0.0
noise_lon_bias: 0.0
covariance:
# Position covariance (variance in meters²)
position_variance: 0.01 # 0.1m standard deviation
# Orientation covariance (variance in radians²)
orientation_variance: 1.0 # Large uncertainty - orientation not measured by GNSS

# Sensor name normalization rules
normalization:
strip_suffixes:
- _base_link
- _link
- /camera_link

# Enabled sensors list
enabled_sensors:
# LiDAR
- velodyne_top_base_link

# Cameras (6 for 360-degree coverage)
- CAM_FRONT/camera_link

# IMU and GNSS
- tamagawa/imu_link
- gnss_link
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,15 @@
<log message="[CARLA Interface] Map Path: '$(var map_path)' -> Loading CARLA Map: '$(var carla_map)'"/>

<!-- Sensor Configuration -->
<arg
name="use_light_weight_sensor_mapping"
default="False"
description="Whether to use the light-weight sensor mapping YAML that reduces the number of sensors and their frequencies for performance optimization"
/>
<arg name="sensor_kit_name" default="carla_sensor_kit_description" description="Name of the sensor kit package containing calibration"/>
<arg name="sensor_mapping_file" default="$(find-pkg-share autoware_carla_interface)/config/sensor_mapping.yaml" description="Path to sensor mapping YAML"/>
<let name="sensor_mapping_file_default" value="$(find-pkg-share autoware_carla_interface)/config/sensor_mapping_light_weight.yaml" if="$(var use_light_weight_sensor_mapping)"/>
<let name="sensor_mapping_file_default" value="$(find-pkg-share autoware_carla_interface)/config/sensor_mapping.yaml" unless="$(var use_light_weight_sensor_mapping)"/>
<arg name="sensor_mapping_file" default="$(var sensor_mapping_file_default)" description="Path to sensor mapping YAML"/>

<!-- CARLA Interface -->
<node pkg="autoware_carla_interface" exec="autoware_carla_interface" name="autoware_carla_interface" output="screen">
Expand Down Expand Up @@ -72,45 +79,52 @@
name="cam_front_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/CAM_FRONT/image_raw -r out/compressed:=/sensing/camera/CAM_FRONT/image_raw/compressed"
/>

<node
pkg="image_transport"
exec="republish"
name="cam_front_left_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/CAM_FRONT_LEFT/image_raw -r out/compressed:=/sensing/camera/CAM_FRONT_LEFT/image_raw/compressed"
unless="$(var use_light_weight_sensor_mapping)"
/>
<node
pkg="image_transport"
exec="republish"
name="cam_front_right_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/CAM_FRONT_RIGHT/image_raw -r out/compressed:=/sensing/camera/CAM_FRONT_RIGHT/image_raw/compressed"
unless="$(var use_light_weight_sensor_mapping)"
/>
<node
pkg="image_transport"
exec="republish"
name="cam_back_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/CAM_BACK/image_raw -r out/compressed:=/sensing/camera/CAM_BACK/image_raw/compressed"
unless="$(var use_light_weight_sensor_mapping)"
/>
<node
pkg="image_transport"
exec="republish"
name="cam_back_left_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/CAM_BACK_LEFT/image_raw -r out/compressed:=/sensing/camera/CAM_BACK_LEFT/image_raw/compressed"
unless="$(var use_light_weight_sensor_mapping)"
/>
<node
pkg="image_transport"
exec="republish"
name="cam_back_right_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/CAM_BACK_RIGHT/image_raw -r out/compressed:=/sensing/camera/CAM_BACK_RIGHT/image_raw/compressed"
unless="$(var use_light_weight_sensor_mapping)"
/>
<node
pkg="image_transport"
exec="republish"
name="traffic_light_republish"
args="raw compressed --ros-args -r in:=/sensing/camera/traffic_light/image_raw -r out/compressed:=/sensing/camera/traffic_light/image_raw/compressed"
unless="$(var use_light_weight_sensor_mapping)"
/>

<!-- Multi-camera combiner for RViz visualization -->
<node pkg="autoware_carla_interface" exec="multi_camera_combiner" output="screen"/>
<node pkg="autoware_carla_interface" exec="multi_camera_combiner" output="screen" unless="$(var use_light_weight_sensor_mapping)"/>

<!-- E2E Planning Infrastructure -->
<group if="$(var use_e2e_planning)">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,10 @@ def _resolve_mapping_file_path(self, mapping_file: Optional[str]) -> Optional[st
# Try source directory as fallback
source_mapping = Path(__file__).resolve().parents[3] / "config" / "sensor_mapping.yaml"
if source_mapping.exists():
self.logger.warning(
f"Sensor mapping file not found at requested path: {mapping_file}. "
f"Falling back to source-tree default: {source_mapping}"
)
return str(source_mapping)

self.logger.error(f"Sensor mapping file not found: {mapping_file}")
Expand Down
Loading