Skip to content

Commit fee14f4

Browse files
committed
feat(ros2): add ROS2 native example scripts and update build system
Update ROS2 example files from ue4-dev reference: add GNSS and IMU sensors to stack.json configuration, update rviz config with new sensor frames and correct lidar topic path, sync ros2_native.py with upstream, and update README with launch instructions. Build system (CMakeLists.txt) uses dynamic file globs so no changes needed for renamed/added/removed source files. Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp>
1 parent 32b2da9 commit fee14f4

4 files changed

Lines changed: 66 additions & 13 deletions

File tree

PythonAPI/examples/ros2/README.md

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,11 @@ To run this example, ensure `docker` is installed in your system, which is used
1313
Launch the CARLA simulator with the ROS 2 integration enabled:
1414

1515
```bash
16-
./CarlaUnreal.sh --ros2
16+
# If running a package:
17+
./CarlaUE4sh --ros2
18+
19+
# If running the editor:
20+
make launch ARGS="--ros2 --editor-flags='--ros2'"
1721
```
1822

1923
### Step 2: Run the ROS2 Example

PythonAPI/examples/ros2/ros2_native.py

Lines changed: 17 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#!/usr/bin/env python
22

3-
# Copyright (c) 2026 Computer Vision Center (CVC) at the Universitat Autonoma de
3+
# Copyright (c) 2025 Computer Vision Center (CVC) at the Universitat Autonoma de
44
# Barcelona (UAB).
55
#
66
# This work is licensed under the terms of the MIT license.
@@ -9,6 +9,18 @@
99
# Allows controlling a vehicle with a keyboard. For a simpler and more
1010
# documented example, please take a look at tutorial.py.
1111

12+
import glob
13+
import os
14+
import sys
15+
16+
try:
17+
sys.path.append(glob.glob('../../carla/dist/carla-*%d.%d-%s.egg' % (
18+
sys.version_info.major,
19+
sys.version_info.minor,
20+
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
21+
except IndexError:
22+
pass
23+
1224
import argparse
1325
import json
1426
import logging
@@ -24,7 +36,7 @@ def _setup_vehicle(world, config):
2436

2537
bp = bp_library.filter(config.get("type"))[0]
2638
bp.set_attribute("role_name", config.get("id"))
27-
bp.set_attribute("ros_name", config.get("id"))
39+
bp.set_attribute("ros_name", config.get("id"))
2840

2941
return world.spawn_actor(
3042
bp,
@@ -40,8 +52,8 @@ def _setup_sensors(world, vehicle, sensors_config):
4052
logging.debug("Spawning sensor: {}".format(sensor))
4153

4254
bp = bp_library.filter(sensor.get("type"))[0]
43-
bp.set_attribute("ros_name", sensor.get("id"))
44-
bp.set_attribute("role_name", sensor.get("id"))
55+
bp.set_attribute("ros_name", sensor.get("id"))
56+
bp.set_attribute("role_name", sensor.get("id"))
4557
for key, value in sensor.get("attributes", {}).items():
4658
bp.set_attribute(str(key), str(value))
4759

@@ -72,7 +84,7 @@ def main(args):
7284

7385
try:
7486
client = carla.Client(args.host, args.port)
75-
client.set_timeout(60.0)
87+
client.set_timeout(10.0)
7688

7789
world = client.get_world()
7890

PythonAPI/examples/ros2/rviz/ros2_native.rviz

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,8 +48,12 @@ Visualization Manager:
4848
Frame Timeout: 15
4949
Frames:
5050
All Enabled: true
51+
gnss:
52+
Value: true
5153
hero:
5254
Value: true
55+
imu:
56+
Value: true
5357
lidar:
5458
Value: true
5559
rgb:
@@ -61,6 +65,10 @@ Visualization Manager:
6165
Show Names: true
6266
Tree:
6367
hero:
68+
gnss:
69+
{}
70+
imu:
71+
{}
6472
lidar:
6573
{}
6674
rgb:
@@ -102,9 +110,9 @@ Visualization Manager:
102110
Enabled: true
103111
Invert Rainbow: false
104112
Max Color: 255; 255; 255
105-
Max Intensity: 0.9900385737419128
113+
Max Intensity: 0.9897720217704773
106114
Min Color: 0; 0; 0
107-
Min Intensity: 0.7121721506118774
115+
Min Intensity: 0.7122171521186829
108116
Name: PointCloud
109117
Position Transformer: XYZ
110118
Selectable: true
@@ -117,7 +125,7 @@ Visualization Manager:
117125
Filter size: 10
118126
History Policy: Keep Last
119127
Reliability Policy: Reliable
120-
Value: /carla/hero/lidar
128+
Value: /carla/hero/lidar/point_cloud
121129
Use Fixed Frame: true
122130
Use rainbow: true
123131
Value: true

PythonAPI/examples/ros2/stack.json

Lines changed: 33 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
11
{
2-
"type": "vehicle.lincoln.mkz",
2+
"type": "vehicle.lincoln.mkz_2017",
33
"id": "hero",
44
"sensors": [
55
{
66
"type": "sensor.camera.rgb",
77
"id": "rgb",
88
"spawn_point": {"x": -4.5, "y": 0.0, "z": 2.5, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
99
"attributes": {
10-
"image_size_x": 400,
11-
"image_size_y": 200,
10+
"image_size_x": 600,
11+
"image_size_y": 400,
1212
"fov": 90.0
1313
}
1414
},
@@ -28,6 +28,35 @@
2828
"dropoff_intensity_limit": 0.8,
2929
"dropoff_zero_intensity": 0.4
3030
}
31+
},
32+
{
33+
"type": "sensor.other.gnss",
34+
"id": "gnss",
35+
"spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
36+
"attributes": {
37+
"noise_alt_stddev": 0.0,
38+
"noise_lat_stddev": 0.0,
39+
"noise_lon_stddev": 0.0,
40+
"noise_alt_bias": 0.0,
41+
"noise_lat_bias": 0.0,
42+
"noise_lon_bias": 0.0
43+
}
44+
},
45+
{
46+
"type": "sensor.other.imu",
47+
"id": "imu",
48+
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
49+
"attributes": {
50+
"noise_accel_stddev_x": 0.0,
51+
"noise_accel_stddev_y": 0.0,
52+
"noise_accel_stddev_z": 0.0,
53+
"noise_gyro_stddev_x": 0.0,
54+
"noise_gyro_stddev_y": 0.0,
55+
"noise_gyro_stddev_z": 0.0,
56+
"noise_gyro_bias_x": 0.0,
57+
"noise_gyro_bias_y": 0.0,
58+
"noise_gyro_bias_z": 0.0
59+
}
3160
}
3261
]
33-
}
62+
}

0 commit comments

Comments
 (0)