-
Notifications
You must be signed in to change notification settings - Fork 70
/
Copy pathdata_collect.py
1677 lines (1542 loc) · 85.1 KB
/
data_collect.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
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
from srunner.scenariomanager.carla_data_provider import CarlaDataProvider
from leaderboard.envs.sensor_interface import SensorInterface, CallBack, OpenDriveMapReader, SpeedometerReader
import cv2
import json
import numpy as np
import xml.etree.ElementTree as ET
import carla
import gzip
from easydict import EasyDict
import math
import h5py
import laspy
from utils import build_projection_matrix, convert_depth, get_relative_transform, normalize_angle, build_skeleton, get_matrix, calculate_cube_vertices, compute_2d_distance
from utils import DIS_CAR_SAVE, DIS_WALKER_SAVE, DIS_SIGN_SAVE, DIS_LIGHT_SAVE
EARTH_RADIUS_EQUA = 6378137.0
class Env_Manager():
frame_rate = 10.0
def tick(self, input_data):
# control
control = self.manager.ego_vehicles[0].get_control()
# camera_bgr
cam_bgr_front = input_data['CAM_FRONT'][1][:, :, :3]
cam_bgr_front_left = input_data['CAM_FRONT_LEFT'][1][:, :, :3]
cam_bgr_front_right = input_data['CAM_FRONT_RIGHT'][1][:, :, :3]
cam_bgr_back = input_data['CAM_BACK'][1][:, :, :3]
cam_bgr_back_left = input_data['CAM_BACK_LEFT'][1][:, :, :3]
cam_bgr_back_right = input_data['CAM_BACK_RIGHT'][1][:, :, :3]
cam_bgr_top_down = input_data['TOP_DOWN'][1][:, :, :3]
# radar
radar_front = input_data['RADAR_FRONT'][1].astype(np.float16)
radar_front_left = input_data['RADAR_FRONT_LEFT'][1].astype(np.float16)
radar_front_right = input_data['RADAR_FRONT_RIGHT'][1].astype(np.float16)
radar_back_left = input_data['RADAR_BACK_LEFT'][1].astype(np.float16)
radar_back_right = input_data['RADAR_BACK_RIGHT'][1].astype(np.float16)
# lidar
lidar = input_data['LIDAR_TOP']
lidar_seg = input_data['LIDAR_TOP_SEG']
def lidar_to_ego_coordinate(lidar):
"""
Converts the LiDAR points given by the simulator into the ego agents
coordinate system
:param config: GlobalConfig, used to read out lidar orientation and location
:param lidar: the LiDAR point cloud as provided in the input of run_step
:return: lidar where the points are w.r.t. 0/0/0 of the car and the carla
coordinate system.
"""
lidar_rot = [0.0, 0.0, 0.0]
lidar_pos = [-0.39, 0.0, 1.84]
yaw = np.deg2rad(lidar_rot[2])
rotation_matrix = np.array([[np.cos(yaw), -np.sin(yaw), 0.0], [np.sin(yaw), np.cos(yaw), 0.0], [0.0, 0.0, 1.0]])
translation = np.array(lidar_pos)
# The double transpose is a trick to compute all the points together.
ego_lidar = (rotation_matrix @ lidar[1][:, :3].T).T + translation
return ego_lidar
lidar = lidar_to_ego_coordinate(lidar)
lidar_360 = lidar
bounding_boxes = self.get_bounding_boxes(lidar=lidar_360, radar=radar_front)
sensors_anno = self.get_sensors_anno()
self.last_lidar = lidar
self.last_ego_transform = self.manager.ego_vehicles[0].get_transform()
# gps/imu
gps = input_data['GPS'][1][:2]
speed = input_data['SPEED'][1]['speed']
compass = input_data['IMU'][1][-1]
acceleration = input_data['IMU'][1][:3]
angular_velocity = input_data['IMU'][1][3:6]
# cam_bgr_depth
cam_bgr_front_depth = input_data['CAM_FRONT_DEPTH'][1][:, :, :3]
cam_bgr_front_left_depth = input_data['CAM_FRONT_LEFT_DEPTH'][1][:, :, :3]
cam_bgr_front_right_depth = input_data['CAM_FRONT_RIGHT_DEPTH'][1][:, :, :3]
cam_bgr_back_depth = input_data['CAM_BACK_DEPTH'][1][:, :, :3]
cam_bgr_back_left_depth = input_data['CAM_BACK_LEFT_DEPTH'][1][:, :, :3]
cam_bgr_back_right_depth = input_data['CAM_BACK_RIGHT_DEPTH'][1][:, :, :3]
# cam_sem_seg
cam_front_sem_seg = input_data["CAM_FRONT_SEM_SEG"][1][:, :, 2]
cam_front_left_sem_seg = input_data["CAM_FRONT_LEFT_SEM_SEG"][1][:, :, 2]
cam_front_right_sem_seg = input_data["CAM_FRONT_RIGHT_SEM_SEG"][1][:, :, 2]
cam_back_sem_seg = input_data["CAM_BACK_SEM_SEG"][1][:, :, 2]
cam_back_left_sem_seg = input_data["CAM_BACK_LEFT_SEM_SEG"][1][:, :, 2]
cam_back_right_sem_seg = input_data["CAM_BACK_RIGHT_SEM_SEG"][1][:, :, 2]
# cam_ins_seg
cam_front_ins_seg = input_data["CAM_FRONT_INS_SEG"][1]
cam_front_left_ins_seg = input_data["CAM_FRONT_LEFT_INS_SEG"][1]
cam_front_right_ins_seg = input_data["CAM_FRONT_RIGHT_INS_SEG"][1]
cam_back_ins_seg = input_data["CAM_BACK_INS_SEG"][1]
cam_back_left_ins_seg = input_data["CAM_BACK_LEFT_INS_SEG"][1]
cam_back_right_ins_seg = input_data["CAM_BACK_RIGHT_INS_SEG"][1]
# cam_gray_depth, 16 bit would be ideal, but we can't afford the extra storage.
cam_gray_front_depth = convert_depth(cam_bgr_front_depth)
cam_gray_front_left_depth = convert_depth(cam_bgr_front_left_depth)
cam_gray_front_right_depth = convert_depth(cam_bgr_front_right_depth)
cam_gray_back_depth = convert_depth(cam_bgr_back_depth)
cam_gray_back_left_depth = convert_depth(cam_bgr_back_left_depth)
cam_gray_back_right_depth = convert_depth(cam_bgr_back_right_depth)
# weather
weather = self._weather_to_dict(self.world.get_weather())
self.cam_bgr_mapping = {
'CAM_FRONT': 'cam_bgr_front',
'CAM_FRONT_LEFT': 'cam_bgr_front_left',
'CAM_FRONT_RIGHT': 'cam_bgr_front_right',
'CAM_BACK': 'cam_bgr_back',
'CAM_BACK_LEFT': 'cam_bgr_back_left',
'CAM_BACK_RIGHT': 'cam_bgr_back_right',
}
self.cam_bgr_depth_mapping = {
'CAM_FRONT': 'cam_bgr_front_depth',
'CAM_FRONT_LEFT': 'cam_bgr_front_left_depth',
'CAM_FRONT_RIGHT': 'cam_bgr_front_right_depth',
'CAM_BACK': 'cam_bgr_back_depth',
'CAM_BACK_LEFT': 'cam_bgr_back_left_depth',
'CAM_BACK_RIGHT': 'cam_bgr_back_right_depth',
}
self.cam_gray_depth_mapping = {
'CAM_FRONT': 'cam_gray_front_depth',
'CAM_FRONT_LEFT': 'cam_gray_front_left_depth',
'CAM_FRONT_RIGHT': 'cam_gray_front_right_depth',
'CAM_BACK': 'cam_gray_back_depth',
'CAM_BACK_LEFT': 'cam_gray_back_left_depth',
'CAM_BACK_RIGHT': 'cam_gray_back_right_depth',
}
self.cam_seg_mapping = {
'CAM_FRONT': 'cam_front_sem_seg',
'CAM_FRONT_LEFT': 'cam_front_left_sem_seg',
'CAM_FRONT_RIGHT': 'cam_front_right_sem_seg',
'CAM_BACK': 'cam_back_sem_seg',
'CAM_BACK_LEFT': 'cam_back_left_sem_seg',
'CAM_BACK_RIGHT': 'cam_back_right_sem_seg',
}
self.cam_ins_mapping = {
'CAM_FRONT': 'cam_front_ins_seg',
'CAM_FRONT_LEFT': 'cam_front_left_ins_seg',
'CAM_FRONT_RIGHT': 'cam_front_right_ins_seg',
'CAM_BACK': 'cam_back_ins_seg',
'CAM_BACK_LEFT': 'cam_back_left_ins_seg',
'CAM_BACK_RIGHT': 'cam_back_right_ins_seg',
}
self.radar_mapping = {
'RADAR_FRONT': 'radar_front',
'RADAR_FRONT_LEFT': 'radar_front_left',
'RADAR_FRONT_RIGHT': 'radar_front_right',
'RADAR_BACK_LEFT': 'radar_back_left',
'RADAR_BACK_RIGHT': 'radar_back_right',
}
self.cam_yaw_mapping = {
'CAM_FRONT': 0.0,
'CAM_FRONT_LEFT': -55.0,
'CAM_FRONT_RIGHT': 55.0,
'CAM_BACK': 180.0,
'CAM_BACK_LEFT': -110.0,
'CAM_BACK_RIGHT': 110.0,
}
results = {
# cam_bgr
'cam_bgr_front': cam_bgr_front,
'cam_bgr_front_left': cam_bgr_front_left,
'cam_bgr_front_right': cam_bgr_front_right,
'cam_bgr_back': cam_bgr_back,
'cam_bgr_back_left': cam_bgr_back_left,
'cam_bgr_back_right': cam_bgr_back_right,
'cam_bgr_top_down': cam_bgr_top_down,
# cam_sem_seg
'cam_front_sem_seg': cam_front_sem_seg,
'cam_front_left_sem_seg': cam_front_left_sem_seg,
'cam_front_right_sem_seg': cam_front_right_sem_seg,
'cam_back_sem_seg': cam_back_sem_seg,
'cam_back_left_sem_seg': cam_back_left_sem_seg,
'cam_back_right_sem_seg': cam_back_right_sem_seg,
# cam_ins_seg
'cam_front_ins_seg': cam_front_ins_seg,
'cam_front_left_ins_seg': cam_front_left_ins_seg,
'cam_front_right_ins_seg': cam_front_right_ins_seg,
'cam_back_ins_seg': cam_back_ins_seg,
'cam_back_left_ins_seg': cam_back_left_ins_seg,
'cam_back_right_ins_seg': cam_back_right_ins_seg,
# cam_gray_depth
# save the original bgr depth, please remember to post-process the depth
'cam_bgr_front_depth': cam_bgr_front_depth,
'cam_bgr_front_left_depth' : cam_bgr_front_left_depth,
'cam_bgr_front_right_depth': cam_bgr_front_right_depth,
'cam_bgr_back_depth': cam_bgr_back_depth,
'cam_bgr_back_left_depth': cam_bgr_back_left_depth,
'cam_bgr_back_right_depth': cam_bgr_back_right_depth,
'cam_gray_front_depth': cam_gray_front_depth,
'cam_gray_front_left_depth': cam_gray_front_left_depth,
'cam_gray_front_right_depth': cam_gray_front_right_depth,
'cam_gray_back_depth': cam_gray_back_depth,
'cam_gray_back_left_depth': cam_gray_back_left_depth,
'cam_gray_back_right_depth': cam_gray_back_right_depth,
# radar
'radar_front': radar_front,
'radar_front_left': radar_front_left,
'radar_front_right': radar_front_right,
'radar_back_left': radar_back_left,
'radar_back_right': radar_back_right,
# lidar
'lidar' : lidar_360,
'lidar_seg': lidar_seg,
# other
'gps': gps,
'speed': speed,
'compass': compass,
'weather': weather,
"acceleration":acceleration,
"angular_velocity":angular_velocity,
'bounding_boxes': bounding_boxes,
'sensors_anno': sensors_anno,
'throttle': control.throttle,
'steer': control.steer,
'brake': control.brake,
'reverse': control.reverse,
'town': self.town,
}
return results
def _preprocess_sensor_spec(self, sensor_spec):
type_ = sensor_spec["type"]
id_ = sensor_spec["id"]
attributes = {}
if type_ == 'sensor.opendrive_map':
attributes['reading_frequency'] = sensor_spec['reading_frequency']
sensor_location = carla.Location()
sensor_rotation = carla.Rotation()
elif type_ == 'sensor.speedometer':
delta_time = CarlaDataProvider.get_world().get_settings().fixed_delta_seconds
attributes['reading_frequency'] = 1 / delta_time
sensor_location = carla.Location()
sensor_rotation = carla.Rotation()
if type_ == 'sensor.camera.rgb':
attributes['image_size_x'] = str(sensor_spec['width'])
attributes['image_size_y'] = str(sensor_spec['height'])
attributes['fov'] = str(sensor_spec['fov'])
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.camera.depth':
attributes['image_size_x'] = str(sensor_spec['width'])
attributes['image_size_y'] = str(sensor_spec['height'])
attributes['fov'] = str(sensor_spec['fov'])
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.camera.semantic_segmentation':
attributes['image_size_x'] = str(sensor_spec['width'])
attributes['image_size_y'] = str(sensor_spec['height'])
attributes['fov'] = str(sensor_spec['fov'])
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.camera.instance_segmentation':
attributes['image_size_x'] = str(sensor_spec['width'])
attributes['image_size_y'] = str(sensor_spec['height'])
attributes['fov'] = str(sensor_spec['fov'])
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.lidar.ray_cast':
attributes['range'] = str(sensor_spec['range'])
attributes['rotation_frequency'] = str(sensor_spec['rotation_frequency'])
attributes['channels'] = str(sensor_spec['channels'])
attributes['upper_fov'] = str(10)
attributes['lower_fov'] = str(-30)
attributes['points_per_second'] = str(sensor_spec['points_per_second'])
attributes['atmosphere_attenuation_rate'] = str(0.004)
attributes['dropoff_general_rate'] = str(sensor_spec['dropoff_general_rate'])
attributes['dropoff_intensity_limit'] = str(sensor_spec['dropoff_intensity_limit'])
attributes['dropoff_zero_intensity'] = str(sensor_spec['dropoff_zero_intensity'])
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.lidar.ray_cast_semantic':
attributes['range'] = str(sensor_spec['range'])
attributes['rotation_frequency'] = str(sensor_spec['rotation_frequency'])
attributes['channels'] = str(sensor_spec['channels'])
attributes['upper_fov'] = str(10)
attributes['lower_fov'] = str(-30)
attributes['points_per_second'] = str(sensor_spec['points_per_second'])
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.other.radar':
attributes['horizontal_fov'] = str(sensor_spec['horizontal_fov']) # degrees
attributes['vertical_fov'] = str(sensor_spec['vertical_fov']) # degrees
attributes['points_per_second'] = '1500'
attributes['range'] = sensor_spec['range'] # meters
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'],
y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif type_ == 'sensor.other.gnss':
attributes['noise_alt_stddev'] = str(0.000005)
attributes['noise_lat_stddev'] = str(0.000005)
attributes['noise_lon_stddev'] = str(0.000005)
attributes['noise_alt_bias'] = str(0.0)
attributes['noise_lat_bias'] = str(0.0)
attributes['noise_lon_bias'] = str(0.0)
sensor_location = carla.Location(x=sensor_spec['x'],
y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation()
attributes['role_name'] = str(sensor_spec['id'])
elif type_ == 'sensor.other.imu':
attributes['noise_accel_stddev_x'] = str(0.001)
attributes['noise_accel_stddev_y'] = str(0.001)
attributes['noise_accel_stddev_z'] = str(0.015)
attributes['noise_gyro_stddev_x'] = str(0.001)
attributes['noise_gyro_stddev_y'] = str(0.001)
attributes['noise_gyro_stddev_z'] = str(0.001)
attributes['role_name'] = str(sensor_spec['id'])
sensor_location = carla.Location(x=sensor_spec['x'],
y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
sensor_transform = carla.Transform(sensor_location, sensor_rotation)
return type_, id_, sensor_transform, attributes
def setup_sensors(self):
"""
Create the sensors defined by the user and attach them to the ego-vehicle
:param vehicle: ego vehicle
:return:
"""
vehicle = self.manager.ego_vehicles[0]
self.sensor_interface = SensorInterface()
world = CarlaDataProvider.get_world()
bp_library = world.get_blueprint_library()
for sensor_spec in self.sensors():
type_, id_, sensor_transform, attributes = self._preprocess_sensor_spec(sensor_spec)
# These are the pseudosensors (not spawned)
if type_ == 'sensor.opendrive_map':
sensor = OpenDriveMapReader(vehicle, attributes['reading_frequency'])
elif type_ == 'sensor.speedometer':
sensor = SpeedometerReader(vehicle, attributes['reading_frequency'])
# These are the sensors spawned on the carla world
else:
bp = bp_library.find(type_)
for key, value in attributes.items():
bp.set_attribute(str(key), str(value))
sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle)
# setup callback
sensor.listen(CallBack(id_, type_, sensor, self.sensor_interface))
self._sensors_list.append(sensor)
# Some sensors miss sending data during the first ticks, so tick several times and remove the data
for _ in range(10):
world.tick()
def sensors(self):
sensors = [
# camera rgb
{
'type': 'sensor.camera.rgb',
'x': 0.80, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT'
},
{
'type': 'sensor.camera.rgb',
'x': 0.27, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_LEFT'
},
{
'type': 'sensor.camera.rgb',
'x': 0.27, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_RIGHT'
},
{
'type': 'sensor.camera.rgb',
'x': -2.0, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,
'width': 1600, 'height': 900, 'fov': 110,
'id': 'CAM_BACK'
},
{
'type': 'sensor.camera.rgb',
'x': -0.32, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_LEFT'
},
{
'type': 'sensor.camera.rgb',
'x': -0.32, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_RIGHT'
},
# camera depth
{
'type': 'sensor.camera.depth',
'x': 0.80, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_DEPTH'
},
{
'type': 'sensor.camera.depth',
'x': 0.27, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_LEFT_DEPTH'
},
{
'type': 'sensor.camera.depth',
'x': 0.27, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_RIGHT_DEPTH'
},
{
'type': 'sensor.camera.depth',
'x': -2.0, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,
'width': 1600, 'height': 900, 'fov': 110,
'id': 'CAM_BACK_DEPTH'
},
{
'type': 'sensor.camera.depth',
'x': -0.32, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_LEFT_DEPTH'
},
{
'type': 'sensor.camera.depth',
'x': -0.32, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_RIGHT_DEPTH'
},
# camera seg
{
'type': 'sensor.camera.semantic_segmentation',
'x': 0.80, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_SEM_SEG'
},
{
'type': 'sensor.camera.semantic_segmentation',
'x': 0.27, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_LEFT_SEM_SEG'
},
{
'type': 'sensor.camera.semantic_segmentation',
'x': 0.27, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_RIGHT_SEM_SEG'
},
{
'type': 'sensor.camera.semantic_segmentation',
'x': -2.0, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,
'width': 1600, 'height': 900, 'fov': 110,
'id': 'CAM_BACK_SEM_SEG'
},
{
'type': 'sensor.camera.semantic_segmentation',
'x': -0.32, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_LEFT_SEM_SEG'
},
{
'type': 'sensor.camera.semantic_segmentation',
'x': -0.32, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_RIGHT_SEM_SEG'
},
# camera seg
{
'type': 'sensor.camera.instance_segmentation',
'x': 0.80, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_INS_SEG'
},
{
'type': 'sensor.camera.instance_segmentation',
'x': 0.27, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_LEFT_INS_SEG'
},
{
'type': 'sensor.camera.instance_segmentation',
'x': 0.27, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 55.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_FRONT_RIGHT_INS_SEG'
},
{
'type': 'sensor.camera.instance_segmentation',
'x': -2.0, 'y': 0.0, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0,
'width': 1600, 'height': 900, 'fov': 110,
'id': 'CAM_BACK_INS_SEG'
},
{
'type': 'sensor.camera.instance_segmentation',
'x': -0.32, 'y': -0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': -110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_LEFT_INS_SEG'
},
{
'type': 'sensor.camera.instance_segmentation',
'x': -0.32, 'y': 0.55, 'z': 1.60,
'roll': 0.0, 'pitch': 0.0, 'yaw': 110.0,
'width': 1600, 'height': 900, 'fov': 70,
'id': 'CAM_BACK_RIGHT_INS_SEG'
},
# lidar
{ 'type': 'sensor.lidar.ray_cast',
'x': -0.39, 'y': 0.0, 'z': 1.84,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'range': 85,
'rotation_frequency': 10,
'channels': 64,
'points_per_second': 600000,
'dropoff_general_rate': 0.0,
'dropoff_intensity_limit': 0.0,
'dropoff_zero_intensity': 0.0,
'id': 'LIDAR_TOP'
},
{ 'type': 'sensor.lidar.ray_cast_semantic',
'x': -0.39, 'y': 0.0, 'z': 1.84,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'range': 85,
'rotation_frequency': 10,
'channels': 64,
'points_per_second': 600000,
'id': 'LIDAR_TOP_SEG'
},
# imu
{
'type': 'sensor.other.imu',
'x': -1.4, 'y': 0.0, 'z': 0.0,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'sensor_tick': 0.05,
'id': 'IMU'
},
# gps
{
'type': 'sensor.other.gnss',
'x': -1.4, 'y': 0.0, 'z': 0.0,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'sensor_tick': 0.01,
'id': 'GPS'
},
# rader
{
'type': 'sensor.other.radar',
'x': 2.27, 'y': 0.0, 'z': 0.48,
'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,
'id': 'RADAR_FRONT'
},
{
'type': 'sensor.other.radar',
'x': 1.21, 'y': -0.85, 'z': 0.74,
'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,
'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,
'id': 'RADAR_FRONT_LEFT'
},
{
'type': 'sensor.other.radar',
'x': 1.21, 'y': 0.85, 'z': 0.74,
'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0,
'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,
'id': 'RADAR_FRONT_RIGHT'
},
{
'type': 'sensor.other.radar',
'x': -2.0, 'y': -0.67, 'z': 0.51,
'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,
'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,
'id': 'RADAR_BACK_LEFT'
},
{
'type': 'sensor.other.radar',
'x': -2.0, 'y': 0.67, 'z': 0.51,
'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0,
'range': 100, 'horizontal_fov': 30, 'vertical_fov': 30,
'id': 'RADAR_BACK_RIGHT'
},
# speed
{
'type': 'sensor.speedometer',
'reading_frequency': 20,
'id': 'SPEED'
},
### Debug sensor, not used by the model
{
'type': 'sensor.camera.rgb',
'x': 0.0, 'y': 0.0, 'z': 50.0,
'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0,
'width': 1600, 'height': 900, 'fov': 110,
'id': 'TOP_DOWN'
},
]
self.sensors_mapping = {}
for sensor in sensors:
self.sensors_mapping[sensor['id']] = sensor
return sensors
def _get_position(self, tick_data):
gps = tick_data['gps']
gps = (gps - self._command_planner.mean) * self._command_planner.scale
return gps
def get_target_gps(self, gps, compass):
# target gps
def gps_to_location(gps):
# gps content: numpy array: [lat, lon, alt]
lat, lon, z = gps
scale = math.cos(self.lat_ref * math.pi / 180.0)
my = math.log(math.tan((lat+90) * math.pi / 360.0)) * (EARTH_RADIUS_EQUA * scale)
mx = (lon * (math.pi * EARTH_RADIUS_EQUA * scale)) / 180.0
y = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + self.lat_ref) * math.pi / 360.0)) - my
x = mx - scale * self.lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0
z = float(z)
location = carla.Location(x=x, y=y, z=z)
return location
pass
global_plan_gps = self._global_plan[:]
next_gps, _ = global_plan_gps[min(self.navigation_idx+1, len(global_plan_gps)-1)]
next_gps = np.array([next_gps['lat'], next_gps['lon'], next_gps['z']])
next_vec_in_global = gps_to_location(next_gps) - gps_to_location(gps)
ref_rot_in_global = carla.Rotation(yaw=np.rad2deg(compass)-90.0)
loc_in_ev = vec_global_to_ref(next_vec_in_global, ref_rot_in_global)
if np.sqrt(loc_in_ev.x**2+loc_in_ev.y**2) < 12.0 and loc_in_ev.x < 0.0:
self.navigation_idx += 1
self.navigation_idx = min(self.navigation_idx, len(self._global_plan)-2)
_, road_option_0 = global_plan_gps[max(0, self.navigation_idx)]
gps_point, road_option_1 = global_plan_gps[self.navigation_idx+1]
gps_point = np.array([gps_point['lat'], gps_point['lon'], gps_point['z']])
if (road_option_0 in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]) \
and (road_option_1 not in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]):
road_option = road_option_1
else:
road_option = road_option_0
return np.array(gps_point, dtype=np.float32), np.array([road_option.value], dtype=np.int8)
def save(self, near_node, far_node, near_command, far_command, tick_data, should_brake):
frame = self.count
# CARLA images are already in opencv's BGR format.
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front_left' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front_left'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_front_right' / (f'{frame:05}.jpg')), tick_data['cam_bgr_front_right'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back_left' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back_left'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_back_right' / (f'{frame:05}.jpg')), tick_data['cam_bgr_back_right'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'rgb_top_down' / (f'{frame:05}.jpg')), tick_data['cam_bgr_top_down'], [cv2.IMWRITE_JPEG_QUALITY, 20])
cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front' / (f'{frame:05}.png')), tick_data['cam_front_sem_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front_left' / (f'{frame:05}.png')), tick_data['cam_front_left_sem_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'semantic_front_right' / (f'{frame:05}.png')), tick_data['cam_front_right_sem_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back' / (f'{frame:05}.png')), tick_data['cam_back_sem_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back_left' / (f'{frame:05}.png')), tick_data['cam_back_left_sem_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'semantic_back_right' / (f'{frame:05}.png')), tick_data['cam_back_right_sem_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'instance_front' / (f'{frame:05}.png')), tick_data['cam_front_ins_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'instance_front_left' / (f'{frame:05}.png')), tick_data['cam_front_left_ins_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'instance_front_right' / (f'{frame:05}.png')), tick_data['cam_front_right_ins_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'instance_back' / (f'{frame:05}.png')), tick_data['cam_back_ins_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'instance_back_left' / (f'{frame:05}.png')), tick_data['cam_back_left_ins_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'instance_back_right' / (f'{frame:05}.png')), tick_data['cam_back_right_ins_seg'])
cv2.imwrite(str(self.save_path / 'camera' / 'depth_front' / (f'{frame:05}.png')), tick_data['cam_gray_front_depth'])
cv2.imwrite(str(self.save_path / 'camera' / 'depth_front_left' / (f'{frame:05}.png')), tick_data['cam_gray_front_left_depth'])
cv2.imwrite(str(self.save_path / 'camera' / 'depth_front_right' / (f'{frame:05}.png')), tick_data['cam_gray_front_right_depth'])
cv2.imwrite(str(self.save_path / 'camera' / 'depth_back' / (f'{frame:05}.png')), tick_data['cam_gray_back_depth'])
cv2.imwrite(str(self.save_path / 'camera' / 'depth_back_left' / (f'{frame:05}.png')), tick_data['cam_gray_back_left_depth'])
cv2.imwrite(str(self.save_path / 'camera' / 'depth_back_right' / (f'{frame:05}.png')), tick_data['cam_gray_back_right_depth'])
with h5py.File(str(self.save_path / 'radar' / (f'{frame:05}.h5')), 'w') as f:
f.create_dataset('radar_front', data=tick_data['radar_front'], compression='gzip', compression_opts=9, chunks=True)
f.create_dataset('radar_front_left', data=tick_data['radar_front_left'], compression='gzip', compression_opts=9, chunks=True)
f.create_dataset('radar_front_right', data=tick_data['radar_front_right'], compression='gzip', compression_opts=9, chunks=True)
f.create_dataset('radar_back_left', data=tick_data['radar_back_left'], compression='gzip', compression_opts=9, chunks=True)
f.create_dataset('radar_back_right', data=tick_data['radar_back_right'], compression='gzip', compression_opts=9, chunks=True)
# Specialized LiDAR compression format
header = laspy.LasHeader(point_format=0) # LARS point format used for storing
header.offsets = np.min(tick_data['lidar'], axis=0)
point_precision = 0.001
header.scales = np.array([point_precision, point_precision, point_precision])
with laspy.open(self.save_path / 'lidar' / (f'{frame:05}.laz'), mode='w', header=header) as writer:
point_record = laspy.ScaleAwarePointRecord.zeros(tick_data['lidar'].shape[0], header=header)
point_record.x = tick_data['lidar'][:, 0]
point_record.y = tick_data['lidar'][:, 1]
point_record.z = tick_data['lidar'][:, 2]
writer.write_points(point_record)
anno_data = {
'x': tick_data['pos'][0],
'y': tick_data['pos'][1],
'throttle': tick_data['throttle'],
'steer': tick_data['steer'],
'brake': tick_data['brake'],
'reverse': tick_data['reverse'],
'theta': tick_data['compass'],
'speed': tick_data['speed'],
'x_command_far': far_node[0],
'y_command_far': far_node[1],
'command_far': far_command.value,
'x_command_near': near_node[0],
'y_command_near': near_node[1],
'command_near': near_command.value,
'should_brake': should_brake,
'x_target': tick_data['x_target'],
'y_target': tick_data['y_target'],
# 'target_command': tick_data['target_command'].tolist(),
# 'target_gps': tick_data['target_gps'].tolist(),
'next_command': tick_data['next_command'],
'weather': tick_data['weather'],
"acceleration":tick_data["acceleration"].tolist(),
"angular_velocity":tick_data["angular_velocity"].tolist(),
'bounding_boxes': tick_data['bounding_boxes'],
'sensors': tick_data['sensors_anno'],
'only_ap_brake': tick_data['only_ap_brake'],
}
with gzip.open(self.save_path / 'anno' / f'{frame:05}.json.gz', 'wt', encoding='utf-8') as f:
json.dump(anno_data, f, indent=4)
if self.count > -1:
np.savez(self.save_path / 'expert_assessment' / f'{frame-1:05}.npz', np.concatenate((self.feature, self.value, np.array([self.action_index], dtype=np.float32))))
# add feature (yzj)
def _point_inside_boundingbox(self, point, bb_center, bb_extent, multiplier=1.5):
A = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)
B = carla.Vector2D(bb_center.x + multiplier * bb_extent.x, bb_center.y - multiplier * bb_extent.y)
D = carla.Vector2D(bb_center.x - multiplier * bb_extent.x, bb_center.y + multiplier * bb_extent.y)
M = carla.Vector2D(point.x, point.y)
AB = B - A
AD = D - A
AM = M - A
am_ab = AM.x * AB.x + AM.y * AB.y
ab_ab = AB.x * AB.x + AB.y * AB.y
am_ad = AM.x * AD.x + AM.y * AD.y
ad_ad = AD.x * AD.x + AD.y * AD.y
return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad
def affected_by_traffic_light(self, traffic_light, center, window_size=50):
inx = min(window_size, len(CarlaDataProvider._ego_actor.route_plan))
if inx <= 1:
return False
for trans, _ in CarlaDataProvider._ego_actor.route_plan[:inx]:
if self._point_inside_boundingbox(trans.location, center, traffic_light.trigger_volume.extent):
return True
return False
def get_traffic_color(self, state):
if state == carla.libcarla.TrafficLightState.Green:
return 'green'
if state == carla.libcarla.TrafficLightState.Yellow:
return 'yellow'
if state == carla.libcarla.TrafficLightState.Red:
return 'red'
if state == carla.libcarla.TrafficLightState.Unknown:
return 'unknown'
if state == carla.libcarla.TrafficLightState.Off:
return 'off'
raise Exception(f"{state} not in Green, Yellow, Red, Unknown, Off")
def get_affect_sign(self, actors):
all_actors = []
affect_signs = []
mini_sign = DIS_SIGN_SAVE + 1
most_affect_sign = None
# find all lights
ego_vehicle_waypoint = CarlaDataProvider.get_map().get_waypoint(self.manager.ego_vehicles[0].get_location())
for sign in actors:
flag = 0
sign_loc = sign.get_location()
if compute_2d_distance(sign_loc, self.manager.ego_vehicles[0].get_transform().location) > DIS_SIGN_SAVE:
continue
all_actors.append(sign)
# find all affect lights
if hasattr(sign, 'trigger_volume'):
sign_vol_loc = sign.trigger_volume.location
sign_vol_loc_world = sign.get_transform().transform(sign_vol_loc)
sign_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(sign_vol_loc_world)
while not sign_vol_loc_world_wp.is_intersection:
if len(sign_vol_loc_world_wp.next(0.5)) > 0:
next_sign_vol_loc_world_wp = sign_vol_loc_world_wp.next(0.5)[0]
else:
flag = 1
break
if next_sign_vol_loc_world_wp and not next_sign_vol_loc_world_wp.is_intersection:
sign_vol_loc_world_wp = next_sign_vol_loc_world_wp
else:
break
if flag:
continue
if self.affected_by_traffic_light(sign, carla.Location(x=sign_vol_loc_world_wp.transform.location.x, y=sign_vol_loc_world_wp.transform.location.y, z=0)):
affect_signs.append(sign)
dis = np.abs(compute_2d_distance(ego_vehicle_waypoint.transform.location, sign.get_transform().transform(sign.trigger_volume.location)))
if dis < mini_sign:
most_affect_sign = sign
mini_sign = dis
else:
sign_vol_loc = sign.get_transform().location
sign_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(sign_vol_loc)
dis = compute_2d_distance(sign_vol_loc_world_wp.transform.location, ego_vehicle_waypoint.transform.location)
forward_vec = self.manager.ego_vehicles[0].get_transform().get_forward_vector()
ray = sign_vol_loc_world_wp.transform.location - self.manager.ego_vehicles[0].get_location()
if forward_vec.dot(ray) < 0:
continue
if dis < mini_sign:
most_affect_sign = sign
mini_sign = dis
return all_actors, most_affect_sign
def get_actor_filter_traffic_sign(self):
actor_data = EasyDict({})
speed_limit_sign = list(CarlaDataProvider.get_world().get_actors().filter("*traffic.speed_limit*")) # carla.libcarla.TrafficSign
stop_sign = list(CarlaDataProvider.get_world().get_actors().filter("*traffic.stop*")) # carla.libcarla.TrafficSign
yield_sign = list(CarlaDataProvider.get_world().get_actors().filter("*traffic.yield*")) # carla.libcarla.TrafficSign
warning = list(CarlaDataProvider.get_world().get_actors().filter('*warning*'))
dirtdebris = list(CarlaDataProvider.get_world().get_actors().filter('*dirtdebris*'))
cone = list(CarlaDataProvider.get_world().get_actors().filter('*cone*'))
actors = speed_limit_sign + stop_sign + yield_sign + warning + dirtdebris + cone
all_actors, most_affect_sign = self.get_affect_sign(actors)
actor_data.actors = all_actors
actor_data.most_affect_sign = most_affect_sign
return actor_data
def get_actor_filter_traffic_light(self):
actor_data = EasyDict({})
lights = CarlaDataProvider.get_world().get_actors().filter("*traffic_light*")
all_lights = []
affect_lights = []
most_affect_light = None
mini_lt = DIS_LIGHT_SAVE + 1
# find all lights
for lt in lights:
flag = 0
lt_loc = lt.get_location()
if compute_2d_distance(lt_loc, self.manager.ego_vehicles[0].get_location()) > DIS_LIGHT_SAVE: # lidar range
continue
all_lights.append(lt)
# find all affect lights
lt_vol_loc = lt.trigger_volume.location
lt_vol_loc_world = lt.get_transform().transform(lt_vol_loc)
lt_vol_loc_world_wp = CarlaDataProvider.get_map().get_waypoint(lt_vol_loc_world)
while not lt_vol_loc_world_wp.is_intersection:
if len(lt_vol_loc_world_wp.next(0.5)) > 0:
next_lt_vol_loc_world_wp = lt_vol_loc_world_wp.next(0.5)[0]
else:
flag = 1
break
if next_lt_vol_loc_world_wp and not next_lt_vol_loc_world_wp.is_intersection:
lt_vol_loc_world_wp = next_lt_vol_loc_world_wp
else:
break
if flag:
continue
if self.affected_by_traffic_light(lt, carla.Location(x=lt_vol_loc_world_wp.transform.location.x, y=lt_vol_loc_world_wp.transform.location.y, z=0)):
affect_lights.append(lt)
# find most affect light_actor, min_dis=DIS_LIGHT_SAVE
dis = np.abs(compute_2d_distance(lt.get_transform().transform(lt.trigger_volume.location), self.manager.ego_vehicles[0].get_location()))
forward_vec = self.manager.ego_vehicles[0].get_transform().get_forward_vector()
ray = lt.get_transform().transform(lt.trigger_volume.location) - self.manager.ego_vehicles[0].get_location()
if forward_vec.dot(ray) < 0:
continue
if dis < mini_lt:
most_affect_light = lt
mini_lt = dis
actor_data.lights = all_lights
actor_data.affect_lights = affect_lights
actor_data.most_affect_light = most_affect_light
# get distance
if most_affect_light is not None:
trigger_volume = most_affect_light.trigger_volume
box = trigger_volume.extent
loc = trigger_volume.location
ori = trigger_volume.rotation.get_forward_vector()
trigger_loc = [loc.x, loc.y, loc.z]
trigger_ori = [ori.x, ori.y, ori.z]
trigger_box = [box.x, box.y]
world_loc = most_affect_light.get_transform().transform(loc)
world_loc_wp = CarlaDataProvider.get_map().get_waypoint(world_loc)
while not world_loc_wp.is_intersection:
next_world_loc_wp = world_loc_wp.next(0.5)[0]
if next_world_loc_wp and not next_world_loc_wp.is_intersection:
world_loc_wp = next_world_loc_wp
else:
break
world_loc_wp = carla.Location(x=world_loc_wp.transform.location.x, y=world_loc_wp.transform.location.y, z=0)
pos = self.manager.ego_vehicles[0].get_location()
pos = carla.Location(x=pos.x, y=pos.y, z=0)
# ego2lane_dis = world_loc_wp.distance(pos)