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
+ from launch_ros .substitutions import FindPackageShare
29
29
import yaml
30
30
31
31
@@ -55,14 +55,11 @@ def get_vehicle_info(context):
55
55
return p
56
56
57
57
58
- def get_vehicle_mirror_info (context ):
59
- path = LaunchConfiguration ("vehicle_mirror_param_file" ).perform (context )
60
- with open (path , "r" ) as f :
61
- p = yaml .safe_load (f )["/**" ]["ros__parameters" ]
62
- return p
63
-
64
-
65
58
def launch_setup (context , * args , ** kwargs ):
59
+ def load_composable_node_param (param_path ):
60
+ with open (LaunchConfiguration (param_path ).perform (context ), "r" ) as f :
61
+ return yaml .safe_load (f )["/**" ]["ros__parameters" ]
62
+
66
63
def create_parameter_dict (* args ):
67
64
result = {}
68
65
for x in args :
@@ -85,12 +82,6 @@ def create_parameter_dict(*args):
85
82
sensor_calib_fp
86
83
), "Sensor calib file under calibration/ was not found: {}" .format (sensor_calib_fp )
87
84
88
- # Pointcloud preprocessor parameters
89
- distortion_corrector_node_param = ParameterFile (
90
- param_file = LaunchConfiguration ("distortion_correction_node_param_path" ).perform (context ),
91
- allow_substs = True ,
92
- )
93
-
94
85
nodes = []
95
86
96
87
nodes .append (
@@ -158,7 +149,7 @@ def create_parameter_dict(*args):
158
149
)
159
150
)
160
151
161
- mirror_info = get_vehicle_mirror_info ( context )
152
+ mirror_info = load_composable_node_param ( "vehicle_mirror_param_file" )
162
153
cropbox_parameters ["min_x" ] = mirror_info ["min_longitudinal_offset" ]
163
154
cropbox_parameters ["max_x" ] = mirror_info ["max_longitudinal_offset" ]
164
155
cropbox_parameters ["min_y" ] = mirror_info ["min_lateral_offset" ]
@@ -191,7 +182,7 @@ def create_parameter_dict(*args):
191
182
("~/input/pointcloud" , "mirror_cropped/pointcloud_ex" ),
192
183
("~/output/pointcloud" , "rectified/pointcloud_ex" ),
193
184
],
194
- parameters = [distortion_corrector_node_param ],
185
+ parameters = [load_composable_node_param ( "distortion_corrector_node_param_file" ) ],
195
186
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
196
187
)
197
188
)
@@ -273,8 +264,6 @@ def add_launch_arg(name: str, default_value=None, description=None):
273
264
DeclareLaunchArgument (name , default_value = default_value , description = description )
274
265
)
275
266
276
- pointcloud_preprocessor_share_dir = get_package_share_directory ("pointcloud_preprocessor" )
277
-
278
267
add_launch_arg ("sensor_model" , description = "sensor model name" )
279
268
add_launch_arg ("config_file" , "" , description = "sensor configuration file" )
280
269
add_launch_arg ("launch_driver" , "True" , "do launch driver" )
@@ -295,22 +284,17 @@ def add_launch_arg(name: str, default_value=None, description=None):
295
284
add_launch_arg ("frame_id" , "lidar" , "frame id" )
296
285
add_launch_arg ("input_frame" , LaunchConfiguration ("base_frame" ), "use for cropbox" )
297
286
add_launch_arg ("output_frame" , LaunchConfiguration ("base_frame" ), "use for cropbox" )
287
+ add_launch_arg ("use_multithread" , "False" , "use multithread" )
288
+ add_launch_arg ("use_intra_process" , "False" , "use ROS 2 component container communication" )
289
+ add_launch_arg ("lidar_container_name" , "nebula_node_container" )
290
+ add_launch_arg ("output_as_sensor_frame" , "True" , "output final pointcloud in sensor frame" )
298
291
add_launch_arg (
299
292
"vehicle_mirror_param_file" , description = "path to the file of vehicle mirror position yaml"
300
293
)
301
294
add_launch_arg (
302
- "distortion_correction_node_param_path" ,
303
- os .path .join (
304
- pointcloud_preprocessor_share_dir ,
305
- "config" ,
306
- "distortion_corrector_node.param.yaml" ,
307
- ),
308
- description = "path to parameter file of distortion correction node" ,
295
+ "distortion_corrector_node_param_file" ,
296
+ [FindPackageShare ("common_sensor_launch" ), "/config/distortion_corrector_node.param.yaml" ],
309
297
)
310
- add_launch_arg ("use_multithread" , "False" , "use multithread" )
311
- add_launch_arg ("use_intra_process" , "False" , "use ROS 2 component container communication" )
312
- add_launch_arg ("lidar_container_name" , "nebula_node_container" )
313
- add_launch_arg ("output_as_sensor_frame" , "True" , "output final pointcloud in sensor frame" )
314
298
315
299
set_container_executable = SetLaunchConfiguration (
316
300
"container_executable" ,
0 commit comments