Skip to content

Commit

Permalink
add centerpoint params
Browse files Browse the repository at this point in the history
Signed-off-by: ismetatabay <ismet@leodrive.ai>
  • Loading branch information
ismetatabay committed Jul 17, 2023
1 parent 154ac27 commit dd796bc
Show file tree
Hide file tree
Showing 5 changed files with 70 additions and 2 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
point_feature_size: 4
max_voxel_size: 40000
point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0]
voxel_size: [0.32, 0.32, 10.0]
downsample_factor: 1
encoder_in_feature_size: 9
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
point_feature_size: 4
max_voxel_size: 40000
point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0]
voxel_size: [0.32, 0.32, 10.0]
downsample_factor: 2
encoder_in_feature_size: 9
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/**:
ros__parameters:
allow_remapping_by_area_matrix:
# NOTE(kl): We turn all vehicles into trailers if they go over 3x12 [m^2].
# NOTE(kl): We turn cars into trucks if they have an area between 2.2 x 5.5 and 3.0 * 12.0 [m^2]
# row: original class. column: class to remap to
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 0, 1, 0, 1, 0, 0, 0, #CAR
0, 0, 0, 0, 1, 0, 0, 0, #TRUCK
0, 0, 0, 0, 1, 0, 0, 0, #BUS
0, 0, 0, 0, 0, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 0, 0, 0, #MOTORBIKE
0, 0, 0, 0, 0, 0, 0, 0, #BICYCLE
0, 0, 0, 0, 0, 0, 0, 0] #PEDESTRIAN

min_area_matrix:
#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
0.000, 0.000, 12.100, 0.000, 36.000, 0.000, 0.000, 0.000, #CAR
0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #TRUCK
0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #BUS
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN


max_area_matrix:
#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
0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml"
/>
<arg
name="object_recognition_detection_pointpainting_model_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/image_projection_based_fusion/pointpainting.param.yaml"
name="object_recognition_detection_lidar_model_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/lidar_model"
/>
<arg
name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"
Expand Down

0 comments on commit dd796bc

Please sign in to comment.