forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 32
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
fix(multi_object_tracker): data association parameter (#541)
* sort matrix Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> * ANIMAL->TRAILER Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> * apply change to another file Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp> * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
- Loading branch information
1 parent
2b9c61d
commit 1e83f76
Showing
2 changed files
with
112 additions
and
108 deletions.
There are no files selected for viewing
110 changes: 56 additions & 54 deletions
110
...onfig/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,62 +1,64 @@ | ||
/**: | ||
ros__parameters: | ||
can_assign_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN | ||
1, 1, 1, 1, 0, 0, 0, 0, #CAR | ||
1, 1, 1, 1, 0, 0, 0, 0, #TRUCK | ||
1, 1, 1, 1, 0, 0, 0, 0, #BUS | ||
0, 0, 0, 0, 1, 1, 1, 0, #BICYCLE | ||
0, 0, 0, 0, 1, 1, 1, 0, #MOTORBIKE | ||
0, 0, 0, 0, 1, 1, 1, 0, #PEDESTRIAN | ||
0, 0, 0, 0, 0, 0, 0, 1] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE PEDESTRIAN | ||
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN | ||
1, 1, 1, 1, 1, 0, 0, 0, #CAR | ||
1, 1, 1, 1, 1, 0, 0, 0, #TRUCK | ||
1, 1, 1, 1, 1, 0, 0, 0, #BUS | ||
1, 1, 1, 1, 1, 0, 0, 0, #TRAILER | ||
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE | ||
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE | ||
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN | ||
|
||
max_dist_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN | ||
4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #CAR | ||
4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #TRUCK | ||
4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #BUS | ||
3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #BICYCLE | ||
3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #MOTORBIKE | ||
2.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #PEDESTRIAN | ||
1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER | ||
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE | ||
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE | ||
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN | ||
max_area_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN | ||
12.10, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #CAR | ||
19.75, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #TRUCK | ||
32.40, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #BUS | ||
2.50, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #BICYCLE | ||
3.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #MOTORBIKE | ||
2.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00, 10000.00, #PEDESTRIAN | ||
2.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN | ||
12.10, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #CAR | ||
19.75, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRUCK | ||
32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #BUS | ||
32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRAILER | ||
3.00, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE | ||
2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE | ||
2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN | ||
min_area_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN | ||
3.600, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #CAR | ||
6.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #TRUCK | ||
10.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #BUS | ||
0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #BICYCLE | ||
0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #MOTORBIKE | ||
0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #PEDESTRIAN | ||
0.500, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN | ||
3.600, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #CAR | ||
6.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRUCK | ||
10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #BUS | ||
10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRAILER | ||
0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #MOTORBIKE | ||
0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #BICYCLE | ||
0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100] #PEDESTRIAN | ||
max_rad_matrix: # If value is greater than pi, it will be ignored. | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN | ||
3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #CAR | ||
3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #TRUCK | ||
3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #BUS | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #PEDESTRIAN | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN | ||
|
||
min_iou_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN | ||
0.1, 0.3, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1, #CAR | ||
0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #TRUCK | ||
0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #BUS | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #PEDESTRIAN | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN | ||
0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR | ||
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK | ||
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS | ||
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN |
110 changes: 56 additions & 54 deletions
110
perception/multi_object_tracker/config/data_association_matrix.param.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,62 +1,64 @@ | ||
/**: | ||
ros__parameters: | ||
can_assign_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN | ||
1, 1, 1, 1, 0, 0, 0, 0, #CAR | ||
1, 1, 1, 1, 0, 0, 0, 0, #TRUCK | ||
1, 1, 1, 1, 0, 0, 0, 0, #BUS | ||
0, 0, 0, 0, 1, 1, 1, 0, #BICYCLE | ||
0, 0, 0, 0, 1, 1, 1, 0, #MOTORBIKE | ||
0, 0, 0, 0, 1, 1, 1, 0, #PEDESTRIAN | ||
0, 0, 0, 0, 0, 0, 0, 1] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE PEDESTRIAN | ||
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN | ||
1, 1, 1, 1, 1, 0, 0, 0, #CAR | ||
1, 1, 1, 1, 1, 0, 0, 0, #TRUCK | ||
1, 1, 1, 1, 1, 0, 0, 0, #BUS | ||
1, 1, 1, 1, 1, 0, 0, 0, #TRAILER | ||
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE | ||
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE | ||
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN | ||
|
||
max_dist_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN | ||
4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #CAR | ||
4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #TRUCK | ||
4.0, 2.0, 5.0, 5.0, 1.0, 1.0, 1.0, 1.0, #BUS | ||
3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #BICYCLE | ||
3.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #MOTORBIKE | ||
2.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 1.0, #PEDESTRIAN | ||
1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS | ||
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER | ||
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE | ||
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE | ||
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN | ||
max_area_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN | ||
12.10, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #CAR | ||
19.75, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #TRUCK | ||
32.40, 12.10, 19.75, 32.40, 10000.00, 10000.00, 10000.00, 10000.00, #BUS | ||
2.50, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #BICYCLE | ||
3.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, 10000.00, #MOTORBIKE | ||
2.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00, 10000.00, #PEDESTRIAN | ||
2.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, 10000.00, #UNKNOWN | ||
12.10, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #CAR | ||
19.75, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRUCK | ||
32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #BUS | ||
32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRAILER | ||
3.00, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE | ||
2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE | ||
2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN | ||
min_area_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN | ||
3.600, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #CAR | ||
6.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #TRUCK | ||
10.000, 3.600, 6.000, 10.000, 0.000, 0.000, 0.000, 0.000, #BUS | ||
0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #BICYCLE | ||
0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #MOTORBIKE | ||
0.001, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, 0.000, #PEDESTRIAN | ||
0.500, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN | ||
3.600, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #CAR | ||
6.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRUCK | ||
10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #BUS | ||
10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRAILER | ||
0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #MOTORBIKE | ||
0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #BICYCLE | ||
0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100] #PEDESTRIAN | ||
max_rad_matrix: # If value is greater than pi, it will be ignored. | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN | ||
3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #CAR | ||
3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #TRUCK | ||
3.150, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, 3.150, #BUS | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #PEDESTRIAN | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS | ||
3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE | ||
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN | ||
|
||
min_iou_matrix: | ||
#UNKNOWN, CAR, TRUCK, BUS, BICYCLE, MOTORBIKE, PEDESTRIAN, ANIMAL | ||
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN | ||
0.1, 0.3, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1, #CAR | ||
0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #TRUCK | ||
0.1, 0.2, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, #BUS | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #PEDESTRIAN | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #ANIMAL | ||
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN | ||
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN | ||
0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR | ||
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK | ||
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS | ||
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE | ||
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] #PEDESTRIAN |