|
| 1 | +<?xml version="1.0"?> |
| 2 | +<launch> |
| 3 | + <group> |
| 4 | + <!-- add namespace --> |
| 5 | + <arg name="namespace" default="camera6"/> |
| 6 | + <arg name="input/image" default="/sensing/camera/$(var namespace)/image_raw"/> |
| 7 | + <arg name="yolox_detected_traffic/rois" default="/perception/traffic_light_recognition/$(var namespace)/detection/yolox/rois"/> |
| 8 | + <arg |
| 9 | + name="model_name" |
| 10 | + default="tlr_car_ped_yolox_s_960_960_batch_1" |
| 11 | + description="options `yolox-sPlus-T4-960x960-pseudo-finetune` if only detection is needed, `yolox-sPlus-opt-pseudoV2-T4-960x960-T4-seg16cls` if sematic segmentation is also needed" |
| 12 | + /> |
| 13 | + <arg name="use_decompress" default="true" description="use image decompress"/> |
| 14 | + <arg name="build_only" default="false" description="exit after trt engine is built"/> |
| 15 | + |
| 16 | + <arg name="param_file" default="$(find-pkg-share autoware_image_transport_decompressor)/config/image_transport_decompressor.param.yaml"/> |
| 17 | + <node pkg="autoware_image_transport_decompressor" exec="image_transport_decompressor_node" name="image_transport_decompressor_$(var namespace)_node" if="$(var use_decompress)"> |
| 18 | + <remap from="~/input/compressed_image" to="$(var input/image)/compressed"/> |
| 19 | + <remap from="~/output/raw_image" to="$(var input/image)"/> |
| 20 | + <param from="$(var param_file)"/> |
| 21 | + </node> |
| 22 | + |
| 23 | + <node pkg="autoware_tensorrt_yolox" exec="autoware_tensorrt_yolox_node_exe" name="traffic_light_yolox_$(var namespace)" output="screen"> |
| 24 | + <remap from="~/in/image" to="$(var input/image)"/> |
| 25 | + <remap from="~/out/objects" to="$(var yolox_detected_traffic/rois)"/> |
| 26 | + <param name="build_only" value="$(var build_only)"/> |
| 27 | + <param name="is_roi_overlap_segment" value="false"/> |
| 28 | + <param name="overlap_roi_score_threshold" value="0.3"/> |
| 29 | + <param name="is_publish_color_mask" value="false"/> |
| 30 | + <param name="roi_overlay_segment_label.UNKNOWN" value="false"/> |
| 31 | + <param name="roi_overlay_segment_label.CAR" value="false"/> |
| 32 | + <param name="roi_overlay_segment_label.TRUCK" value="false"/> |
| 33 | + <param name="roi_overlay_segment_label.BUS" value="false"/> |
| 34 | + <param name="roi_overlay_segment_label.MOTORCYCLE" value="false"/> |
| 35 | + <param name="roi_overlay_segment_label.BICYCLE" value="false"/> |
| 36 | + <param name="roi_overlay_segment_label.PEDESTRIAN" value="false"/> |
| 37 | + <param name="roi_overlay_segment_label.ANIMAL" value="false"/> |
| 38 | + <param name="model_path" value="/opt/autoware/mlmodels/traffic_light_detector/$(var model_name).onnx"/> |
| 39 | + <param name="label_path" value="/opt/autoware/mlmodels/traffic_light_detector/label.txt"/> |
| 40 | + <param name="color_map_path" value=""/> |
| 41 | + <param name="score_threshold" value="0.35"/> |
| 42 | + <param name="nms_threshold" value="0.7"/> |
| 43 | + <param name="precision" value="fp16"/> |
| 44 | + <param name="calibration_algorithm" value="Entropy"/> |
| 45 | + <param name="dla_core_id" value="-1"/> |
| 46 | + <param name="quantize_first_layer" value="false"/> |
| 47 | + <param name="quantize_last_layer" value="false"/> |
| 48 | + <param name="profile_per_layer" value="false"/> |
| 49 | + <param name="clip_value" value="6.0"/> |
| 50 | + <param name="preprocess_on_gpu" value="true"/> |
| 51 | + <param name="gpu_id" value="0"/> |
| 52 | + <param name="calibration_image_list_path" value=""/> |
| 53 | + </node> |
| 54 | + <arg name="input/detected_rois" default="input/detected_rois"/> |
| 55 | + <arg name="input/rough_rois" default="/perception/traffic_light_recognition/$(var namespace)/detection/rough/rois"/> |
| 56 | + <arg name="output/traffic_light_rois" default="/perception/traffic_light_recognition/$(var namespace)/detection/rois"/> |
| 57 | + <arg name="input/expect_rois" default="/perception/traffic_light_recognition/$(var namespace)/detection/expect/rois"/> |
| 58 | + <arg name="input/camera_info" default="/sensing/camera/$(var namespace)/camera_info"/> |
| 59 | + <!-- Node --> |
| 60 | + <node pkg="autoware_traffic_light_selector" exec="traffic_light_selector_node" name="autoware_traffic_light_selector_$(var namespace)" output="screen"> |
| 61 | + <remap from="input/detected_rois" to="$(var yolox_detected_traffic/rois)"/> |
| 62 | + <remap from="input/rough_rois" to="$(var input/rough_rois)"/> |
| 63 | + <remap from="input/expect_rois" to="$(var input/expect_rois)"/> |
| 64 | + <remap from="output/traffic_light_rois" to="$(var output/traffic_light_rois)"/> |
| 65 | + <remap from="input/camera_info" to="$(var input/camera_info)"/> |
| 66 | + <param name="max_iou_threshold" value="0.0"/> |
| 67 | + <param name="debug" value="true"/> |
| 68 | + </node> |
| 69 | + </group> |
| 70 | +</launch> |
0 commit comments