Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore(aip_x2_gen2_launch): use parameter file for ring_outlier_filter #385

Merged
merged 1 commit into from
Feb 3, 2025
Merged
Changes from all commits
Commits
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
19 changes: 19 additions & 0 deletions aip_x2_gen2_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.parameter_descriptions import ParameterFile
from launch_ros.substitutions import FindPackageShare
import yaml

Expand Down Expand Up @@ -161,6 +162,18 @@ def str2vector(string):
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

ring_outlier_filter_node_param = ParameterFile(
param_file=LaunchConfiguration("ring_outlier_filter_node_param_file").perform(context),
allow_substs=True,
)

# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true":
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
else:
# keep the output frame as the input frame
ring_outlier_output_frame = {"output_frame": ""}

ring_outlier_filter_component = ComposableNode(
package="autoware_pointcloud_preprocessor",
plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent",
Expand All @@ -169,6 +182,7 @@ def str2vector(string):
("input", "rectified/pointcloud_ex"),
("output", "pointcloud"),
],
parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand Down Expand Up @@ -298,6 +312,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
"blockage_diagnostics_param_file",
[FindPackageShare("common_sensor_launch"), "/config/blockage_diagnostics.param.yaml"],
)
add_launch_arg(
"ring_outlier_filter_node_param_file",
[FindPackageShare("common_sensor_launch"), "/config/ring_outlier_filter_node.param.yaml"],
)
add_launch_arg(
"distortion_corrector_node_param_file",
[FindPackageShare("common_sensor_launch"), "/config/distortion_corrector_node.param.yaml"],
Expand All @@ -312,6 +330,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("point_filters_param_file")

add_launch_arg("calibration_file", "")
add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
Loading