Skip to content

Commit

Permalink
fix: on off detector and merger
Browse files Browse the repository at this point in the history
  • Loading branch information
technolojin committed Jun 17, 2024
1 parent 766ab06 commit 6234f40
Showing 1 changed file with 97 additions and 147 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,49 @@
<!-- Radar interfaces -->
<arg name="input/radar"/>

<!-- Camera-Lidar-Radar fusion based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_radar_fusion&quot;')">
<!-- Module switching -->
<arg name="switch/detector/camera_lidar" default="false"/>
<arg name="switch/detector/lidar_dnn" default="false"/>
<arg name="switch/detector/lidar_rule" default="false"/>
<arg name="switch/detector/radar" default="false"/>
<arg name="switch/detector/radar_only" default="false"/>
<arg name="switch/detector/tracker_based" default="false"/>
<let name="switch/detector/tracker_based" value="true" if="$(var use_detection_by_tracker)"/>

<arg name="switch/merger/camera_lidar_radar" default="false"/>
<arg name="switch/merger/camera_lidar" default="false"/>
<arg name="switch/merger/lidar_radar" default="false"/>
<arg name="switch/merger/lidar" default="false"/>

<group scoped="false" if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_radar_fusion&quot;')">
<let name="switch/detector/camera_lidar" value="true"/>
<let name="switch/detector/lidar_dnn" value="true"/>
<let name="switch/detector/radar" value="true"/>
<let name="switch/merger/camera_lidar_radar" value="true"/>
</group>
<group scoped="false" if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_fusion&quot;')">
<let name="switch/detector/camera_lidar" value="true"/>
<let name="switch/detector/lidar_dnn" value="true"/>
<let name="switch/merger/camera_lidar" value="true"/>
</group>
<group scoped="false" if="$(eval '&quot;$(var mode)&quot;==&quot;lidar_radar_fusion&quot;')">
<let name="switch/detector/lidar_dnn" value="true"/>
<let name="switch/detector/lidar_rule" value="true"/>
<let name="switch/detector/radar" value="true"/>
<let name="switch/merger/lidar_radar" value="true"/>
</group>
<group scoped="false" if="$(eval '&quot;$(var mode)&quot;==&quot;lidar&quot;')">
<let name="switch/detector/lidar_dnn" value="true"/>
<let name="switch/detector/lidar_rule" value="true"/>
<let name="switch/merger/lidar" value="true"/>
</group>
<group scoped="false" if="$(eval '&quot;$(var mode)&quot;==&quot;radar&quot;')">
<let name="switch/detector/radar_only" value="true"/>
<let name="switch/detector/tracker_based" value="false"/>
</group>

<!-- Detector -->
<group if="$(var switch/detector/camera_lidar)">
<!-- Camera-Lidar detectors -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml">
<arg name="number_of_cameras" value="$(var number_of_cameras)"/>
Expand Down Expand Up @@ -87,32 +128,60 @@
<arg name="detection_by_tracker_param_path" value="$(var detection_by_tracker_param_path)"/>
<arg name="use_low_intensity_cluster_filter" value="$(var use_low_intensity_cluster_filter)"/>
</include>
</group>
<group if="$(var switch/detector/lidar_dnn)">
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- Radar detector/filter-->
<group>
<push-ros-namespace namespace="radar"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/filter/radar_filter.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="far_objects"/>
<arg name="radar_lanelet_filtering_range_param_path" value="$(var radar_lanelet_filtering_range_param_path)"/>
<arg name="radar_crossing_objects_noise_filter_param_path" value="$(var object_recognition_detection_radar_crossing_objects_noise_filter_param_path)"/>
<arg name="object_velocity_splitter_param_path" value="$(var object_recognition_detection_object_velocity_splitter_radar_fusion_param_path)"/>
<arg name="object_range_splitter_param_path" value="$(var object_recognition_detection_object_range_splitter_radar_fusion_param_path)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
<!-- DetectionByTracker -->
<group if="$(var use_detection_by_tracker)">
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml">
<arg name="detection_by_tracker_param_path" value="$(var object_recognition_detection_detection_by_tracker_param)"/>
</include>
</group>
<!-- Object merger -->
</group>
<group if="$(var switch/detector/lidar_rule)">
<!-- Lidar rule-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml">
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="input/pointcloud_map/pointcloud" value="$(var input/pointcloud_map/pointcloud)"/>
<arg name="input/obstacle_segmentation/pointcloud" value="$(var input/obstacle_segmentation/pointcloud)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
</include>
</group>
<group if="$(var switch/detector/radar)">
<!-- Radar detector/filter, in case of sensor fusion-->
<push-ros-namespace namespace="radar"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/filter/radar_filter.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="far_objects"/>
<arg name="radar_lanelet_filtering_range_param_path" value="$(var radar_lanelet_filtering_range_param_path)"/>
<arg name="radar_crossing_objects_noise_filter_param_path" value="$(var object_recognition_detection_radar_crossing_objects_noise_filter_param_path)"/>
<arg name="object_velocity_splitter_param_path" value="$(var object_recognition_detection_object_velocity_splitter_radar_fusion_param_path)"/>
<arg name="object_range_splitter_param_path" value="$(var object_recognition_detection_object_range_splitter_radar_fusion_param_path)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
<group if="$(var switch/detector/radar_only)">
<!-- Radar detector/filter, in case of radar only -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/filter/radar_filter.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="objects"/>
<arg name="radar_lanelet_filtering_range_param_path" value="$(var radar_lanelet_filtering_range_param_path)"/>
<arg name="radar_crossing_objects_noise_filter_param_path" value="$(var object_recognition_detection_radar_crossing_objects_noise_filter_param_path)"/>
<arg name="object_velocity_splitter_param_path" value="$(var object_recognition_detection_object_velocity_splitter_radar_param_path)"/>
<arg name="object_range_splitter_param_path" value="$(var object_recognition_detection_object_range_splitter_radar_param_path)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
<!-- DetectionByTracker -->
<group if="$(var switch/detector/tracker_based)">
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml">
<arg name="detection_by_tracker_param_path" value="$(var object_recognition_detection_detection_by_tracker_param)"/>
</include>
</group>

<!-- Merger -->
<group if="$(var switch/merger/camera_lidar_radar)">
<!-- Camera-Lidar-Radar merger -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml">
<arg name="number_of_cameras" value="$(var number_of_cameras)"/>
<arg name="input/camera0/image" value="$(var input/camera0/image)"/>
Expand Down Expand Up @@ -153,58 +222,8 @@
</include>
</group>

<!-- Camera-Lidar fusion based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_fusion&quot;')">
<!-- Camera-Lidar detectors -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml">
<arg name="number_of_cameras" value="$(var number_of_cameras)"/>
<arg name="input/camera0/image" value="$(var input/camera0/image)"/>
<arg name="input/camera0/info" value="$(var input/camera0/info)"/>
<arg name="input/camera0/rois" value="$(var input/camera0/rois)"/>
<arg name="input/camera1/image" value="$(var input/camera1/image)"/>
<arg name="input/camera1/info" value="$(var input/camera1/info)"/>
<arg name="input/camera1/rois" value="$(var input/camera1/rois)"/>
<arg name="input/camera2/image" value="$(var input/camera2/image)"/>
<arg name="input/camera2/info" value="$(var input/camera2/info)"/>
<arg name="input/camera2/rois" value="$(var input/camera2/rois)"/>
<arg name="input/camera3/image" value="$(var input/camera3/image)"/>
<arg name="input/camera3/info" value="$(var input/camera3/info)"/>
<arg name="input/camera3/rois" value="$(var input/camera3/rois)"/>
<arg name="input/camera4/image" value="$(var input/camera4/image)"/>
<arg name="input/camera4/info" value="$(var input/camera4/info)"/>
<arg name="input/camera4/rois" value="$(var input/camera4/rois)"/>
<arg name="input/camera5/image" value="$(var input/camera5/image)"/>
<arg name="input/camera5/info" value="$(var input/camera5/info)"/>
<arg name="input/camera5/rois" value="$(var input/camera5/rois)"/>
<arg name="input/camera6/image" value="$(var input/camera6/image)"/>
<arg name="input/camera6/info" value="$(var input/camera6/info)"/>
<arg name="input/camera6/rois" value="$(var input/camera6/rois)"/>
<arg name="input/camera7/image" value="$(var input/camera7/image)"/>
<arg name="input/camera7/info" value="$(var input/camera7/info)"/>
<arg name="input/camera7/rois" value="$(var input/camera7/rois)"/>
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="input/pointcloud_map/pointcloud" value="$(var input/pointcloud_map/pointcloud)"/>
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
<arg name="use_roi_based_cluster" value="$(var use_roi_based_cluster)"/>
<arg name="detection_by_tracker_param_path" value="$(var detection_by_tracker_param_path)"/>
<arg name="use_low_intensity_cluster_filter" value="$(var use_low_intensity_cluster_filter)"/>
</include>
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- DetectionByTracker -->
<group if="$(var use_detection_by_tracker)">
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml">
<arg name="detection_by_tracker_param_path" value="$(var object_recognition_detection_detection_by_tracker_param)"/>
</include>
</group>
<!-- Object merger -->
<group if="$(var switch/merger/camera_lidar)">
<!-- Camera-Lidar merger -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml">
<arg name="number_of_cameras" value="$(var number_of_cameras)"/>
<arg name="input/camera0/image" value="$(var input/camera0/image)"/>
Expand Down Expand Up @@ -243,42 +262,8 @@
</include>
</group>

<!-- Lidar-Radar fusion based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;lidar_radar_fusion&quot;')">
<!-- Radar detector/filter-->
<group>
<push-ros-namespace namespace="radar"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/filter/radar_filter.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="far_objects"/>
<arg name="radar_lanelet_filtering_range_param_path" value="$(var radar_lanelet_filtering_range_param_path)"/>
<arg name="radar_crossing_objects_noise_filter_param_path" value="$(var object_recognition_detection_radar_crossing_objects_noise_filter_param_path)"/>
<arg name="object_velocity_splitter_param_path" value="$(var object_recognition_detection_object_velocity_splitter_radar_fusion_param_path)"/>
<arg name="object_range_splitter_param_path" value="$(var object_recognition_detection_object_range_splitter_radar_fusion_param_path)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- Lidar rule-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml">
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="input/pointcloud_map/pointcloud" value="$(var input/pointcloud_map/pointcloud)"/>
<arg name="input/obstacle_segmentation/pointcloud" value="$(var input/obstacle_segmentation/pointcloud)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
</include>
<!-- DetectionByTracker -->
<group if="$(var use_detection_by_tracker)">
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml">
<arg name="detection_by_tracker_param_path" value="$(var object_recognition_detection_detection_by_tracker_param)"/>
</include>
</group>
<!-- Lidar object merger -->
<group if="$(var switch/merger/lidar_radar)">
<!-- Lidar object merger-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/lidar_merger.launch.xml">
<arg name="input/pointcloud_map/pointcloud" value="$(var input/pointcloud_map/pointcloud)"/>
<arg name="input/obstacle_segmentation/pointcloud" value="$(var input/obstacle_segmentation/pointcloud)"/>
Expand All @@ -299,29 +284,8 @@
</include>
</group>

<!-- Lidar based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;lidar&quot;')">
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- Lidar rule-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml">
<arg name="node/pointcloud_container" value="$(var node/pointcloud_container)"/>
<arg name="input/pointcloud_map/pointcloud" value="$(var input/pointcloud_map/pointcloud)"/>
<arg name="input/obstacle_segmentation/pointcloud" value="$(var input/obstacle_segmentation/pointcloud)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
</include>
<!-- DetectionByTracker -->
<group if="$(var use_detection_by_tracker)">
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml">
<arg name="detection_by_tracker_param_path" value="$(var object_recognition_detection_detection_by_tracker_param)"/>
</include>
</group>
<!-- Lidar object merger -->
<group if="$(var switch/merger/lidar)">
<!-- Lidar object merger-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/lidar_merger.launch.xml">
<arg name="input/pointcloud_map/pointcloud" value="$(var input/pointcloud_map/pointcloud)"/>
<arg name="input/obstacle_segmentation/pointcloud" value="$(var input/obstacle_segmentation/pointcloud)"/>
Expand All @@ -335,18 +299,4 @@
<arg name="objects_validation_method" value="$(var objects_validation_method)"/>
</include>
</group>

<!-- Radar based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;radar&quot;')">
<!-- Radar detector/filter-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/filter/radar_filter.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="objects"/>
<arg name="radar_lanelet_filtering_range_param_path" value="$(var radar_lanelet_filtering_range_param_path)"/>
<arg name="radar_crossing_objects_noise_filter_param_path" value="$(var object_recognition_detection_radar_crossing_objects_noise_filter_param_path)"/>
<arg name="object_velocity_splitter_param_path" value="$(var object_recognition_detection_object_velocity_splitter_radar_param_path)"/>
<arg name="object_range_splitter_param_path" value="$(var object_recognition_detection_object_range_splitter_radar_param_path)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
</launch>

0 comments on commit 6234f40

Please sign in to comment.