Skip to content
This repository has been archived by the owner on Mar 27, 2023. It is now read-only.

feat: change input pointcloud from outside of launch file #257

Merged
merged 21 commits into from
Apr 11, 2022
Merged
Show file tree
Hide file tree
Changes from 14 commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
56c6a4c
change localization util input topic
taichiH Feb 22, 2022
20299b8
add arg to input arbitrary lidar topic to perception module
taichiH Feb 22, 2022
6d18813
remove default value except autoware and logging launch
taichiH Feb 22, 2022
84b2d70
add default value in localization and perception launch
taichiH Feb 25, 2022
678abae
remove default value from root launch file
taichiH Mar 1, 2022
97588d7
change input_sensor_points_topic to input/pointcloud
taichiH Mar 9, 2022
9e60cfd
Merge branch 'tier4/universe' into feature/change-rectified-to-outliered
yukkysaito Mar 31, 2022
1c970a3
cosmetic change
yukkysaito Mar 31, 2022
dc16bb7
feat: use pointcloud container
h-ohta Apr 4, 2022
92b048c
feat: move into util
h-ohta Apr 4, 2022
df053d7
Merge branch 'tier4/universe' into feature/change-rectified-to-outliered
h-ohta Apr 4, 2022
6849e67
ci(pre-commit): autofix
pre-commit-ci[bot] Apr 4, 2022
0449939
Merge branch 'tier4/universe' into feature/change-rectified-to-outliered
h-ohta Apr 5, 2022
c669708
feat: make final output topic arg
h-ohta Apr 5, 2022
6637839
fix: typo
h-ohta Apr 5, 2022
4a22938
Merge branch 'tier4/universe' into feature/change-rectified-to-outliered
h-ohta Apr 5, 2022
1bbd630
fix: some lack things
h-ohta Apr 5, 2022
a356205
Merge branch 'tier4/universe' into feature/change-rectified-to-outliered
h-ohta Apr 7, 2022
4efa1f9
fix: revert use pointcloud container
h-ohta Apr 7, 2022
c5f0f28
change to work tutorial
yukkysaito Apr 7, 2022
4e7f934
change to work tutorial
yukkysaito Apr 7, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion autoware_launch/launch/autoware.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,10 @@

<!-- Localization -->
<group>
<include file="$(find-pkg-share localization_launch)/launch/localization.launch.xml"/>
<include file="$(find-pkg-share localization_launch)/launch/localization.launch.xml">
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

<!-- Perception -->
Expand Down
5 changes: 4 additions & 1 deletion autoware_launch/launch/logging_simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,10 @@

<!-- Localization -->
<group>
<include file="$(find-pkg-share localization_launch)/launch/localization.launch.xml" if="$(var localization)"/>
<include file="$(find-pkg-share localization_launch)/launch/localization.launch.xml" if="$(var localization)">
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>

<!-- Perception -->
Expand Down
7 changes: 7 additions & 0 deletions localization_launch/launch/localization.launch.xml
Original file line number Diff line number Diff line change
@@ -1,12 +1,19 @@
<?xml version="1.0"?>
<launch>
<arg name="input/pointcloud" default="/sensing/lidar/pointcloud" description="The topic will be used in the localization util module" />
<arg name="use_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<!-- localization module -->
<group>
<push-ros-namespace namespace="localization"/>
<!-- util module -->
<group>
<push-ros-namespace namespace="util"/>
<include file="$(find-pkg-share localization_launch)/launch/util/util.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)" />
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
<!-- pose_estimator module -->
Expand Down
61 changes: 27 additions & 34 deletions localization_launch/launch/util/util.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,10 @@
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.conditions import LaunchConfigurationNotEquals
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
Expand All @@ -34,8 +36,8 @@ def load_composable_node_param(param_path):
plugin="pointcloud_preprocessor::CropBoxFilterComponent",
name="crop_box_filter_measurement_range",
remappings=[
("input", LaunchConfiguration("input_sensor_points_topic")),
("output", LaunchConfiguration("output_measurement_range_sensor_points_topic")),
("input", LaunchConfiguration("input/pointcloud")),
("output", "measurement_range/pointcloud"),
],
parameters=[
load_composable_node_param("crop_box_filter_measurement_range_param_path"),
Expand All @@ -47,8 +49,8 @@ def load_composable_node_param(param_path):
plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent",
name="voxel_grid_downsample_filter",
remappings=[
("input", LaunchConfiguration("output_measurement_range_sensor_points_topic")),
("output", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")),
("input", "measurement_range/pointcloud"),
("output", "voxel_grid_downsample/pointcloud"),
],
parameters=[load_composable_node_param("voxel_grid_downsample_filter_param_path")],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand All @@ -58,8 +60,8 @@ def load_composable_node_param(param_path):
plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent",
name="random_downsample_filter",
remappings=[
("input", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")),
("output", LaunchConfiguration("output_downsample_sensor_points_topic")),
("input", "voxel_grid_downsample/pointcloud"),
("output", LaunchConfiguration("output/pointcloud")),
],
parameters=[load_composable_node_param("random_downsample_filter_param_path")],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand All @@ -71,13 +73,21 @@ def load_composable_node_param(param_path):
random_downsample_component,
]

load_composable_nodes = LoadComposableNodes(
condition=LaunchConfigurationNotEquals("container", ""),
individual_container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=composable_nodes,
target_container=LaunchConfiguration("container"),
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)

return [load_composable_nodes]
pointcloud_container_loader = LoadComposableNodes(
composable_node_descriptions=composable_nodes,
target_container=LaunchConfiguration("container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)
return [individual_container, pointcloud_container_loader]


def generate_launch_description():
Expand Down Expand Up @@ -106,30 +116,13 @@ def add_launch_arg(name: str, default_value=None, description=None):
"path to the parameter file of random_downsample_filter",
)
add_launch_arg("use_intra_process", "true", "use ROS2 component container communication")
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "perception_pipeline_container")
YamatoAndo marked this conversation as resolved.
Show resolved Hide resolved

add_launch_arg(
"container",
"/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container",
"container name",
)
add_launch_arg(
"input_sensor_points_topic",
"/sensing/lidar/top/rectified/pointcloud",
"input topic name for raw pointcloud",
)
add_launch_arg(
"output_measurement_range_sensor_points_topic",
"measurement_range/pointcloud",
"output topic name for crop box filter",
)
add_launch_arg(
"output_voxel_grid_downsample_sensor_points_topic",
"voxel_grid_downsample/pointcloud",
"output topic name for voxel grid downsample filter",
)
add_launch_arg(
"output_downsample_sensor_points_topic",
"output/pointcloud",
"downsample/pointcloud",
"output topic name for downsample filter. this is final output",
"final output topic name",
)

return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)])
23 changes: 11 additions & 12 deletions localization_launch/launch/util/util.launch.xml
Original file line number Diff line number Diff line change
@@ -1,22 +1,21 @@
<?xml version="1.0"?>
<launch>

<!-- Topics -->
<arg name="input_sensor_points_topic" default="/sensing/lidar/top/rectified/pointcloud" description="input topic name for raw pointcloud"/>
<arg name="output_measurement_range_sensor_points_topic" default="measurement_range/pointcloud" description="output topic name for crop box filter"/>
<arg name="output_voxel_grid_downsample_sensor_points_topic" default="voxel_grid_downsample/pointcloud" description="output topic name for voxel grid downsample filter"/>
<arg name="output_downsample_sensor_points_topic" default="downsample/pointcloud" description="output topic name for downsample filter. this is final output"/>

<!-- container -->
<arg name="container" default="/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container" description="container name"/>

<!-- option -->
<arg name="use_intra_process" default="true" description="use ROS2 component container communication"/>
<arg name="input/pointcloud" description="input topic name"/>
<arg name="use_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="output/pointcloud" default="downsample/pointcloud" description="final output topic name"/>

<!-- pose_initializer -->
<include file="$(find-pkg-share pose_initializer)/launch/pose_initializer.launch.xml" />

<!-- util -->
<include file="$(find-pkg-share localization_launch)/launch/util/util.launch.py" />
<include file="$(find-pkg-share localization_launch)/launch/util/util.launch.py">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="output/pointcloud" value="$(var output/pointcloud)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" />
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_intra_process" value="true"/>
</include>

</launch>
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="input/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"/>
<arg name="image_raw1" default="/image_raw1"/>
Expand Down Expand Up @@ -110,6 +111,7 @@
<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>
Expand All @@ -118,7 +120,9 @@
<group if="$(eval &quot;'$(var lidar_detection_model)'=='apollo'&quot;)">
<push-ros-namespace namespace="apollo"/>
<group>
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml" />
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
</include>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="output/objects" value="objects_with_feature"/>
<arg name="use_vehicle_reference_yaw" value="true"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<?xml version="1.0"?>

<launch>
<arg name="input/pointcloud" />
<arg name="mode" default="camera_lidar_fusion" description="options: `camera_lidar_fusion`, `lidar` or `camera`"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`"/>
<!-- "camera_lidar_fusion", "lidar" or "camera" -->
Expand All @@ -26,6 +27,7 @@
<!-- camera lidar fusion based detection-->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_fusion&quot;')">
<include file="$(find-pkg-share perception_launch)/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="camera_info0" value="$(var camera_info0)"/>
<arg name="image_raw1" value="$(var image_raw1)"/>
Expand All @@ -50,6 +52,7 @@
<!-- lidar based detection-->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;lidar&quot;')">
<include file="$(find-pkg-share perception_launch)/launch/object_recognition/detection/lidar_based_detection.launch.xml">
<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)"/>
</include>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<launch>
<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="input_pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>

<!-- Pointcloud map filter -->
<group>
Expand Down Expand Up @@ -37,15 +37,19 @@
<group if="$(eval &quot;'$(var lidar_detection_model)'=='centerpoint'&quot;)">
<push-ros-namespace namespace="centerpoint"/>
<group>
<include file="$(find-pkg-share lidar_centerpoint)/launch/lidar_centerpoint.launch.xml" />
<include file="$(find-pkg-share lidar_centerpoint)/launch/lidar_centerpoint.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
</include>
</group>
</group>

<!-- Lidar Apollo Instance Segmentation -->
<group if="$(eval &quot;'$(var lidar_detection_model)'=='apollo'&quot;)">
<push-ros-namespace namespace="apollo"/>
<group>
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml" />
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
</include>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="output/objects" value="objects_with_feature"/>
<arg name="use_vehicle_reference_yaw" value="true"/>
Expand Down
2 changes: 2 additions & 0 deletions perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<launch>
<!-- common parameters -->
<arg name="mode" default="camera_lidar_fusion" description="options: `camera_lidar_fusion`, `lidar` or `camera`"/>
<arg name="input/pointcloud" default="/sensing/lidar/pointcloud" description="The topic will be used in the detection module" />
<arg name="image_raw0" default="/sensing/camera/camera0/image_rect_color" description="image raw topic name"/>
<arg name="camera_info0" default="/sensing/camera/camera0/camera_info" description="camera info topic name"/>
<arg name="image_raw1" default="/sensing/camera/camera1/image_rect_color"/>
Expand Down Expand Up @@ -64,6 +65,7 @@
<push-ros-namespace namespace="detection"/>
<include file="$(find-pkg-share perception_launch)/launch/object_recognition/detection/detection.launch.xml">
<arg name="mode" value="$(var mode)"/>
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="camera_info0" value="$(var camera_info0)"/>
<arg name="image_raw1" value="$(var image_raw1)"/>
Expand Down