Skip to content

Commit 803c445

Browse files
authored
feat(aip_launcher): ring outlier filter node load from param file (#305)
* feat: ring outlier filter node load from param file Signed-off-by: vividf <[email protected]> * chore: remove distortion related in order to seperate PRs Signed-off-by: vividf <[email protected]> * chore: add param file Signed-off-by: vividf <[email protected]> --------- Signed-off-by: vividf <[email protected]>
1 parent a2efe2c commit 803c445

File tree

5 files changed

+43
-6
lines changed

5 files changed

+43
-6
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
distance_ratio: 1.03
4+
object_length_threshold: 0.1
5+
num_points_threshold: 4
6+
max_rings_num: 128
7+
max_points_num_per_ring: 4000
8+
publish_outlier_pointcloud: false
9+
min_azimuth_deg: 0.0
10+
max_azimuth_deg: 360.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
horizontal_bins: 36
14+
noise_threshold: 2

aip_x2_launch/launch/pandar_node_container.launch.py

+11-6
Original file line numberDiff line numberDiff line change
@@ -209,11 +209,9 @@ def create_parameter_dict(*args):
209209

210210
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
211211
if LaunchConfiguration("output_as_sensor_frame").perform(context):
212-
ring_outlier_filter_parameters = {"output_frame": LaunchConfiguration("frame_id")}
212+
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
213213
else:
214-
ring_outlier_filter_parameters = {
215-
"output_frame": ""
216-
} # keep the output frame as the input frame
214+
ring_outlier_output_frame = {"output_frame": ""} # keep the output frame as the input frame
217215
ring_outlier_filter_component = ComposableNode(
218216
package="autoware_pointcloud_preprocessor",
219217
plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent",
@@ -222,7 +220,10 @@ def create_parameter_dict(*args):
222220
("input", "rectified/pointcloud_ex"),
223221
("output", "pointcloud_before_sync"),
224222
],
225-
parameters=[ring_outlier_filter_parameters],
223+
parameters=[
224+
load_composable_node_param("ring_outlier_filter_node_param_file"),
225+
ring_outlier_output_frame,
226+
],
226227
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
227228
)
228229

@@ -342,7 +343,11 @@ def add_launch_arg(name: str, default_value=None):
342343
add_launch_arg("horizontal_resolution", "0.4")
343344
add_launch_arg(
344345
"blockage_diagnostics_param_file",
345-
[FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"],
346+
[FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics.param.yaml"],
347+
)
348+
add_launch_arg(
349+
"ring_outlier_filter_node_param_file",
350+
[FindPackageShare("aip_x2_launch"), "/config/ring_outlier_filter_node.param.yaml"],
346351
)
347352
add_launch_arg(
348353
"distortion_corrector_node_param_file",
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
distance_ratio: 1.03
4+
object_length_threshold: 0.1
5+
num_points_threshold: 4
6+
max_rings_num: 128
7+
max_points_num_per_ring: 4000
8+
publish_outlier_pointcloud: false
9+
min_azimuth_deg: 0.0
10+
max_azimuth_deg: 360.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
horizontal_bins: 36
14+
noise_threshold: 2

common_sensor_launch/launch/nebula_node_container.launch.py

+4
Original file line numberDiff line numberDiff line change
@@ -382,6 +382,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
382382
"distortion_corrector_node_param_file",
383383
[FindPackageShare("common_sensor_launch"), "/config/distortion_corrector_node.param.yaml"],
384384
)
385+
add_launch_arg(
386+
"ring_outlier_filter_node_param_file",
387+
[FindPackageShare("common_sensor_launch"), "/config/ring_outlier_filter_node.param.yaml"],
388+
)
385389

386390
set_container_executable = SetLaunchConfiguration(
387391
"container_executable",

0 commit comments

Comments
 (0)