diff --git a/edge_auto_jetson_launch/config/bytetrack.param.yaml b/edge_auto_jetson_launch/config/bytetrack.param.yaml new file mode 100644 index 0000000..e38dbdb --- /dev/null +++ b/edge_auto_jetson_launch/config/bytetrack.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + track_buffer_length: 30 diff --git a/edge_auto_jetson_launch/config/bytetrack_visualizer.param.yaml b/edge_auto_jetson_launch/config/bytetrack_visualizer.param.yaml new file mode 100644 index 0000000..960fa34 --- /dev/null +++ b/edge_auto_jetson_launch/config/bytetrack_visualizer.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + use_raw: true diff --git a/edge_auto_jetson_launch/config/yolox_tiny.param.yaml b/edge_auto_jetson_launch/config/yolox_tiny.param.yaml new file mode 100644 index 0000000..e1ece63 --- /dev/null +++ b/edge_auto_jetson_launch/config/yolox_tiny.param.yaml @@ -0,0 +1,39 @@ +# 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. + quantize_first_layer: false # If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8. + quantize_last_layer: false # If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8. + profile_per_layer: false # If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose. + clip_value: 0.0 # If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration. + preprocess_on_gpu: true # If true, pre-processing is performed on GPU. + calibration_image_list_path: "" # Path to a file which contains path to images. Those images will be used for int8 quantization. diff --git a/edge_auto_jetson_launch/launch/bytetrack.launch.xml b/edge_auto_jetson_launch/launch/bytetrack.launch.xml index ad18d16..d5875e0 100755 --- a/edge_auto_jetson_launch/launch/bytetrack.launch.xml +++ b/edge_auto_jetson_launch/launch/bytetrack.launch.xml @@ -1,60 +1,25 @@ - - - - - - - - - - - - - - + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - + + + + + diff --git a/edge_auto_jetson_launch/launch/perception_jetson0.launch.xml b/edge_auto_jetson_launch/launch/perception_jetson0.launch.xml index beb904f..64e8409 100644 --- a/edge_auto_jetson_launch/launch/perception_jetson0.launch.xml +++ b/edge_auto_jetson_launch/launch/perception_jetson0.launch.xml @@ -44,6 +44,7 @@ + @@ -52,6 +53,7 @@ + @@ -95,12 +97,14 @@ + + diff --git a/edge_auto_jetson_launch/launch/tensorrt_yolox.launch.xml b/edge_auto_jetson_launch/launch/tensorrt_yolox.launch.xml index 0f0f344..5ec70a8 100644 --- a/edge_auto_jetson_launch/launch/tensorrt_yolox.launch.xml +++ b/edge_auto_jetson_launch/launch/tensorrt_yolox.launch.xml @@ -1,93 +1,19 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + diff --git a/edge_auto_jetson_launch/package.xml b/edge_auto_jetson_launch/package.xml index 134b498..82f46e1 100644 --- a/edge_auto_jetson_launch/package.xml +++ b/edge_auto_jetson_launch/package.xml @@ -15,10 +15,10 @@ image_view image_transport_plugins individual_params - tensorrt_yolox - bytetrack + autoware_tensorrt_yolox + autoware_bytetrack intrinsic_camera_calibrator - image_transport_decompressor + autoware_image_transport_decompressor ament_lint_auto ament_lint_common