Skip to content

Commit

Permalink
feat(carla_autoware): add interface to easily use CARLA with Autoware (
Browse files Browse the repository at this point in the history
…#6859)

Signed-off-by: mraditya01 <[email protected]>
Signed-off-by: Maxime CLEMENT <[email protected]>
Co-authored-by: Minsu Kim <[email protected]>
  • Loading branch information
mraditya01 and Kim-mins authored Jul 19, 2024
1 parent 245f365 commit 5b1d14e
Show file tree
Hide file tree
Showing 17 changed files with 2,307 additions and 0 deletions.
31 changes: 31 additions & 0 deletions simulator/autoware_carla_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
cmake_minimum_required(VERSION 3.8)
project(autoware_carla_interface)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(
catkin REQUIRED COMPONENTS std_msgs)


if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

ament_export_dependencies(rclpy)

find_package(ros_environment REQUIRED)
set(ROS_VERSION $ENV{ROS_VERSION})


# Install launch files.
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/)


ament_auto_package(
launch
resource
config
src
)
ament_package()
161 changes: 161 additions & 0 deletions simulator/autoware_carla_interface/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,161 @@
# autoware_carla_interface

## ROS 2/Autoware.universe bridge for CARLA simulator

Thanks to <https://github.com/gezp> for ROS 2 Humble support for CARLA Communication.
This ros package enables communication between Autoware and CARLA for autonomous driving simulation.

## Supported Environment

| ubuntu | ros | carla | autoware |
| :----: | :----: | :----: | :------: |
| 22.04 | humble | 0.9.15 | Main |

## Setup

### Install

- [CARLA Installation](https://carla.readthedocs.io/en/latest/start_quickstart/)
- [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/)
- [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)

- Install the wheel using pip.
- OR add the egg file to the `PYTHONPATH`.

1. Download maps (y-axis inverted version) to arbitrary location
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`)
3. Create `map_projector_info.yaml` on the folder and add `projector_type: local` on the first line.

### Build

```bash
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release
```

### Run

1. Run carla, change map, spawn object if you need
<!--- cspell:ignore prefernvidia -->

```bash
cd CARLA
./CarlaUE4.sh -prefernvidia -quality-level=Low -RenderOffScreen
```

2. Run ros nodes

```bash
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
```

3. Set initial pose (Init by GNSS)
4. Set goal position
5. Wait for planning
6. Engage

## Inner-workings / Algorithms

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`.

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`.

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`.

### Configurable Parameters for World Loading

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] |
| `carla_map` | string | "Town01" | Name of the map to load in CARLA |
| `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) |
| `objects_definition_file` | string | "$(find-pkg-share autoware_carla_interface)/objects.json" | Sensor parameters file that are used for spawning sensor in CARLA |
| `use_traffic_manager` | bool | True | 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` |
| `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. |

### Configurable Parameters for Sensors

Below parameters can be configured in `carla_ros.py`.

| Name | Type | Default Value | Description |
| ------------------------- | ---- | -------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `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. |

- CARLA sensor parameters can be configured in `config/objects.json`.
- 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/).

### World Loading

The `carla_ros.py` sets up the CARLA world:

1. **Client Connection**:

```python
client = carla.Client(self.local_host, self.port)
client.set_timeout(self.timeout)
```

2. **Load the Map**:

Map loaded in CARLA world with map according to `carla_map` parameter.

```python
client.load_world(self.map_name)
self.world = client.get_world()
```

3. **Spawn Ego Vehicle**:

Vehicle are spawn according to `vehicle_type`, `spawn_point`, and `agent_role_name` parameter.

```python
spawn_point = carla.Transform()
point_items = self.spawn_point.split(",")
if len(point_items) == 6:
spawn_point.location.x = float(point_items[0])
spawn_point.location.y = float(point_items[1])
spawn_point.location.z = float(point_items[2]) + 2
spawn_point.rotation.roll = float(point_items[3])
spawn_point.rotation.pitch = float(point_items[4])
spawn_point.rotation.yaw = float(point_items[5])
CarlaDataProvider.request_new_actor(self.vehicle_type, spawn_point, self.agent_role_name)
```

## Traffic Light Recognition

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.

- Options to Modify the Map

- A. Create a New Map from Scratch
- Use the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map.

- B. Modify the Existing Carla Lanelet2 Maps
- 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).
- Use this [tool](https://github.com/mraditya01/offset_lanelet2/tree/main) to modify the coordinates.
- Snap Lanelet with PCD and add the traffic lights using the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/).

- 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.
- 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).

## Tips

- Misalignment might occurs during initialization, pressing `init by gnss` button should fix it.
- 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).

## Known Issues and Future Works

- Testing on procedural map (Adv Digital Twin).
- Currently unable to test it due to failing in the creation of the Adv digital twin map.
- Automatic sensor configuration of the CARLA sensors from the Autoware sensor kit.
- 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.
- Traffic light recognition.
- 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 number Diff line number Diff line change
@@ -0,0 +1,7 @@
default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89
0,0.090,-0.204,-0.490,-0.490,-0.491,-0.492,-0.493,-0.494,-0.495,-0.496,-0.500
0.100,0.167,0.166,-0.093,-0.243,-0.244,-0.245,-0.246,-0.247,-0.248,-0.249,-0.280
0.200,0.941,0.464,0.186,0.004,-0.100,-0.101,-0.102,-0.103,-0.104,-0.105,-0.106
0.300,1.747,1.332,0.779,0.778,0.777,0.776,0.775,0.774,0.720,0.640,0.580
0.400,2.650,2.480,2.300,2.130,1.950,1.750,1.580,1.450,1.320,1.200,1.100
0.500,3.300,3.250,3.120,2.920,2.680,2.350,2.170,1.980,1.880,1.730,1.610
10 changes: 10 additions & 0 deletions simulator/autoware_carla_interface/calibration_maps/brake_map.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89
0,0.090,-0.204,-0.490,-0.490,-0.491,-0.492,-0.493,-0.494,-0.495,-0.496,-0.500
0.100,0.089,-0.226,-0.535,-0.536,-0.537,-0.538,-0.539,-0.540,-0.541,-0.542,-0.543
0.200,-0.380,-0.414,-0.746,-0.800,-0.820,-0.850,-0.870,-0.890,-0.910,-0.940,-0.960
0.300,-1.000,-1.040,-1.480,-1.550,-1.570,-1.590,-1.610,-1.630,-1.631,-1.632,-1.633
0.400,-1.480,-1.500,-1.850,-2.050,-2.100,-2.101,-2.102,-2.103,-2.104,-2.105,-2.106
0.500,-1.490,-1.510,-1.860,-2.060,-2.110,-2.111,-2.112,-2.113,-2.114,-2.115,-2.116
0.600,-1.500,-1.520,-1.870,-2.070,-2.120,-2.121,-2.122,-2.123,-2.124,-2.125,-2.126
0.700,-1.510,-1.530,-1.880,-2.080,-2.130,-2.131,-2.132,-2.133,-2.134,-2.135,-2.136
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 number Diff line number Diff line change
@@ -0,0 +1,4 @@
default,-10,0,10
-1,-0.9,-0.9,-0.9
0,0,0,0
1,0.9,0.9,0.9
62 changes: 62 additions & 0 deletions simulator/autoware_carla_interface/config/objects.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
{
"sensors": [
{
"type": "sensor.camera.rgb",
"id": "rgb_front",
"spawn_point": {
"x": 0.7,
"y": 0.0,
"z": 1.6,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
},
"image_size_x": 1920,
"image_size_y": 1080,
"fov": 90.0
},
{
"type": "sensor.lidar.ray_cast",
"id": "top",
"spawn_point": {
"x": 0.0,
"y": 0.0,
"z": 3.1,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
},
"range": 100,
"channels": 64,
"points_per_second": 300000,
"upper_fov": 10.0,
"lower_fov": -30.0,
"rotation_frequency": 20,
"noise_stddev": 0.0
},
{
"type": "sensor.other.gnss",
"id": "gnss",
"spawn_point": {
"x": 0.0,
"y": 0.0,
"z": 1.6,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
}
},
{
"type": "sensor.other.imu",
"id": "imu",
"spawn_point": {
"x": 0.0,
"y": 0.0,
"z": 1.6,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0
}
}
]
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
/**:
ros__parameters:
csv_path_accel_map: $(find-pkg-share autoware_carla_interface)/accel_map.csv
csv_path_brake_map: $(find-pkg-share autoware_carla_interface)/brake_map.csv
csv_path_steer_map: $(find-pkg-share autoware_carla_interface)/steer_map.csv
convert_accel_cmd: true
convert_brake_cmd: true
convert_steer_cmd: false
use_steer_ff: true
use_steer_fb: true
is_debugging: false
max_throttle: 0.4
max_brake: 0.8
max_steer: 1.0
min_steer: -1.0
steer_pid:
kp: 150.0
ki: 15.0
kd: 0.0
max: 8.0
min: -8.0
max_p: 8.0
min_p: -8.0
max_i: 8.0
min_i: -8.0
max_d: 0.0
min_d: 0.0
invalid_integration_decay: 0.97
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
<launch>
<group>
<arg name="host" default="localhost"/>
<arg name="port" default="2000"/>
<arg name="timeout" default="20"/>
<arg name="ego_vehicle_role_name" default="ego_vehicle"/>
<arg name="vehicle_type" default="vehicle.toyota.prius"/>
<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.]"/>
<arg name="carla_map" default="Town01"/>
<arg name="sync_mode" default="True"/>
<arg name="fixed_delta_seconds" default="0.05" description="Time step for CARLA, FPS=1/value"/>
<arg name="objects_definition_file" default="$(find-pkg-share autoware_carla_interface)/objects.json"/>
<arg name="use_traffic_manager" default="False"/>
<arg name="max_real_delta_seconds" default="0.05"/>

<!-- CARLA Interface -->
<node pkg="autoware_carla_interface" exec="autoware_carla_interface" name="autoware_carla_interface" output="screen">
<param name="host" value="$(var host)"/>
<param name="port" value="$(var port)"/>
<param name="timeout" value="$(var timeout)"/>
<param name="sync_mode" value="$(var sync_mode)"/>
<param name="fixed_delta_seconds" value="$(var fixed_delta_seconds)"/>
<param name="carla_map" value="$(var carla_map)"/>
<param name="ego_vehicle_role_name" value="$(var ego_vehicle_role_name)"/>
<param name="spawn_point" value="$(var spawn_point)"/>
<param name="vehicle_type" value="$(var vehicle_type)"/>
<param name="objects_definition_file" value="$(var objects_definition_file)"/>
<param name="use_traffic_manager" value="$(var use_traffic_manager)"/>
<param name="max_real_delta_seconds" value="$(var max_real_delta_seconds)"/>
</node>

<arg name="input_control_cmd" default="/control/command/control_cmd"/>
<arg name="input_odometry" default="/localization/kinematic_state"/>
<arg name="input_steering" default="/vehicle/status/steering_status"/>
<arg name="output_actuation_cmd" default="/control/command/actuation_cmd"/>
<arg name="config_file" default="$(find-pkg-share autoware_carla_interface)/raw_vehicle_cmd_converter.param.yaml"/>

<node pkg="autoware_raw_vehicle_cmd_converter" exec="autoware_raw_vehicle_cmd_converter_node" name="autoware_raw_vehicle_cmd_converter" output="screen">
<param from="$(var config_file)" allow_substs="true"/>
<remap from="~/input/control_cmd" to="$(var input_control_cmd)"/>
<remap from="~/input/odometry" to="$(var input_odometry)"/>
<remap from="~/input/steering" to="$(var input_steering)"/>
<remap from="~/output/actuation_cmd" to="$(var output_actuation_cmd)"/>
</node>

<!-- Awsim configuration frame to CARLA frame -->
<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 "/>
<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 "/>
</group>
</launch>
Loading

0 comments on commit 5b1d14e

Please sign in to comment.