Skip to content
This repository was archived by the owner on Mar 28, 2025. It is now read-only.

Commit e8b7db0

Browse files
committed
feat: modify the nebula_node_container based on tier4 internal common_sensor_launch
Signed-off-by: vividf <[email protected]>
1 parent 070cb9c commit e8b7db0

File tree

3 files changed

+19
-29
lines changed

3 files changed

+19
-29
lines changed

common_sensor_launch/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -11,4 +11,5 @@ endif()
1111

1212
ament_auto_package(INSTALL_TO_SHARE
1313
launch
14+
config
1415
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
/**:
2+
ros__parameters:
3+
base_frame: base_link
4+
use_imu: true
5+
use_3d_distortion_correction: false

common_sensor_launch/launch/nebula_node_container.launch.py

+13-29
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
from launch_ros.actions import ComposableNodeContainer
2626
from launch_ros.actions import LoadComposableNodes
2727
from launch_ros.descriptions import ComposableNode
28-
from launch_ros.parameter_descriptions import ParameterFile
28+
from launch_ros.substitutions import FindPackageShare
2929
import yaml
3030

3131

@@ -55,14 +55,11 @@ def get_vehicle_info(context):
5555
return p
5656

5757

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-
6558
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+
6663
def create_parameter_dict(*args):
6764
result = {}
6865
for x in args:
@@ -85,12 +82,6 @@ def create_parameter_dict(*args):
8582
sensor_calib_fp
8683
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)
8784

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-
9485
nodes = []
9586

9687
nodes.append(
@@ -158,7 +149,7 @@ def create_parameter_dict(*args):
158149
)
159150
)
160151

161-
mirror_info = get_vehicle_mirror_info(context)
152+
mirror_info = load_composable_node_param("vehicle_mirror_param_file")
162153
cropbox_parameters["min_x"] = mirror_info["min_longitudinal_offset"]
163154
cropbox_parameters["max_x"] = mirror_info["max_longitudinal_offset"]
164155
cropbox_parameters["min_y"] = mirror_info["min_lateral_offset"]
@@ -191,7 +182,7 @@ def create_parameter_dict(*args):
191182
("~/input/pointcloud", "mirror_cropped/pointcloud_ex"),
192183
("~/output/pointcloud", "rectified/pointcloud_ex"),
193184
],
194-
parameters=[distortion_corrector_node_param],
185+
parameters=[load_composable_node_param("distortion_corrector_node_param_file")],
195186
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
196187
)
197188
)
@@ -273,8 +264,6 @@ def add_launch_arg(name: str, default_value=None, description=None):
273264
DeclareLaunchArgument(name, default_value=default_value, description=description)
274265
)
275266

276-
pointcloud_preprocessor_share_dir = get_package_share_directory("pointcloud_preprocessor")
277-
278267
add_launch_arg("sensor_model", description="sensor model name")
279268
add_launch_arg("config_file", "", description="sensor configuration file")
280269
add_launch_arg("launch_driver", "True", "do launch driver")
@@ -295,22 +284,17 @@ def add_launch_arg(name: str, default_value=None, description=None):
295284
add_launch_arg("frame_id", "lidar", "frame id")
296285
add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox")
297286
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")
298291
add_launch_arg(
299292
"vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml"
300293
)
301294
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"],
309297
)
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")
314298

315299
set_container_executable = SetLaunchConfiguration(
316300
"container_executable",

0 commit comments

Comments
 (0)