-
Notifications
You must be signed in to change notification settings - Fork 0
/
sensors.py
317 lines (240 loc) · 12.6 KB
/
sensors.py
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
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
'''
Sensors Module:
It provides classes for each CARLA sensor to attach to the vehicle and listen to the data from the sensor using callbacks.
Available sensors:
- RGB Camera
- LiDAR
- Radar
- GNSS
- IMU
- Collision
- Lane Invasion
Future Sensors:
- Semantic Segmentation Camera
- Instance Segmentation Camera
- Depth Camera
- Lidar Semantic Segmentation
- Obstacle Detection
- Optical Flow Camera (AKA: Motion Camera)
'''
import carla
import numpy as np
from PIL import Image
import cv2
import configuration
# ====================================== RGB Camera ======================================
class RGB_Camera:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_rgb_camera(world, vehicle, sensor_dict)
self.last_data = None
self.sensor.listen(lambda data: self.callback(data))
def attach_rgb_camera(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.camera.rgb')
# attributes
sensor_bp.set_attribute('image_size_x', str(sensor_dict['image_size_x']))
sensor_bp.set_attribute('image_size_y', str(sensor_dict['image_size_y']))
sensor_bp.set_attribute('fov', str(sensor_dict['fov']))
sensor_bp.set_attribute('sensor_tick', str(sensor_dict['sensor_tick']))
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
camera_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return camera_sensor
def callback(self, data):
global configuration
# Get the image from the data
image = Image.frombytes('RGBA', (data.width, data.height), data.raw_data, 'raw', 'RGBA')
# Convert the image to a NumPy array
image_array = np.array(image)
# Ensure the array is contiguous in memory
image_array = np.ascontiguousarray(image_array)
# Convert to RGB using OpenCV function
image_array = cv2.cvtColor(image_array, cv2.COLOR_RGBA2RGB)
# Display the processed image using Pygame
self.last_data = image_array
# Save image in directory
if configuration.VERBOSE:
timestamp = data.timestamp
cv2.imwrite(f'data/rgb_camera/{timestamp}.png', image_array)
def get_last_data(self):
return self.last_data
def destroy(self):
self.sensor.destroy()
# ====================================== LiDAR ======================================
class Lidar:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_lidar(world, vehicle, sensor_dict)
self.last_data = None
self.sensor.listen(lambda data: self.callback(data))
def attach_lidar(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.lidar.ray_cast')
# attributes
sensor_bp.set_attribute('channels', str(sensor_dict['channels']))
sensor_bp.set_attribute('points_per_second', str(sensor_dict['points_per_second']))
sensor_bp.set_attribute('rotation_frequency', str(sensor_dict['rotation_frequency']))
sensor_bp.set_attribute('range', str(sensor_dict['range']))
sensor_bp.set_attribute('upper_fov', str(sensor_dict['upper_fov']))
sensor_bp.set_attribute('lower_fov', str(sensor_dict['lower_fov']))
sensor_bp.set_attribute('sensor_tick', str(sensor_dict['sensor_tick']))
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
lidar_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return lidar_sensor
def callback(self, data):
global configuration
# Get the LiDAR point cloud from the data
lidar_data = data.raw_data
lidar_data = np.frombuffer(lidar_data, dtype=np.dtype('f4'))
lidar_data = np.reshape(lidar_data, (int(lidar_data.shape[0] / 4), 4))
# Extract X, Y, Z coordinates and intensity values
points_xyz = lidar_data[:, :3]
intensity = lidar_data[:, 3]
# Intensity scaling factor
intensity_scale = 10.0 # Adjust this value to control the brightness
# Create a 2D histogram with a predetermined size
width, height = 640, 360
lidar_image_array = np.zeros((height, width))
# Scale and shift X and Y coordinates to fit within the histogram size
x_scaled = ((points_xyz[:, 0] + 50) / 100) * (width - 1)
y_scaled = ((points_xyz[:, 1] + 50) / 100) * (height - 1)
# Round the scaled coordinates to integers
x_indices = np.round(x_scaled).astype(int)
y_indices = np.round(y_scaled).astype(int)
# Clip the indices to stay within the image bounds
x_indices = np.clip(x_indices, 0, width - 1)
y_indices = np.clip(y_indices, 0, height - 1)
# Assign scaled intensity values to the corresponding pixel in the histogram
lidar_image_array[y_indices, x_indices] = intensity * intensity_scale
# Clip the intensity values to stay within the valid color range
lidar_image_array = np.clip(lidar_image_array, 0, 255)
# Display the processed image using Pygame
self.last_data = lidar_image_array
# Save image in directory
if configuration.VERBOSE:
timestamp = data.timestamp
cv2.imwrite(f'data/lidar/{timestamp}.png', lidar_image_array)
def get_last_data(self):
return self.last_data
def destroy(self):
self.sensor.destroy()
# ====================================== Radar ======================================
class Radar:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_radar(world, vehicle, sensor_dict)
self.last_data = None
self.sensor.listen(lambda data: self.callback(data))
def attach_radar(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.other.radar')
# attributes
sensor_bp.set_attribute('horizontal_fov', str(sensor_dict['horizontal_fov']))
sensor_bp.set_attribute('vertical_fov', str(sensor_dict['vertical_fov']))
sensor_bp.set_attribute('points_per_second', str(sensor_dict['points_per_second']))
sensor_bp.set_attribute('range', str(sensor_dict['range']))
sensor_bp.set_attribute('sensor_tick', str(sensor_dict['sensor_tick']))
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
radar_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return radar_sensor
def callback(self, data):
global configuration
# Get the radar data
radar_data = data.raw_data
points = np.frombuffer(radar_data, dtype=np.dtype('f4'))
points = np.reshape(points, (len(data), 4))
# Extract information from radar points
azimuths = points[:, 1]
depths = points[:, 3]
# Create a 2D histogram with a predetermined size
width, height = 640, 360
radar_image_array = np.zeros((height, width))
# Scale azimuth values to fit within the histogram size
azimuth_scaled = ((np.degrees(azimuths) + 180) / 360) * (width - 1)
# Scale depth values to fit within the histogram size
depth_scaled = (depths / 100) * (height - 1)
# Round the scaled azimuth and depth values to integers
azimuth_indices = np.round(azimuth_scaled).astype(int)
depth_indices = np.round(depth_scaled).astype(int)
# Clip the indices to stay within the image bounds
azimuth_indices = np.clip(azimuth_indices, 0, width - 1)
depth_indices = np.clip(depth_indices, 0, height - 1)
# Set a value (e.g., velocity) at each (azimuth, depth) coordinate in the histogram
radar_image_array[depth_indices, azimuth_indices] = 255 # Set a constant value for visibility
self.last_data = radar_image_array
# Save image in directory
if configuration.VERBOSE:
timestamp = data.timestamp
cv2.imwrite(f'data/radar/{timestamp}.png', radar_image_array)
def get_last_data(self):
return self.last_data
def destroy(self):
self.sensor.destroy()
# ====================================== GNSS ======================================
class GNSS:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_gnss(world, vehicle, sensor_dict)
self.last_data = None
self.sensor.listen(lambda data: self.callback(data))
def attach_gnss(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.other.gnss')
# attributes
sensor_bp.set_attribute('sensor_tick', str(sensor_dict['sensor_tick']))
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
gnss_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return gnss_sensor
def callback(self, data):
global configuration
self.last_data = data
def get_last_data(self):
return self.last_data
def destroy(self):
self.sensor.destroy()
# ====================================== IMU ======================================
class IMU:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_imu(world, vehicle, sensor_dict)
self.sensor.listen(lambda data: self.callback(data))
def attach_imu(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.other.imu')
# attributes
sensor_bp.set_attribute('sensor_tick', str(sensor_dict['sensor_tick']))
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
imu_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return imu_sensor
def callback(self, data):
global configuration
self.last_data = data
def get_last_data(self):
return self.last_data
def destroy(self):
self.sensor.destroy()
# ====================================== Collision ======================================
class Collision:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_collision(world, vehicle, sensor_dict)
self.sensor.listen(lambda data: self.callback(data))
def attach_collision(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.other.collision')
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
collision_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return collision_sensor
def callback(self, data):
print(f"Collision Occurred at {data.timestamp} with {data.other_actor}")
def destroy(self):
self.sensor.destroy()
# ====================================== Lane Invasion ======================================
class Lane_Invasion:
def __init__(self, world, vehicle, sensor_dict):
self.sensor = self.attach_lane_invasion(world, vehicle, sensor_dict)
self.sensor.listen(lambda data: self.callback(data))
def attach_lane_invasion(self, world, vehicle, sensor_dict):
sensor_bp = world.get_blueprint_library().find('sensor.other.lane_invasion')
# This will place the camera in the front bumper of the car
transform = carla.Transform(carla.Location(x=sensor_dict['location_x'], y=sensor_dict['location_y'] , z=sensor_dict['location_z']))
lane_invasion_sensor = world.spawn_actor(sensor_bp, transform, attach_to=vehicle)
return lane_invasion_sensor
def callback(self, data):
print(f"Lane Invasion Occurred at {data.timestamp} with {data.crossed_lane_markings}")
def destroy(self):
self.sensor.destroy()