Skip to content

Commit

Permalink
Feat/sync perception launch (#534)
Browse files Browse the repository at this point in the history
* sync from autoware.universe

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* sync perception launch

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* Fix package.xml

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

* sync from autoware.universe again

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>

Signed-off-by: Shunsuke Miura <shunsuke.miura@tier4.jp>
  • Loading branch information
miursh committed Nov 9, 2022
1 parent 6b00a8c commit d3503d3
Show file tree
Hide file tree
Showing 10 changed files with 110 additions and 42 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE
2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN
max_area_matrix:
# NOTE(yukke42): The size of truck is 12 m length x 3 m width.
# NOTE(yukke42): The size of trailer is 20 m length x 3 m width.
# NOTE: The size of truck is 12 m length x 3 m width.
# NOTE: The size of trailer is 20 m length x 3 m width.
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, #UNKNOWN
12.10, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #CAR
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,14 @@
<arg name="image_number" default="1" description="choose image raw number(0-7)"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
<arg name="use_validator" default="true" description="use obstacle_pointcloud based validator"/>
<arg name="score_threshold" default="0.35"/>
<arg name="centerpoint_model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
<arg name="centerpoint_model_path" default="$(find-pkg-share lidar_centerpoint)/data"/>
<arg name="centerpoint_model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var centerpoint_model_name).param.yaml"/>

<!-- Jetson AGX -->
<!-- <include file="$(find-pkg-share tensorrt_yolo)/launch/yolo.launch.xml">
Expand Down Expand Up @@ -148,10 +153,16 @@
<!-- 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"/>
</include>
<group>
<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="score_threshold" value="$(var score_threshold)"/>
<arg name="model_name" value="$(var centerpoint_model_name)"/>
<arg name="model_path" value="$(var centerpoint_model_path)"/>
<arg name="model_param_path" value="$(var centerpoint_model_param_path)"/>
</include>
</group>
</group>

<!-- Lidar Apollo Instance Segmentation -->
Expand All @@ -169,6 +180,7 @@
<arg name="input/objects" value="labeled_clusters"/>
<arg name="output/objects" value="objects_with_feature"/>
<arg name="use_vehicle_reference_yaw" value="true"/>
<arg name="use_vehicle_reference_shape_size" value="false"/>
</include>
</group>

Expand All @@ -181,6 +193,40 @@
</group>
</group>

<!-- PointPainting -->
<group if="$(eval &quot;'$(var lidar_detection_model)'=='pointpainting'&quot;)">
<push-ros-namespace namespace="pointpainting"/>
<include file="$(find-pkg-share image_projection_based_fusion)/launch/pointpainting_fusion.launch.xml">
<arg name="input/camera_info0" value="$(var camera_info0)"/>
<arg name="input/rois0" value="/perception/object_recognition/detection/rois0"/>
<arg name="input/camera_info1" value="$(var camera_info1)"/>
<arg name="input/rois1" value="/perception/object_recognition/detection/rois1"/>
<arg name="input/camera_info2" value="$(var camera_info2)"/>
<arg name="input/rois2" value="/perception/object_recognition/detection/rois2"/>
<arg name="input/camera_info3" value="$(var camera_info3)"/>
<arg name="input/rois3" value="/perception/object_recognition/detection/rois3"/>
<arg name="input/camera_info4" value="$(var camera_info4)"/>
<arg name="input/rois4" value="/perception/object_recognition/detection/rois4"/>
<arg name="input/camera_info5" value="$(var camera_info5)"/>
<arg name="input/rois5" value="/perception/object_recognition/detection/rois5"/>
<arg name="input/camera_info6" value="$(var camera_info6)"/>
<arg name="input/rois6" value="/perception/object_recognition/detection/rois6"/>
<arg name="input/camera_info7" value="$(var camera_info7)"/>
<arg name="input/rois7" value="/perception/object_recognition/detection/rois7"/>
<arg name="input/rois_number" value="$(var image_number)"/>
<arg name="input/image0" value="$(var image_raw0)"/>
<arg name="input/image1" value="$(var image_raw1)"/>
<arg name="input/image2" value="$(var image_raw2)"/>
<arg name="input/image3" value="$(var image_raw3)"/>
<arg name="input/image4" value="$(var image_raw4)"/>
<arg name="input/image5" value="$(var image_raw5)"/>
<arg name="input/image6" value="$(var image_raw6)"/>
<arg name="input/image7" value="$(var image_raw7)"/>
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="output/objects" value="objects"/>
</include>
</group>

<!-- Validator -->
<group>
<let name="validator/input/obstacle_pointcloud" value="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud" if="$(var use_pointcloud_map)"/>
Expand All @@ -205,23 +251,25 @@

<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/object0" value="clustering/objects"/>
<arg name="input/object1" value="camera_lidar_fusion/objects"/>
<arg name="output/object" value="temporary_merged_objects"/>
</include>
</group>

<group>
<let name="merger/output/objects" value="objects_before_filter" if="$(var use_object_filter)"/>
<let name="merger/output/objects" value="$(var output/objects)" unless="$(var use_object_filter)"/>
<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_before_filter"/>
<arg name="input/object1" value="detection_by_tracker/objects"/>
<arg name="output/object" value="$(var merger/output/objects)"/>
</include>
</group>

<!-- Filter -->
<group>
<include file="$(find-pkg-share detected_object_validation)/launch/object_lanelet_filter.launch.xml">
<include file="$(find-pkg-share detected_object_validation)/launch/object_lanelet_filter.launch.xml" if="$(var use_object_filter)">
<arg name="input/object" value="objects_before_filter"/>
<arg name="output/object" value="$(var output/objects)"/>
<arg name="filtering_range_param" value="$(find-pkg-share perception_launch)/config/object_recognition/detection/object_lanelet_filter.param.yaml"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,10 @@
<arg name="input/pointcloud"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
<arg name="score_threshold" default="0.20"/>

<!-- camera param -->
<arg name="image_raw0" default="/image_raw" description="image raw topic name"/>
Expand Down Expand Up @@ -50,8 +52,10 @@
<arg name="image_number" value="$(var image_number)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="score_threshold" value="$(var score_threshold)"/>
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,9 @@

<!-- lidar param -->
<arg name="input/pointcloud"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `pointpainting`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>

Expand Down Expand Up @@ -53,6 +54,7 @@
<arg name="image_number" value="$(var image_number)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
Expand Down Expand Up @@ -81,6 +83,7 @@
<arg name="image_number" value="$(var image_number)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
Expand All @@ -92,6 +95,7 @@
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
Expand All @@ -103,6 +107,7 @@
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
</include>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,14 @@
<arg name="output/objects" default="objects"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
<arg name="use_validator" default="true" description="use obstacle_pointcloud based validator"/>
<arg name="score_threshold" default="0.35"/>
<arg name="centerpoint_model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
<arg name="centerpoint_model_path" default="$(find-pkg-share lidar_centerpoint)/data"/>
<arg name="centerpoint_model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var centerpoint_model_name).param.yaml"/>

<!-- Pointcloud map filter -->
<group>
Expand Down Expand Up @@ -62,6 +67,11 @@
<group>
<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="score_threshold" value="$(var score_threshold)"/>
<arg name="model_name" value="$(var centerpoint_model_name)"/>
<arg name="model_path" value="$(var centerpoint_model_path)"/>
<arg name="model_param_path" value="$(var centerpoint_model_param_path)"/>
</include>
</group>
</group>
Expand All @@ -81,6 +91,7 @@
<arg name="input/objects" value="labeled_clusters"/>
<arg name="output/objects" value="objects_with_feature"/>
<arg name="use_vehicle_reference_yaw" value="true"/>
<arg name="use_vehicle_reference_shape_size" value="false"/>
</include>
</group>

Expand Down Expand Up @@ -116,16 +127,18 @@
</group>

<group>
<let name="merger/output/objects" value="objects_before_filter" if="$(var use_object_filter)"/>
<let name="merger/output/objects" value="$(var output/objects)" unless="$(var use_object_filter)"/>
<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_before_filter"/>
<arg name="output/object" value="$(var merger/output/objects)"/>
</include>
</group>

<!-- Filter -->
<group>
<include file="$(find-pkg-share detected_object_validation)/launch/object_lanelet_filter.launch.xml">
<include file="$(find-pkg-share detected_object_validation)/launch/object_lanelet_filter.launch.xml" if="$(var use_object_filter)">
<arg name="input/object" value="objects_before_filter"/>
<arg name="output/object" value="$(var output/objects)"/>
<arg name="filtering_range_param" value="$(find-pkg-share perception_launch)/config/object_recognition/detection/object_lanelet_filter.param.yaml"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,10 @@
<arg name="input/pointcloud"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_pointcloud_container" default="false" description="use pointcloud container for detection preprocessor"/>
<arg name="container_name" default="pointcloud_container"/>
<arg name="score_threshold" default="0.20"/>

<!-- lidar based detection-->
<group>
Expand All @@ -14,8 +16,10 @@
<arg name="output/objects" value="lidar/objects"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="score_threshold" value="$(var score_threshold)"/>
</include>
</group>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,6 @@
from launch.actions import DeclareLaunchArgument
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import LaunchConfigurationEquals
from launch.conditions import LaunchConfigurationNotEquals
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
Expand Down Expand Up @@ -62,26 +60,27 @@ def add_launch_arg(name: str, default_value=None):
]

occupancy_grid_map_container = ComposableNodeContainer(
condition=LaunchConfigurationEquals("container", ""),
name="occupancy_grid_map_container",
name=LaunchConfiguration("container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=composable_nodes,
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)

load_composable_nodes = LoadComposableNodes(
condition=LaunchConfigurationNotEquals("container", ""),
composable_node_descriptions=composable_nodes,
target_container=LaunchConfiguration("container"),
target_container=LaunchConfiguration("container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)

return LaunchDescription(
[
add_launch_arg("container", ""),
add_launch_arg("use_multithread", "false"),
add_launch_arg("use_intra_process", "false"),
add_launch_arg("use_multithread", "False"),
add_launch_arg("use_intra_process", "True"),
add_launch_arg("use_pointcloud_container", "False"),
add_launch_arg("container_name", "occupancy_grid_map_container"),
add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"),
add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"),
add_launch_arg("output", "occupancy_grid"),
Expand Down
Loading

0 comments on commit d3503d3

Please sign in to comment.