NOTICE
This contents may be invalid after CARLA’s official support for ROS interface.
I used Carla0.8.1, its latest commit was on Apr 5, 2018.
Carla0.8.1 on GitHub
Summary
This articles explains how to get point cloud data in CARLA and export it to ROS. Specifically how to do the followings.
- equip a pseudo LiDAR on a vehicle
- obtain pointcloud data from the CARLA server via a client
- convert pointcloud into ROS message and publish it as a ROS topic
- display points in RVIZ
It’s assumed that you’ve already built CARLA from source.
Overview
Right after the installation, CARLA will be launched in stand-alone mode (it’s like video game mode: we manually control a vehicle with the keyboard) and no sensors are equipped on the vehicle.
In order to obtain sensor data from the virtual 3D world, CARLA should be launched in server mode.
When CARLA is working in server mode, we can get pseudo sensor data via a client program.
Equip pseudo LiDAR
You already should have CarlaSettings.ini under the directory in which you built CARLA. Let’s copy and modify it.
First, we need to define what types of sensors we use.
Find [CARLA/Sensor] block and add “Sensors=MyLidar”.
Probably you can see some default definitions already exist and all of them are commented-out. It’s also OK to un-comment one of them, for example, “Sensors=MyCamera,MyLidar” (now we don’t use camera although). “MyLidar” is just a name, so whatever will be fine: “main_lidar”, “Lidar01”, etc.1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30[CARLA/Sensor]
; Names of the sensors to be attached to the player, comma-separated, each of
; them should be defined in its own subsection.
; Uncomment next line to add a camera called MyCamera to the vehicle
; Sensors=MyCamera
; or uncomment next line to add a camera and a Lidar
Sensors=MyCamera,MyLidar
[CARLA/Sensor/MyLidar]
SensorType=LIDAR_RAY_CAST
; Number of lasers.
Channels=32
; Measure distance in meters.
Range=50.0
; Points generated by all lasers per second.
PointsPerSecond=100000
; Lidar rotation frequency.
RotationFrequency=10
; Upper and lower laser angles, positive values means above horizontal line.
UpperFOVLimit=10
LowerFOVLimit=-30
; Position and rotation relative to the vehicle.
PositionX=0
PositionY=0
PositionZ=1.40
RotationPitch=0
RotationYaw=0
RotationRoll=0
Make client program
A sample client program is already included in the installed directory. Find “client_example.py”.
You can modify this program so that the obtained LiDAR data is published as a ROS topic.
Obtain LiDAR data from the server
Find the following sentences. This is where sensor data is received.1
2# Read the data produced by the server this frame.
measurements, sensor_data = client.read_data()
You can check the contents like below. All the attributes are shown in the official support page.
Ray-cast based Lidar1
2
3
4
5
6
7
8# Read the data produced by the server this frame.
measurements, sensor_data = client.read_data()
# Check LiDAR data is included
for name, m in sensor_data.items():
print('Sensor name: %s' % name)
if name == 'MyLidar':
print('LiDAR %f, %d, %d' % (m.horizontal_angle, m.channels, len(m.point_count_by_channel)))
Publish pointcloud as a ROS topic
Here I excerpt codes to add. Please insert them into client_example.py properly.
1 | # import ROS module |
1 | def convert_pointcloud_carla_to_ros(frame, points): |
1 | # setup ROS node |
1 | # Read the data produced by the server this frame. |
Run CARLA in server mode
When launching CARLA, add -carla-server
option. See the below link.
Connecting a Python client
Run client program
After launching the server, run the client program on another terminal. Notice that you might need to change shebang because ROS uses Python2 (not 3).1
./client_example.py -c CarlaSettings.ini
Then, the client will publish LiDAR data as a ROS topic and you can see in RVIZ easily.