@@ -99,6 +99,10 @@ def create_parameter_dict(*args):
99
99
param_file = LaunchConfiguration ("distortion_correction_node_param_path" ).perform (context ),
100
100
allow_substs = True ,
101
101
)
102
+ ring_outlier_filter_node_param = ParameterFile (
103
+ param_file = LaunchConfiguration ("ring_outlier_filter_node_param_path" ).perform (context ),
104
+ allow_substs = True ,
105
+ )
102
106
103
107
nodes = []
104
108
@@ -210,11 +214,9 @@ def create_parameter_dict(*args):
210
214
211
215
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
212
216
if LaunchConfiguration ("output_as_sensor_frame" ).perform (context ).lower () == "true" :
213
- ring_outlier_filter_parameters = {"output_frame" : LaunchConfiguration ("frame_id" )}
217
+ ring_outlier_output_frame = {"output_frame" : LaunchConfiguration ("frame_id" )}
214
218
else :
215
- ring_outlier_filter_parameters = {
216
- "output_frame" : ""
217
- } # keep the output frame as the input frame
219
+ ring_outlier_output_frame = {"output_frame" : "" } # keep the output frame as the input frame
218
220
nodes .append (
219
221
ComposableNode (
220
222
package = "autoware_pointcloud_preprocessor" ,
@@ -224,7 +226,7 @@ def create_parameter_dict(*args):
224
226
("input" , "rectified/pointcloud_ex" ),
225
227
("output" , "pointcloud_before_sync" ),
226
228
],
227
- parameters = [filter_param , ring_outlier_filter_parameters ],
229
+ parameters = [filter_param , ring_outlier_filter_node_param , ring_outlier_output_frame ],
228
230
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
229
231
)
230
232
)
@@ -333,6 +335,15 @@ def add_launch_arg(name: str, default_value=None, description=None):
333
335
),
334
336
description = "path to parameter file of distortion correction node" ,
335
337
)
338
+ add_launch_arg (
339
+ "ring_outlier_filter_node_param_path" ,
340
+ os .path .join (
341
+ common_sensor_share_dir ,
342
+ "config" ,
343
+ "ring_outlier_filter_node.param.yaml" ,
344
+ ),
345
+ description = "path to parameter file of ring outlier filter node" ,
346
+ )
336
347
337
348
set_container_executable = SetLaunchConfiguration (
338
349
"container_executable" ,
0 commit comments