25
25
from launch_ros .actions import ComposableNodeContainer
26
26
from launch_ros .actions import LoadComposableNodes
27
27
from launch_ros .descriptions import ComposableNode
28
+ from launch_ros .parameter_descriptions import ParameterFile
28
29
from launch_ros .substitutions import FindPackageShare
29
30
import yaml
30
31
@@ -221,13 +222,18 @@ def create_parameter_dict(*args):
221
222
)
222
223
)
223
224
225
+ ring_outlier_filter_node_param = ParameterFile (
226
+ param_file = LaunchConfiguration ("ring_outlier_filter_node_param_file" ).perform (context ),
227
+ allow_substs = True ,
228
+ )
229
+
224
230
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
225
- if LaunchConfiguration ("output_as_sensor_frame" ).perform (context ):
226
- ring_outlier_filter_parameters = {"output_frame" : LaunchConfiguration ("frame_id" )}
231
+ if LaunchConfiguration ("output_as_sensor_frame" ).perform (context ). lower () == "true" :
232
+ ring_outlier_output_frame = {"output_frame" : LaunchConfiguration ("frame_id" )}
227
233
else :
228
- ring_outlier_filter_parameters = {
229
- "output_frame" : ""
230
- } # keep the output frame as the input frame
234
+ # keep the output frame as the input frame
235
+ ring_outlier_output_frame = { "output_frame" : "" }
236
+
231
237
nodes .append (
232
238
ComposableNode (
233
239
package = "autoware_pointcloud_preprocessor" ,
@@ -237,7 +243,7 @@ def create_parameter_dict(*args):
237
243
("input" , "rectified/pointcloud_ex" ),
238
244
("output" , "pointcloud_before_sync" ),
239
245
],
240
- parameters = [ring_outlier_filter_parameters ],
246
+ parameters = [ring_outlier_filter_node_param , ring_outlier_output_frame ],
241
247
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
242
248
)
243
249
)
0 commit comments