Skip to content

Commit 5b1d14e

Browse files
mraditya01Kim-mins
andauthored
feat(carla_autoware): add interface to easily use CARLA with Autoware (#6859)
Signed-off-by: mraditya01 <mraditya01@yahoo.com> Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> Co-authored-by: Minsu Kim <minsu@korea.ac.kr>
1 parent 245f365 commit 5b1d14e

17 files changed

+2307
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
cmake_minimum_required(VERSION 3.8)
2+
project(autoware_carla_interface)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
7+
find_package(
8+
catkin REQUIRED COMPONENTS std_msgs)
9+
10+
11+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
12+
add_compile_options(-Wall -Wextra -Wpedantic)
13+
endif()
14+
15+
ament_export_dependencies(rclpy)
16+
17+
find_package(ros_environment REQUIRED)
18+
set(ROS_VERSION $ENV{ROS_VERSION})
19+
20+
21+
# Install launch files.
22+
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/)
23+
24+
25+
ament_auto_package(
26+
launch
27+
resource
28+
config
29+
src
30+
)
31+
ament_package()
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,161 @@
1+
# autoware_carla_interface
2+
3+
## ROS 2/Autoware.universe bridge for CARLA simulator
4+
5+
Thanks to <https://github.com/gezp> for ROS 2 Humble support for CARLA Communication.
6+
This ros package enables communication between Autoware and CARLA for autonomous driving simulation.
7+
8+
## Supported Environment
9+
10+
| ubuntu | ros | carla | autoware |
11+
| :----: | :----: | :----: | :------: |
12+
| 22.04 | humble | 0.9.15 | Main |
13+
14+
## Setup
15+
16+
### Install
17+
18+
- [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/)
19+
- [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/)
20+
- [Python Package for CARLA 0.9.15 ROS 2 Humble communication](https://github.com/gezp/carla_ros/releases/tag/carla-0.9.15-ubuntu-22.04)
21+
22+
- Install the wheel using pip.
23+
- OR add the egg file to the `PYTHONPATH`.
24+
25+
1. Download maps (y-axis inverted version) to arbitrary location
26+
2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`)
27+
3. Create `map_projector_info.yaml` on the folder and add `projector_type: local` on the first line.
28+
29+
### Build
30+
31+
```bash
32+
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release
33+
```
34+
35+
### Run
36+
37+
1. Run carla, change map, spawn object if you need
38+
<!--- cspell:ignore prefernvidia -->
39+
40+
```bash
41+
cd CARLA
42+
./CarlaUE4.sh -prefernvidia -quality-level=Low -RenderOffScreen
43+
```
44+
45+
2. Run ros nodes
46+
47+
```bash
48+
ros2 launch autoware_launch e2e_simulator.launch.xml map_path:=$HOME/autoware_map/Town01 vehicle_model:=sample_vehicle sensor_model:=awsim_sensor_kit simulator_type:=carla carla_map:=Town01
49+
```
50+
51+
3. Set initial pose (Init by GNSS)
52+
4. Set goal position
53+
5. Wait for planning
54+
6. Engage
55+
56+
## Inner-workings / Algorithms
57+
58+
The `InitializeInterface` class is key to setting up both the CARLA world and the ego vehicle. It fetches configuration parameters through the `autoware_carla_interface.launch.xml`.
59+
60+
The main simulation loop runs within the `carla_ros2_interface` class. This loop ticks simulation time inside the CARLA simulator at `fixed_delta_seconds` time, where data is received and published as ROS 2 messages at frequencies defined in `self.sensor_frequencies`.
61+
62+
Ego vehicle commands from Autoware are processed through the `autoware_raw_vehicle_cmd_converter`, which calibrates these commands for CARLA. The calibrated commands are then fed directly into CARLA control via `CarlaDataProvider`.
63+
64+
### Configurable Parameters for World Loading
65+
66+
All the key parameters can be configured in `autoware_carla_interface.launch.xml`.
67+
68+
| Name | Type | Default Value | Description |
69+
| ------------------------- | ------ | --------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
70+
| `host` | string | "localhost" | Hostname for the CARLA server |
71+
| `port` | int | "2000" | Port number for the CARLA server |
72+
| `timeout` | int | 20 | Timeout for the CARLA client |
73+
| `ego_vehicle_role_name` | string | "ego_vehicle" | Role name for the ego vehicle |
74+
| `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/) |
75+
| `spawn_point` | string | None | Coordinates for spawning the ego vehicle (None is random). Format = [x, y, z, roll, pitch, yaw] |
76+
| `carla_map` | string | "Town01" | Name of the map to load in CARLA |
77+
| `sync_mode` | bool | True | Boolean flag to set synchronous mode in CARLA |
78+
| `fixed_delta_seconds` | double | 0.05 | Time step for the simulation (related to client FPS) |
79+
| `objects_definition_file` | string | "$(find-pkg-share autoware_carla_interface)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA |
80+
| `use_traffic_manager` | bool | True | Boolean flag to set traffic manager in CARLA |
81+
| `max_real_delta_seconds` | double | 0.05 | Parameter to limit the simulation speed below `fixed_delta_seconds` |
82+
| `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. |
83+
84+
### Configurable Parameters for Sensors
85+
86+
Below parameters can be configured in `carla_ros.py`.
87+
88+
| Name | Type | Default Value | Description |
89+
| ------------------------- | ---- | -------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
90+
| `self.sensor_frequencies` | dict | {"top": 11, "left": 11, "right": 11, "camera": 11, "imu": 50, "status": 50, "pose": 2} | (line 67) Calculates the time interval since the last publication and checks if this interval meets the minimum required to not exceed the desired frequency. It will only affect ROS publishing frequency not CARLA sensor tick. |
91+
92+
- CARLA sensor parameters can be configured in `config/objects.json`.
93+
- For more details regarding the parameters that can be modified in CARLA are explained in [Carla Ref Sensor](https://carla.readthedocs.io/en/latest/ref_sensors/).
94+
95+
### World Loading
96+
97+
The `carla_ros.py` sets up the CARLA world:
98+
99+
1. **Client Connection**:
100+
101+
```python
102+
client = carla.Client(self.local_host, self.port)
103+
client.set_timeout(self.timeout)
104+
```
105+
106+
2. **Load the Map**:
107+
108+
Map loaded in CARLA world with map according to `carla_map` parameter.
109+
110+
```python
111+
client.load_world(self.map_name)
112+
self.world = client.get_world()
113+
```
114+
115+
3. **Spawn Ego Vehicle**:
116+
117+
Vehicle are spawn according to `vehicle_type`, `spawn_point`, and `agent_role_name` parameter.
118+
119+
```python
120+
spawn_point = carla.Transform()
121+
point_items = self.spawn_point.split(",")
122+
if len(point_items) == 6:
123+
spawn_point.location.x = float(point_items[0])
124+
spawn_point.location.y = float(point_items[1])
125+
spawn_point.location.z = float(point_items[2]) + 2
126+
spawn_point.rotation.roll = float(point_items[3])
127+
spawn_point.rotation.pitch = float(point_items[4])
128+
spawn_point.rotation.yaw = float(point_items[5])
129+
CarlaDataProvider.request_new_actor(self.vehicle_type, spawn_point, self.agent_role_name)
130+
```
131+
132+
## Traffic Light Recognition
133+
134+
The maps provided by the Carla Simulator ([Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/)) currently lack proper traffic light components for Autoware and have different latitude and longitude coordinates compared to the pointcloud map. To enable traffic light recognition, follow the steps below to modify the maps.
135+
136+
- Options to Modify the Map
137+
138+
- A. Create a New Map from Scratch
139+
- Use the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map.
140+
141+
- B. Modify the Existing Carla Lanelet2 Maps
142+
- Adjust the longitude and latitude of the [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) to align with the PCD (origin).
143+
- Use this [tool](https://github.com/mraditya01/offset_lanelet2/tree/main) to modify the coordinates.
144+
- Snap Lanelet with PCD and add the traffic lights using the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/).
145+
146+
- When using the Tier4 Vector Map Builder, you must convert the PCD format from `binary_compressed` to `ascii`. You can use `pcl_tools` for this conversion.
147+
- For reference, an example of Town01 with added traffic lights at one intersection can be downloaded [here](https://drive.google.com/drive/folders/1QFU0p3C8NW71sT5wwdnCKXoZFQJzXfTG?usp=sharing).
148+
149+
## Tips
150+
151+
- Misalignment might occurs during initialization, pressing `init by gnss` button should fix it.
152+
- Changing the `fixed_delta_seconds` can increase the simulation tick (default 0.05 s), some sensors params in `objects.json` need to be adjusted when it is changed (example: LIDAR rotation frequency have to match the FPS).
153+
154+
## Known Issues and Future Works
155+
156+
- Testing on procedural map (Adv Digital Twin).
157+
- Currently unable to test it due to failing in the creation of the Adv digital twin map.
158+
- Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit.
159+
- Sensor currently not automatically configured to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`autoware_carla_interface.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached.
160+
- Traffic light recognition.
161+
- Currently the HDmap of CARLA did not have information regarding the traffic light which is necessary for Autoware to conduct traffic light recognition.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89
2+
0,0.090,-0.204,-0.490,-0.490,-0.491,-0.492,-0.493,-0.494,-0.495,-0.496,-0.500
3+
0.100,0.167,0.166,-0.093,-0.243,-0.244,-0.245,-0.246,-0.247,-0.248,-0.249,-0.280
4+
0.200,0.941,0.464,0.186,0.004,-0.100,-0.101,-0.102,-0.103,-0.104,-0.105,-0.106
5+
0.300,1.747,1.332,0.779,0.778,0.777,0.776,0.775,0.774,0.720,0.640,0.580
6+
0.400,2.650,2.480,2.300,2.130,1.950,1.750,1.580,1.450,1.320,1.200,1.100
7+
0.500,3.300,3.250,3.120,2.920,2.680,2.350,2.170,1.980,1.880,1.730,1.610
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89
2+
0,0.090,-0.204,-0.490,-0.490,-0.491,-0.492,-0.493,-0.494,-0.495,-0.496,-0.500
3+
0.100,0.089,-0.226,-0.535,-0.536,-0.537,-0.538,-0.539,-0.540,-0.541,-0.542,-0.543
4+
0.200,-0.380,-0.414,-0.746,-0.800,-0.820,-0.850,-0.870,-0.890,-0.910,-0.940,-0.960
5+
0.300,-1.000,-1.040,-1.480,-1.550,-1.570,-1.590,-1.610,-1.630,-1.631,-1.632,-1.633
6+
0.400,-1.480,-1.500,-1.850,-2.050,-2.100,-2.101,-2.102,-2.103,-2.104,-2.105,-2.106
7+
0.500,-1.490,-1.510,-1.860,-2.060,-2.110,-2.111,-2.112,-2.113,-2.114,-2.115,-2.116
8+
0.600,-1.500,-1.520,-1.870,-2.070,-2.120,-2.121,-2.122,-2.123,-2.124,-2.125,-2.126
9+
0.700,-1.510,-1.530,-1.880,-2.080,-2.130,-2.131,-2.132,-2.133,-2.134,-2.135,-2.136
10+
0.800,-2.180,-2.200,-2.700,-2.800,-2.900,-2.950,-2.951,-2.952,-2.953,-2.954,-2.955
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
default,-10,0,10
2+
-1,-0.9,-0.9,-0.9
3+
0,0,0,0
4+
1,0.9,0.9,0.9
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
{
2+
"sensors": [
3+
{
4+
"type": "sensor.camera.rgb",
5+
"id": "rgb_front",
6+
"spawn_point": {
7+
"x": 0.7,
8+
"y": 0.0,
9+
"z": 1.6,
10+
"roll": 0.0,
11+
"pitch": 0.0,
12+
"yaw": 0.0
13+
},
14+
"image_size_x": 1920,
15+
"image_size_y": 1080,
16+
"fov": 90.0
17+
},
18+
{
19+
"type": "sensor.lidar.ray_cast",
20+
"id": "top",
21+
"spawn_point": {
22+
"x": 0.0,
23+
"y": 0.0,
24+
"z": 3.1,
25+
"roll": 0.0,
26+
"pitch": 0.0,
27+
"yaw": 0.0
28+
},
29+
"range": 100,
30+
"channels": 64,
31+
"points_per_second": 300000,
32+
"upper_fov": 10.0,
33+
"lower_fov": -30.0,
34+
"rotation_frequency": 20,
35+
"noise_stddev": 0.0
36+
},
37+
{
38+
"type": "sensor.other.gnss",
39+
"id": "gnss",
40+
"spawn_point": {
41+
"x": 0.0,
42+
"y": 0.0,
43+
"z": 1.6,
44+
"roll": 0.0,
45+
"pitch": 0.0,
46+
"yaw": 0.0
47+
}
48+
},
49+
{
50+
"type": "sensor.other.imu",
51+
"id": "imu",
52+
"spawn_point": {
53+
"x": 0.0,
54+
"y": 0.0,
55+
"z": 1.6,
56+
"roll": 0.0,
57+
"pitch": 0.0,
58+
"yaw": 0.0
59+
}
60+
}
61+
]
62+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
/**:
2+
ros__parameters:
3+
csv_path_accel_map: $(find-pkg-share autoware_carla_interface)/accel_map.csv
4+
csv_path_brake_map: $(find-pkg-share autoware_carla_interface)/brake_map.csv
5+
csv_path_steer_map: $(find-pkg-share autoware_carla_interface)/steer_map.csv
6+
convert_accel_cmd: true
7+
convert_brake_cmd: true
8+
convert_steer_cmd: false
9+
use_steer_ff: true
10+
use_steer_fb: true
11+
is_debugging: false
12+
max_throttle: 0.4
13+
max_brake: 0.8
14+
max_steer: 1.0
15+
min_steer: -1.0
16+
steer_pid:
17+
kp: 150.0
18+
ki: 15.0
19+
kd: 0.0
20+
max: 8.0
21+
min: -8.0
22+
max_p: 8.0
23+
min_p: -8.0
24+
max_i: 8.0
25+
min_i: -8.0
26+
max_d: 0.0
27+
min_d: 0.0
28+
invalid_integration_decay: 0.97
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
<launch>
2+
<group>
3+
<arg name="host" default="localhost"/>
4+
<arg name="port" default="2000"/>
5+
<arg name="timeout" default="20"/>
6+
<arg name="ego_vehicle_role_name" default="ego_vehicle"/>
7+
<arg name="vehicle_type" default="vehicle.toyota.prius"/>
8+
<arg name="spawn_point" default="None" description="location of ego vehicle spawn (default is random), example = [0.2 , 4.1, 0.4, 0., 0., 0.]"/>
9+
<arg name="carla_map" default="Town01"/>
10+
<arg name="sync_mode" default="True"/>
11+
<arg name="fixed_delta_seconds" default="0.05" description="Time step for CARLA, FPS=1/value"/>
12+
<arg name="objects_definition_file" default="$(find-pkg-share autoware_carla_interface)/objects.json"/>
13+
<arg name="use_traffic_manager" default="False"/>
14+
<arg name="max_real_delta_seconds" default="0.05"/>
15+
16+
<!-- CARLA Interface -->
17+
<node pkg="autoware_carla_interface" exec="autoware_carla_interface" name="autoware_carla_interface" output="screen">
18+
<param name="host" value="$(var host)"/>
19+
<param name="port" value="$(var port)"/>
20+
<param name="timeout" value="$(var timeout)"/>
21+
<param name="sync_mode" value="$(var sync_mode)"/>
22+
<param name="fixed_delta_seconds" value="$(var fixed_delta_seconds)"/>
23+
<param name="carla_map" value="$(var carla_map)"/>
24+
<param name="ego_vehicle_role_name" value="$(var ego_vehicle_role_name)"/>
25+
<param name="spawn_point" value="$(var spawn_point)"/>
26+
<param name="vehicle_type" value="$(var vehicle_type)"/>
27+
<param name="objects_definition_file" value="$(var objects_definition_file)"/>
28+
<param name="use_traffic_manager" value="$(var use_traffic_manager)"/>
29+
<param name="max_real_delta_seconds" value="$(var max_real_delta_seconds)"/>
30+
</node>
31+
32+
<arg name="input_control_cmd" default="/control/command/control_cmd"/>
33+
<arg name="input_odometry" default="/localization/kinematic_state"/>
34+
<arg name="input_steering" default="/vehicle/status/steering_status"/>
35+
<arg name="output_actuation_cmd" default="/control/command/actuation_cmd"/>
36+
<arg name="config_file" default="$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml"/>
37+
38+
<node pkg="autoware_raw_vehicle_cmd_converter" exec="autoware_raw_vehicle_cmd_converter_node" name="autoware_raw_vehicle_cmd_converter" output="screen">
39+
<param from="$(var config_file)" allow_substs="true"/>
40+
<remap from="~/input/control_cmd" to="$(var input_control_cmd)"/>
41+
<remap from="~/input/odometry" to="$(var input_odometry)"/>
42+
<remap from="~/input/steering" to="$(var input_steering)"/>
43+
<remap from="~/output/actuation_cmd" to="$(var output_actuation_cmd)"/>
44+
</node>
45+
46+
<!-- Awsim configuration frame to CARLA frame -->
47+
<node pkg="tf2_ros" exec="static_transform_publisher" name="velodyne_top" args="0 0 1 -1.5386 -0.015 0.001 /velodyne_top /velodyne_top_changed "/>
48+
<node pkg="tf2_ros" exec="static_transform_publisher" name="imu" args="0 0 1 -3.10519265 -0.015 -3.14059265359 /tamagawa/imu_link /tamagawa/imu_link_changed "/>
49+
</group>
50+
</launch>

0 commit comments

Comments
 (0)