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

feat(aip_launcher): ring outlier filter node load from param file #305

Merged
Merged
Show file tree
Hide file tree
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
14 changes: 14 additions & 0 deletions aip_x2_launch/config/ring_outlier_filter_node.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
distance_ratio: 1.03
object_length_threshold: 0.1
num_points_threshold: 4
max_rings_num: 128
max_points_num_per_ring: 4000
publish_outlier_pointcloud: false
min_azimuth_deg: 0.0
max_azimuth_deg: 360.0
max_distance: 12.0
vertical_bins: 128
horizontal_bins: 36
noise_threshold: 2
17 changes: 11 additions & 6 deletions aip_x2_launch/launch/pandar_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -209,11 +209,9 @@ def create_parameter_dict(*args):

# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
if LaunchConfiguration("output_as_sensor_frame").perform(context):
ring_outlier_filter_parameters = {"output_frame": LaunchConfiguration("frame_id")}
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
else:
ring_outlier_filter_parameters = {
"output_frame": ""
} # keep the output frame as the input frame
ring_outlier_output_frame = {"output_frame": ""} # keep the output frame as the input frame
ring_outlier_filter_component = ComposableNode(
package="autoware_pointcloud_preprocessor",
plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent",
Expand All @@ -222,7 +220,10 @@ def create_parameter_dict(*args):
("input", "rectified/pointcloud_ex"),
("output", "pointcloud_before_sync"),
],
parameters=[ring_outlier_filter_parameters],
parameters=[
load_composable_node_param("ring_outlier_filter_node_param_file"),
ring_outlier_output_frame,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand Down Expand Up @@ -342,7 +343,11 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("horizontal_resolution", "0.4")
add_launch_arg(
"blockage_diagnostics_param_file",
[FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"],
[FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics.param.yaml"],
)
add_launch_arg(
"ring_outlier_filter_node_param_file",
[FindPackageShare("aip_x2_launch"), "/config/ring_outlier_filter_node.param.yaml"],
)
add_launch_arg(
"distortion_corrector_node_param_file",
Expand Down
14 changes: 14 additions & 0 deletions common_sensor_launch/config/ring_outlier_filter_node.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
distance_ratio: 1.03
object_length_threshold: 0.1
num_points_threshold: 4
max_rings_num: 128
max_points_num_per_ring: 4000
publish_outlier_pointcloud: false
min_azimuth_deg: 0.0
max_azimuth_deg: 360.0
max_distance: 12.0
vertical_bins: 128
horizontal_bins: 36
noise_threshold: 2
4 changes: 4 additions & 0 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -382,6 +382,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
"distortion_corrector_node_param_file",
[FindPackageShare("common_sensor_launch"), "/config/distortion_corrector_node.param.yaml"],
)
add_launch_arg(
"ring_outlier_filter_node_param_file",
[FindPackageShare("common_sensor_launch"), "/config/ring_outlier_filter_node.param.yaml"],
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
Loading