Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit ad97a17

Browse files
mraditya01Kim-mins
authored andcommittedAug 13, 2024
feat(carla_autoware): add interface to easily use CARLA with Autoware (autowarefoundation#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 f97253a commit ad97a17

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>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
<?xml version="1.0"?>
2+
<package format="3">
3+
<name>autoware_carla_interface</name>
4+
<version>0.0.0</version>
5+
<description>The carla autoware bridge package</description>
6+
<maintainer email="mradityagio@gmail.com">Muhammad Raditya GIOVANNI</maintainer>
7+
<maintainer email="maxime.clement@tier4.jp">Maxime CLEMENT</maintainer>
8+
<license>Apache License 2.0</license>
9+
10+
<exec_depend>std_msgs</exec_depend>
11+
<depend>autoware_perception_msgs</depend>
12+
<depend>autoware_vehicle_msgs</depend>
13+
<depend>geometry_msgs</depend>
14+
<depend>rclpy</depend>
15+
<depend>sensor_msgs</depend>
16+
<depend>sensor_msgs_py</depend>
17+
<depend>tf2</depend>
18+
<depend>tf2_ros</depend>
19+
<depend>tier4_vehicle_msgs</depend>
20+
21+
<buildtool_depend>ament_cmake</buildtool_depend>
22+
23+
<test_depend>ament_lint_auto</test_depend>
24+
<test_depend>ament_lint_common</test_depend>
25+
26+
<export>
27+
<build_type>ament_python</build_type>
28+
</export>
29+
</package>

‎simulator/autoware_carla_interface/resource/carla_autoware

Whitespace-only changes.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
[develop]
2+
script_dir=$base/lib/autoware_carla_interface
3+
[install]
4+
install_scripts=$base/lib/autoware_carla_interface
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
from glob import glob
2+
import os
3+
4+
from setuptools import setup
5+
6+
ROS_VERSION = int(os.environ["ROS_VERSION"])
7+
8+
package_name = "autoware_carla_interface"
9+
10+
setup(
11+
name=package_name,
12+
version="0.0.0",
13+
packages=[package_name],
14+
data_files=[
15+
("share/" + package_name, glob("config/*")),
16+
("share/" + package_name, glob("calibration_maps/*.csv")),
17+
("share/" + package_name, ["package.xml"]),
18+
(os.path.join("share", package_name), glob("launch/autoware_carla_interface.launch.xml")),
19+
],
20+
install_requires=["setuptools"],
21+
zip_safe=True,
22+
maintainer="Muhammad Raditya GIOVANNI, Maxime CLEMENT",
23+
maintainer_email="mradityagio@gmail.com, maxime.clement@tier4.jp",
24+
description="CARLA ROS 2 bridge for AUTOWARE",
25+
license="Apache License 2.0",
26+
tests_require=["pytest"],
27+
entry_points={
28+
"console_scripts": [
29+
"autoware_carla_interface = autoware_carla_interface.carla_autoware:main"
30+
],
31+
},
32+
package_dir={"": "src"},
33+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,195 @@
1+
# Copyright 2024 Tier IV, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.sr/bin/env python
14+
15+
import random
16+
import signal
17+
import time
18+
19+
import carla
20+
21+
from .carla_ros import carla_ros2_interface
22+
from .modules.carla_data_provider import CarlaDataProvider
23+
from .modules.carla_data_provider import GameTime
24+
from .modules.carla_wrapper import SensorReceivedNoData
25+
from .modules.carla_wrapper import SensorWrapper
26+
27+
28+
class SensorLoop(object):
29+
def __init__(self):
30+
self.start_game_time = None
31+
self.start_system_time = None
32+
self.sensor = None
33+
self.ego_actor = None
34+
self.running = False
35+
self.timestamp_last_run = 0.0
36+
self.timeout = 20.0
37+
38+
def _stop_loop(self):
39+
self.running = False
40+
41+
def _tick_sensor(self, timestamp):
42+
if self.timestamp_last_run < timestamp.elapsed_seconds and self.running:
43+
self.timestamp_last_run = timestamp.elapsed_seconds
44+
GameTime.on_carla_tick(timestamp)
45+
CarlaDataProvider.on_carla_tick()
46+
try:
47+
ego_action = self.sensor()
48+
except SensorReceivedNoData as e:
49+
raise RuntimeError(e)
50+
self.ego_actor.apply_control(ego_action)
51+
if self.running:
52+
CarlaDataProvider.get_world().tick()
53+
54+
55+
class InitializeInterface(object):
56+
def __init__(self):
57+
self.interface = carla_ros2_interface()
58+
self.param_ = self.interface.get_param()
59+
self.world = None
60+
self.sensor_wrapper = None
61+
self.ego_actor = None
62+
self.prev_tick_wall_time = 0.0
63+
64+
# Parameter for Initializing Carla World
65+
self.local_host = self.param_["host"]
66+
self.port = self.param_["port"]
67+
self.timeout = self.param_["timeout"]
68+
self.sync_mode = self.param_["sync_mode"]
69+
self.fixed_delta_seconds = self.param_["fixed_delta_seconds"]
70+
self.carla_map = self.param_["carla_map"]
71+
self.agent_role_name = self.param_["ego_vehicle_role_name"]
72+
self.vehicle_type = self.param_["vehicle_type"]
73+
self.spawn_point = self.param_["spawn_point"]
74+
self.use_traffic_manager = self.param_["use_traffic_manager"]
75+
self.max_real_delta_seconds = self.param_["max_real_delta_seconds"]
76+
77+
def load_world(self):
78+
client = carla.Client(self.local_host, self.port)
79+
client.set_timeout(self.timeout)
80+
client.load_world(self.carla_map)
81+
self.world = client.get_world()
82+
settings = self.world.get_settings()
83+
settings.fixed_delta_seconds = self.fixed_delta_seconds
84+
settings.synchronous_mode = self.sync_mode
85+
self.world.apply_settings(settings)
86+
CarlaDataProvider.set_world(self.world)
87+
CarlaDataProvider.set_client(client)
88+
spawn_point = carla.Transform()
89+
point_items = self.spawn_point.split(",")
90+
randomize = False
91+
if len(point_items) == 6:
92+
spawn_point.location.x = float(point_items[0])
93+
spawn_point.location.y = float(point_items[1])
94+
spawn_point.location.z = (
95+
float(point_items[2]) + 2
96+
) # +2 is used so the car did not stuck on the road when spawned.
97+
spawn_point.rotation.roll = float(point_items[3])
98+
spawn_point.rotation.pitch = float(point_items[4])
99+
spawn_point.rotation.yaw = float(point_items[5])
100+
else:
101+
randomize = True
102+
self.ego_actor = CarlaDataProvider.request_new_actor(
103+
self.vehicle_type, spawn_point, self.agent_role_name, random_location=randomize
104+
)
105+
self.interface.ego_actor = self.ego_actor # TODO improve design
106+
self.interface.physics_control = self.ego_actor.get_physics_control()
107+
108+
self.sensor_wrapper = SensorWrapper(self.interface)
109+
self.sensor_wrapper.setup_sensors(self.ego_actor, False)
110+
##########################################################################################################################################################
111+
# TRAFFIC MANAGER
112+
##########################################################################################################################################################
113+
# cspell:ignore trafficmanager
114+
if self.use_traffic_manager:
115+
traffic_manager = client.get_trafficmanager()
116+
traffic_manager.set_synchronous_mode(True)
117+
traffic_manager.set_random_device_seed(0)
118+
random.seed(0)
119+
spawn_points_tm = self.world.get_map().get_spawn_points()
120+
for i, spawn_point in enumerate(spawn_points_tm):
121+
self.world.debug.draw_string(spawn_point.location, str(i), life_time=10)
122+
models = [
123+
"dodge",
124+
"audi",
125+
"model3",
126+
"mini",
127+
"mustang",
128+
"lincoln",
129+
"prius",
130+
"nissan",
131+
"crown",
132+
"impala",
133+
]
134+
blueprints = []
135+
for vehicle in self.world.get_blueprint_library().filter("*vehicle*"):
136+
if any(model in vehicle.id for model in models):
137+
blueprints.append(vehicle)
138+
max_vehicles = 30
139+
max_vehicles = min([max_vehicles, len(spawn_points_tm)])
140+
vehicles = []
141+
for i, spawn_point in enumerate(random.sample(spawn_points_tm, max_vehicles)):
142+
temp = self.world.try_spawn_actor(random.choice(blueprints), spawn_point)
143+
if temp is not None:
144+
vehicles.append(temp)
145+
146+
for vehicle in vehicles:
147+
vehicle.set_autopilot(True)
148+
149+
def run_bridge(self):
150+
self.bridge_loop = SensorLoop()
151+
self.bridge_loop.sensor = self.sensor_wrapper
152+
self.bridge_loop.ego_actor = self.ego_actor
153+
self.bridge_loop.start_system_time = time.time()
154+
self.bridge_loop.start_game_time = GameTime.get_time()
155+
self.bridge_loop.running = True
156+
while self.bridge_loop.running:
157+
timestamp = None
158+
world = CarlaDataProvider.get_world()
159+
if world:
160+
snapshot = world.get_snapshot()
161+
if snapshot:
162+
timestamp = snapshot.timestamp
163+
if timestamp:
164+
delta_step = time.time() - self.prev_tick_wall_time
165+
if delta_step <= self.max_real_delta_seconds:
166+
# Add a wait to match the max_real_delta_seconds
167+
time.sleep(self.max_real_delta_seconds - delta_step)
168+
self.prev_tick_wall_time = time.time()
169+
self.bridge_loop._tick_sensor(timestamp)
170+
171+
def _stop_loop(self, sign, frame):
172+
self.bridge_loop._stop_loop()
173+
174+
def _cleanup(self):
175+
self.sensor_wrapper.cleanup()
176+
CarlaDataProvider.cleanup()
177+
if self.ego_actor:
178+
self.ego_actor.destroy()
179+
self.ego_actor = None
180+
181+
if self.interface:
182+
self.interface.shutdown()
183+
self.interface = None
184+
185+
186+
def main():
187+
carla_bridge = InitializeInterface()
188+
carla_bridge.load_world()
189+
signal.signal(signal.SIGINT, carla_bridge._stop_loop)
190+
carla_bridge.run_bridge()
191+
carla_bridge._cleanup()
192+
193+
194+
if __name__ == "__main__":
195+
main()

‎simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py

+486
Large diffs are not rendered by default.

‎simulator/autoware_carla_interface/src/autoware_carla_interface/modules/carla_data_provider.py

+867
Large diffs are not rendered by default.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
1+
import ctypes
2+
import math
3+
import struct
4+
import sys
5+
6+
import carla
7+
from geometry_msgs.msg import Point
8+
from geometry_msgs.msg import Quaternion
9+
from sensor_msgs.msg import PointCloud2
10+
from sensor_msgs.msg import PointField
11+
from transforms3d.euler import euler2quat
12+
from transforms3d.euler import quat2euler
13+
14+
15+
def _get_struct_fmt(is_bigendian, fields, field_names=None):
16+
_DATATYPES = {}
17+
_DATATYPES[PointField.INT8] = ("b", 1)
18+
_DATATYPES[PointField.UINT8] = ("B", 1)
19+
_DATATYPES[PointField.INT16] = ("h", 2)
20+
_DATATYPES[PointField.UINT16] = ("H", 2)
21+
_DATATYPES[PointField.INT32] = ("i", 4)
22+
_DATATYPES[PointField.UINT32] = ("I", 4)
23+
_DATATYPES[PointField.FLOAT32] = ("f", 4)
24+
_DATATYPES[PointField.FLOAT64] = ("d", 8)
25+
26+
fmt = ">" if is_bigendian else "<"
27+
28+
offset = 0
29+
for field in (
30+
f
31+
for f in sorted(fields, key=lambda f: f.offset)
32+
if field_names is None or f.name in field_names
33+
):
34+
if offset < field.offset:
35+
fmt += "x" * (field.offset - offset)
36+
offset = field.offset
37+
if field.datatype not in _DATATYPES:
38+
print("Skipping unknown PointField datatype [{}]" % field.datatype, file=sys.stderr)
39+
else:
40+
datatype_fmt, datatype_length = _DATATYPES[field.datatype]
41+
fmt += field.count * datatype_fmt
42+
offset += field.count * datatype_length
43+
44+
return fmt
45+
46+
47+
def create_cloud(header, fields, points):
48+
"""Create a L{sensor_msgs.msg.PointCloud2} message with different datatype (Modified create_cloud function)."""
49+
cloud_struct = struct.Struct(_get_struct_fmt(False, fields))
50+
51+
buff = ctypes.create_string_buffer(cloud_struct.size * len(points))
52+
53+
point_step, pack_into = cloud_struct.size, cloud_struct.pack_into
54+
offset = 0
55+
for p in points:
56+
pack_into(buff, offset, *p)
57+
offset += point_step
58+
59+
return PointCloud2(
60+
header=header,
61+
height=1,
62+
width=len(points),
63+
is_dense=False,
64+
is_bigendian=False,
65+
fields=fields,
66+
point_step=cloud_struct.size,
67+
row_step=cloud_struct.size * len(points),
68+
data=buff.raw,
69+
)
70+
71+
72+
def carla_location_to_ros_point(carla_location):
73+
"""Convert a carla location to a ROS point."""
74+
ros_point = Point()
75+
ros_point.x = carla_location.x
76+
ros_point.y = -carla_location.y
77+
ros_point.z = carla_location.z
78+
79+
return ros_point
80+
81+
82+
def carla_rotation_to_ros_quaternion(carla_rotation):
83+
"""Convert a carla rotation to a ROS quaternion."""
84+
roll = math.radians(carla_rotation.roll)
85+
pitch = -math.radians(carla_rotation.pitch)
86+
yaw = -math.radians(carla_rotation.yaw)
87+
quat = euler2quat(roll, pitch, yaw)
88+
ros_quaternion = Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3])
89+
90+
return ros_quaternion
91+
92+
93+
def ros_quaternion_to_carla_rotation(ros_quaternion):
94+
"""Convert ROS quaternion to carla rotation."""
95+
roll, pitch, yaw = quat2euler(
96+
[ros_quaternion.w, ros_quaternion.x, ros_quaternion.y, ros_quaternion.z]
97+
)
98+
99+
return carla.Rotation(
100+
roll=math.degrees(roll), pitch=-math.degrees(pitch), yaw=-math.degrees(yaw)
101+
)
102+
103+
104+
def ros_pose_to_carla_transform(ros_pose):
105+
"""Convert ROS pose to carla transform."""
106+
return carla.Transform(
107+
carla.Location(ros_pose.position.x, -ros_pose.position.y, ros_pose.position.z),
108+
ros_quaternion_to_carla_rotation(ros_pose.orientation),
109+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,231 @@
1+
# Copyright 2024 Tier IV, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.sr/bin/env python
14+
15+
from __future__ import print_function
16+
17+
import logging
18+
from queue import Empty
19+
from queue import Queue
20+
21+
import carla
22+
import numpy as np
23+
24+
from .carla_data_provider import CarlaDataProvider
25+
26+
27+
# Sensor Wrapper for Agent
28+
class SensorReceivedNoData(Exception):
29+
"""Exceptions when no data received from the sensors."""
30+
31+
32+
class GenericMeasurement(object):
33+
def __init__(self, data, frame):
34+
self.data = data
35+
self.frame = frame
36+
37+
38+
class CallBack(object):
39+
def __init__(self, tag, sensor, data_provider):
40+
self._tag = tag
41+
self._data_provider = data_provider
42+
43+
self._data_provider.register_sensor(tag, sensor)
44+
45+
def __call__(self, data):
46+
if isinstance(data, carla.Image):
47+
self._parse_image_cb(data, self._tag)
48+
elif isinstance(data, carla.LidarMeasurement):
49+
self._parse_lidar_cb(data, self._tag)
50+
elif isinstance(data, carla.GnssMeasurement):
51+
self._parse_gnss_cb(data, self._tag)
52+
elif isinstance(data, carla.IMUMeasurement):
53+
self._parse_imu_cb(data, self._tag)
54+
elif isinstance(data, GenericMeasurement):
55+
self._parse_pseudo_sensor(data, self._tag)
56+
else:
57+
logging.error("No callback method for this sensor.")
58+
59+
# Parsing CARLA physical Sensors
60+
def _parse_image_cb(self, image, tag):
61+
self._data_provider.update_sensor(tag, image, image.frame)
62+
63+
def _parse_lidar_cb(self, lidar_data, tag):
64+
self._data_provider.update_sensor(tag, lidar_data, lidar_data.frame)
65+
66+
def _parse_imu_cb(self, imu_data, tag):
67+
self._data_provider.update_sensor(tag, imu_data, imu_data.frame)
68+
69+
def _parse_gnss_cb(self, gnss_data, tag):
70+
array = np.array(
71+
[gnss_data.latitude, gnss_data.longitude, gnss_data.altitude], dtype=np.float64
72+
)
73+
self._data_provider.update_sensor(tag, array, gnss_data.frame)
74+
75+
def _parse_pseudo_sensor(self, package, tag):
76+
self._data_provider.update_sensor(tag, package.data, package.frame)
77+
78+
79+
class SensorInterface(object):
80+
def __init__(self):
81+
self._sensors_objects = {}
82+
self._new_data_buffers = Queue()
83+
self._queue_timeout = 10
84+
self.tag = ""
85+
86+
def register_sensor(self, tag, sensor):
87+
self.tag = tag
88+
if tag in self._sensors_objects:
89+
raise ValueError(f"Duplicated sensor tag [{tag}]")
90+
91+
self._sensors_objects[tag] = sensor
92+
93+
def update_sensor(self, tag, data, timestamp):
94+
if tag not in self._sensors_objects:
95+
raise ValueError(f"Sensor with tag [{tag}] has not been created")
96+
97+
self._new_data_buffers.put((tag, timestamp, data))
98+
99+
def get_data(self):
100+
try:
101+
data_dict = {}
102+
while len(data_dict.keys()) < len(self._sensors_objects.keys()):
103+
sensor_data = self._new_data_buffers.get(True, self._queue_timeout)
104+
data_dict[sensor_data[0]] = (sensor_data[1], sensor_data[2])
105+
except Empty:
106+
raise SensorReceivedNoData(
107+
f"Sensor with tag [{self.tag}] took too long to send its data"
108+
)
109+
110+
return data_dict
111+
112+
113+
# Sensor Wrapper
114+
115+
116+
class SensorWrapper(object):
117+
_agent = None
118+
_sensors_list = []
119+
120+
def __init__(self, agent):
121+
self._agent = agent
122+
123+
def __call__(self):
124+
return self._agent()
125+
126+
def setup_sensors(self, vehicle, debug_mode=False):
127+
"""Create and attach the sensor defined in objects.json."""
128+
bp_library = CarlaDataProvider.get_world().get_blueprint_library()
129+
130+
for sensor_spec in self._agent.sensors["sensors"]:
131+
bp = bp_library.find(str(sensor_spec["type"]))
132+
133+
if sensor_spec["type"].startswith("sensor.camera"):
134+
bp.set_attribute("image_size_x", str(sensor_spec["image_size_x"]))
135+
bp.set_attribute("image_size_y", str(sensor_spec["image_size_y"]))
136+
bp.set_attribute("fov", str(sensor_spec["fov"]))
137+
sensor_location = carla.Location(
138+
x=sensor_spec["spawn_point"]["x"],
139+
y=sensor_spec["spawn_point"]["y"],
140+
z=sensor_spec["spawn_point"]["z"],
141+
)
142+
sensor_rotation = carla.Rotation(
143+
pitch=sensor_spec["spawn_point"]["pitch"],
144+
roll=sensor_spec["spawn_point"]["roll"],
145+
yaw=sensor_spec["spawn_point"]["yaw"],
146+
)
147+
148+
elif sensor_spec["type"].startswith("sensor.lidar"):
149+
bp.set_attribute("range", str(sensor_spec["range"]))
150+
bp.set_attribute("rotation_frequency", str(sensor_spec["rotation_frequency"]))
151+
bp.set_attribute("channels", str(sensor_spec["channels"]))
152+
bp.set_attribute("upper_fov", str(sensor_spec["upper_fov"]))
153+
bp.set_attribute("lower_fov", str(sensor_spec["lower_fov"]))
154+
bp.set_attribute("points_per_second", str(sensor_spec["points_per_second"]))
155+
sensor_location = carla.Location(
156+
x=sensor_spec["spawn_point"]["x"],
157+
y=sensor_spec["spawn_point"]["y"],
158+
z=sensor_spec["spawn_point"]["z"],
159+
)
160+
sensor_rotation = carla.Rotation(
161+
pitch=sensor_spec["spawn_point"]["pitch"],
162+
roll=sensor_spec["spawn_point"]["roll"],
163+
yaw=sensor_spec["spawn_point"]["yaw"],
164+
)
165+
166+
elif sensor_spec["type"].startswith("sensor.other.gnss"):
167+
bp.set_attribute("noise_alt_stddev", str(0.0))
168+
bp.set_attribute("noise_lat_stddev", str(0.0))
169+
bp.set_attribute("noise_lon_stddev", str(0.0))
170+
bp.set_attribute("noise_alt_bias", str(0.0))
171+
bp.set_attribute("noise_lat_bias", str(0.0))
172+
bp.set_attribute("noise_lon_bias", str(0.0))
173+
sensor_location = carla.Location(
174+
x=sensor_spec["spawn_point"]["x"],
175+
y=sensor_spec["spawn_point"]["y"],
176+
z=sensor_spec["spawn_point"]["z"],
177+
)
178+
sensor_rotation = carla.Rotation(
179+
pitch=sensor_spec["spawn_point"]["pitch"],
180+
roll=sensor_spec["spawn_point"]["roll"],
181+
yaw=sensor_spec["spawn_point"]["yaw"],
182+
)
183+
184+
elif sensor_spec["type"].startswith("sensor.other.imu"):
185+
bp.set_attribute("noise_accel_stddev_x", str(0.0))
186+
bp.set_attribute("noise_accel_stddev_y", str(0.0))
187+
bp.set_attribute("noise_accel_stddev_z", str(0.0))
188+
bp.set_attribute("noise_gyro_stddev_x", str(0.0))
189+
bp.set_attribute("noise_gyro_stddev_y", str(0.0))
190+
bp.set_attribute("noise_gyro_stddev_z", str(0.0))
191+
sensor_location = carla.Location(
192+
x=sensor_spec["spawn_point"]["x"],
193+
y=sensor_spec["spawn_point"]["y"],
194+
z=sensor_spec["spawn_point"]["z"],
195+
)
196+
sensor_rotation = carla.Rotation(
197+
pitch=sensor_spec["spawn_point"]["pitch"],
198+
roll=sensor_spec["spawn_point"]["roll"],
199+
yaw=sensor_spec["spawn_point"]["yaw"],
200+
)
201+
202+
elif sensor_spec["type"].startswith("sensor.pseudo.*"):
203+
sensor_location = carla.Location(
204+
x=sensor_spec["spawn_point"]["x"],
205+
y=sensor_spec["spawn_point"]["y"],
206+
z=sensor_spec["spawn_point"]["z"],
207+
)
208+
sensor_rotation = carla.Rotation(
209+
pitch=sensor_spec["spawn_point"]["pitch"] + 0.001,
210+
roll=sensor_spec["spawn_point"]["roll"] - 0.015,
211+
yaw=sensor_spec["spawn_point"]["yaw"] + 0.0364,
212+
)
213+
214+
# create sensor
215+
sensor_transform = carla.Transform(sensor_location, sensor_rotation)
216+
sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)
217+
# setup callback
218+
sensor.listen(CallBack(sensor_spec["id"], sensor, self._agent.sensor_interface))
219+
self._sensors_list.append(sensor)
220+
221+
# Tick once to spawn the sensors
222+
CarlaDataProvider.get_world().tick()
223+
224+
def cleanup(self):
225+
"""Cleanup sensors."""
226+
for i, _ in enumerate(self._sensors_list):
227+
if self._sensors_list[i] is not None:
228+
self._sensors_list[i].stop()
229+
self._sensors_list[i].destroy()
230+
self._sensors_list[i] = None
231+
self._sensors_list = []

0 commit comments

Comments
 (0)
Please sign in to comment.