Skip to content

Commit

Permalink
feat: sync awf perception launch (autowarefoundation#358)
Browse files Browse the repository at this point in the history
* feat: sync awf perception launch

Signed-off-by: Yukihiro Saito <yukky.saito@gmail.com>

* bug fix

Signed-off-by: Yukihiro Saito <yukky.saito@gmail.com>
  • Loading branch information
yukkysaito authored Jun 23, 2022
1 parent 003edde commit 918855a
Show file tree
Hide file tree
Showing 3 changed files with 77 additions and 56 deletions.
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
/**:
ros__parameters:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
1, 1, 1, 1, 1, 0, 0, 0, #CAR
1, 1, 1, 1, 1, 0, 0, 0, #TRUCK
1, 1, 1, 1, 1, 0, 0, 0, #BUS
1, 1, 1, 1, 1, 0, 0, 0, #TRAILER
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN <-Measurement
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN <-Tracker
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
0, 1, 1, 1, 1, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE
0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE
0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN

max_dist_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN
[4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK
4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS
Expand All @@ -28,7 +28,7 @@
19.75, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRUCK
32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #BUS
32.40, 12.10, 19.75, 32.40, 32.40, 10000.00, 10000.00, 10000.00, #TRAILER
3.00, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE
2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE
2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE
2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN
min_area_matrix:
Expand All @@ -52,13 +52,13 @@
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE
3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN

min_iou_matrix:
min_iou_matrix: # If value is negative, it will be ignored.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN
0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN
[0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN
0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS
0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE
0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="input/pointcloud" />
<arg name="input/pointcloud"/>
<arg name="input/obstacle_segmentation/pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>
<arg name="image_raw0" default="/image_raw" description="image raw topic name"/>
<arg name="camera_info0" default="/camera_info" description="camera info topic name"/>
Expand Down Expand Up @@ -38,13 +38,14 @@
<!-- Pointcloud map filter -->
<group>
<include file="$(find-pkg-share compare_map_segmentation)/launch/voxel_based_compare_map_filter.launch.xml" if="$(var use_pointcloud_map)">
<arg name="input" value="$(var input/obstacle_segmentation/pointcloud)" />
<arg name="input_map" value="/map/pointcloud_map" />
<arg name="output" value="pointcloud_map_filtered/pointcloud" />
<arg name="distance_threshold" value="0.5" />
<arg name="input" value="$(var input/obstacle_segmentation/pointcloud)"/>
<arg name="input_map" value="/map/pointcloud_map"/>
<arg name="output" value="pointcloud_map_filtered/pointcloud"/>
<arg name="distance_threshold" value="0.5"/>
</include>
</group>

<!-- Clustering -->
<group>
<push-ros-namespace namespace="clustering"/>
<let name="clustering/input/pointcloud" value="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud" if="$(var use_pointcloud_map)"/>
Expand All @@ -54,6 +55,16 @@
<arg name="output_clusters" value="clusters"/>
<arg name="use_pointcloud_map" value="false"/>
</include>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="input/objects" value="clusters"/>
<arg name="output/objects" value="objects_with_feature"/>
</include>
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
<arg name="input" value="objects_with_feature"/>
<arg name="output" value="objects"/>
</include>
<!-- Fusion camera-lidar to classify -->
<include file="$(find-pkg-share image_projection_based_fusion)/launch/roi_cluster_fusion.launch.xml">
<arg name="input/camera_info0" value="$(var camera_info0)"/>
<arg name="input/rois0" value="/perception/object_recognition/detection/rois0"/>
Expand Down Expand Up @@ -84,13 +95,13 @@
<arg name="output/clusters" value="camera_lidar_fusion/clusters"/>
</include>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="input/objects" value="camera_lidar_fusion/clusters" />
<arg name="output/objects" value="camera_lidar_fusion/objects_with_feature" />
<arg name="input/objects" value="camera_lidar_fusion/clusters"/>
<arg name="output/objects" value="camera_lidar_fusion/objects_with_feature"/>
</include>
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
<arg name="input" value="camera_lidar_fusion/objects_with_feature" />
<arg name="output" value="camera_lidar_fusion/objects" />
<arg name="input" value="camera_lidar_fusion/objects_with_feature"/>
<arg name="output" value="camera_lidar_fusion/objects"/>
</include>
<include file="$(find-pkg-share object_range_splitter)/launch/object_range_splitter.launch.xml">
<arg name="input/object" value="camera_lidar_fusion/objects"/>
Expand All @@ -103,16 +114,15 @@
<!-- DetectionByTracker -->
<group>
<push-ros-namespace namespace="detection_by_tracker"/>
<include file="$(find-pkg-share detection_by_tracker)/launch/detection_by_tracker.launch.xml">
</include>
<include file="$(find-pkg-share detection_by_tracker)/launch/detection_by_tracker.launch.xml"/>
</group>

<!-- CenterPoint -->
<group if="$(eval &quot;'$(var lidar_detection_model)'=='centerpoint'&quot;)">
<push-ros-namespace namespace="centerpoint"/>
<include file="$(find-pkg-share lidar_centerpoint)/launch/lidar_centerpoint.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="output/objects" value="objects" />
<arg name="output/objects" value="objects"/>
</include>
</group>

Expand All @@ -129,8 +139,8 @@
</include>
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
<arg name="input" value="objects_with_feature" />
<arg name="output" value="objects" />
<arg name="input" value="objects_with_feature"/>
<arg name="output" value="objects"/>
</include>
</group>
</group>
Expand All @@ -147,20 +157,19 @@
</group>

<!-- Merger -->
<group>
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="$(var lidar_detection_model)/validation/objects"/>
<arg name="input/object1" value="clustering/camera_lidar_fusion/short_range_objects"/>
<arg name="output/object" value="camera_lidar_fusion/objects"/>
</include>
</group>

<group>
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="detection_by_tracker/objects"/>
<arg name="input/object1" value="camera_lidar_fusion/objects"/>
<arg name="output/object" value="objects"/>
</include>
</group>

<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="$(var lidar_detection_model)/validation/objects"/>
<arg name="input/object1" value="clustering/camera_lidar_fusion/short_range_objects"/>
<arg name="output/object" value="camera_lidar_fusion/objects"/>
</include>
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="detection_by_tracker/objects"/>
<arg name="input/object1" value="camera_lidar_fusion/objects"/>
<arg name="output/object" value="temporary_merged_objects"/>
</include>
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="temporary_merged_objects"/>
<arg name="input/object1" value="clustering/objects"/>
<arg name="output/object" value="objects"/>
</include>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@
<!-- Pointcloud map filter -->
<group>
<include file="$(find-pkg-share compare_map_segmentation)/launch/voxel_based_compare_map_filter.launch.xml" if="$(var use_pointcloud_map)">
<arg name="input" value="$(var input/obstacle_segmentation/pointcloud)" />
<arg name="input_map" value="/map/pointcloud_map" />
<arg name="output" value="pointcloud_map_filtered/pointcloud" />
<arg name="distance_threshold" value="0.5" />
<arg name="input" value="$(var input/obstacle_segmentation/pointcloud)"/>
<arg name="input_map" value="/map/pointcloud_map"/>
<arg name="output" value="pointcloud_map_filtered/pointcloud"/>
<arg name="distance_threshold" value="0.5"/>
</include>
</group>

Expand All @@ -25,13 +25,21 @@
<arg name="output_clusters" value="clusters"/>
<arg name="use_pointcloud_map" value="false"/>
</include>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="input/objects" value="clusters"/>
<arg name="output/objects" value="objects_with_feature"/>
</include>
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
<arg name="input" value="objects_with_feature"/>
<arg name="output" value="objects"/>
</include>
</group>

<!-- DetectionByTracker -->
<group>
<push-ros-namespace namespace="detection_by_tracker"/>
<include file="$(find-pkg-share detection_by_tracker)/launch/detection_by_tracker.launch.xml">
</include>
<include file="$(find-pkg-share detection_by_tracker)/launch/detection_by_tracker.launch.xml"/>
</group>

<!-- CenterPoint -->
Expand All @@ -57,8 +65,8 @@
</include>
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
<arg name="input" value="objects_with_feature" />
<arg name="output" value="objects" />
<arg name="input" value="objects_with_feature"/>
<arg name="output" value="objects"/>
</include>
</group>
</group>
Expand All @@ -78,9 +86,13 @@
<group>
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="$(var lidar_detection_model)/validation/objects"/>
<arg name="input/object1" value="clustering/objects"/>
<arg name="output/object" value="temporary_merged_objects"/>
</include>
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="temporary_merged_objects"/>
<arg name="input/object1" value="detection_by_tracker/objects"/>
<arg name="output/object" value="objects"/>
</include>
</group>

</launch>

0 comments on commit 918855a

Please sign in to comment.