From 959d59f7b798e5ab75f0124e420f6fd4fed2752f Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Mon, 22 Jul 2024 19:20:15 +0900 Subject: [PATCH] fix: resolve `yolox_tiny` to work Signed-off-by: ktro2828 --- .../config/yolox_tiny.param.yaml | 24 +++++++++++++++++++ .../launch/yolox_tiny.launch.xml | 4 +++- 2 files changed, 27 insertions(+), 1 deletion(-) diff --git a/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml b/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml index 051aa22f52d7d..e1ece63a4940f 100644 --- a/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml +++ b/perception/autoware_tensorrt_yolox/config/yolox_tiny.param.yaml @@ -1,9 +1,33 @@ +# cspell:ignore semseg /**: ros__parameters: + + # refine segmentation mask by overlay roi class + # disable when sematic segmentation accuracy is good enough + is_roi_overlap_segment: true + + # minimum existence_probability of detected roi considered to replace segmentation + overlap_roi_score_threshold: 0.3 + + # publish color mask for result visualization + is_publish_color_mask: false + + roi_overlay_segment_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + MOTORCYCLE : true + BICYCLE : true + PEDESTRIAN : true + ANIMAL: true + model_path: "$(var data_path)/tensorrt_yolox/$(var model_name).onnx" # The onnx file name for YOLOX model. label_path: "$(var data_path)/tensorrt_yolox/label.txt" # The label file path for YOLOX model. + color_map_path: "$(var data_path)/tensorrt_yolox/semseg_color_map.csv" score_threshold: 0.35 # Objects with a score lower than this value will be ignored. This threshold will be ignored if specified model contains EfficientNMS_TRT module in it. nms_threshold: 0.7 # Detection results will be ignored if IoU over this value. This threshold will be ignored if specified model contains EfficientNMS_TRT module in it. + precision: "fp16" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8]. calibration_algorithm: "MinMax" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]. dla_core_id: -1 # If positive ID value is specified, the node assign inference task to the DLA core. diff --git a/perception/autoware_tensorrt_yolox/launch/yolox_tiny.launch.xml b/perception/autoware_tensorrt_yolox/launch/yolox_tiny.launch.xml index 28637e7353e22..dc6ebc2edeebb 100644 --- a/perception/autoware_tensorrt_yolox/launch/yolox_tiny.launch.xml +++ b/perception/autoware_tensorrt_yolox/launch/yolox_tiny.launch.xml @@ -4,13 +4,15 @@ - + + +