From ca44474a3b2ea2f856de25b9774dd97b769971d3 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 21 Dec 2023 02:03:53 +0900 Subject: [PATCH 01/11] fix: enable blocakge diag for xx1 Signed-off-by: badai-nguyen --- .../sensor_kit.param.yaml | 9 ++++ aip_xx1_launch/launch/lidar.launch.xml | 25 +++++++++ common_sensor_launch/CMakeLists.txt | 1 + .../blockage_diagnostics_param_file.yaml | 13 +++++ .../launch/nebula_node_container.launch.py | 51 ++++++++++++++++--- 5 files changed, 91 insertions(+), 8 deletions(-) create mode 100644 common_sensor_launch/config/blockage_diagnostics_param_file.yaml diff --git a/aip_xx1_launch/config/diagnostic_aggregator/sensor_kit.param.yaml b/aip_xx1_launch/config/diagnostic_aggregator/sensor_kit.param.yaml index 6df6325d..7495279f 100644 --- a/aip_xx1_launch/config/diagnostic_aggregator/sensor_kit.param.yaml +++ b/aip_xx1_launch/config/diagnostic_aggregator/sensor_kit.param.yaml @@ -18,6 +18,15 @@ type: diagnostic_aggregator/AnalyzerGroup path: lidar analyzers: + performance_monitoring: + type: diagnostic_aggregator/AnalyzerGroup + path: performance_monitoring + analyzers: + blockage: + type: diagnostic_aggregator/GenericAnalyzer + path: blockage + contains: [": blockage_validation"] + timeout: 1.0 velodyne: type: diagnostic_aggregator/AnalyzerGroup path: velodyne diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 77ec443f..f39e90c9 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -7,6 +7,7 @@ + @@ -24,6 +25,12 @@ + + + + + + @@ -42,6 +49,12 @@ + + + + + + @@ -60,6 +73,12 @@ + + + + + + @@ -78,6 +97,12 @@ + + + + + + diff --git a/common_sensor_launch/CMakeLists.txt b/common_sensor_launch/CMakeLists.txt index 0b3dcbd5..89bfc9f5 100644 --- a/common_sensor_launch/CMakeLists.txt +++ b/common_sensor_launch/CMakeLists.txt @@ -11,4 +11,5 @@ endif() ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/common_sensor_launch/config/blockage_diagnostics_param_file.yaml b/common_sensor_launch/config/blockage_diagnostics_param_file.yaml new file mode 100644 index 00000000..e8409a50 --- /dev/null +++ b/common_sensor_launch/config/blockage_diagnostics_param_file.yaml @@ -0,0 +1,13 @@ +/**: + ros__parameters: + blockage_ratio_threshold: 0.1 + blockage_count_threshold: 50 + blockage_buffering_frames: 2 + blockage_buffering_interval: 1 + dust_ratio_threshold: 0.2 + dust_count_threshold: 10 + dust_kernel_size: 2 + dust_buffering_frames: 10 + dust_buffering_interval: 1 + distance_coefficient: 327.67 + horizontal_resolution: 0.4 diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index a79681b8..c4c2dc50 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -25,6 +25,7 @@ from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare import yaml @@ -54,14 +55,12 @@ def get_vehicle_info(context): return p -def get_vehicle_mirror_info(context): - path = LaunchConfiguration("vehicle_mirror_param_file").perform(context) - with open(path, "r") as f: - p = yaml.safe_load(f)["/**"]["ros__parameters"] - return p - def launch_setup(context, *args, **kwargs): + def load_composable_node_param(param_path): + with open(LaunchConfiguration(param_path).perform(context), "r") as f: + return yaml.safe_load(f)["/**"]["ros__parameters"] + def create_parameter_dict(*args): result = {} for x in args: @@ -143,7 +142,7 @@ def create_parameter_dict(*args): ) ) - mirror_info = get_vehicle_mirror_info(context) + mirror_info = load_composable_node_param("vehicle_mirror_param_file") cropbox_parameters["min_x"] = mirror_info["min_longitudinal_offset"] cropbox_parameters["max_x"] = mirror_info["max_longitudinal_offset"] cropbox_parameters["min_y"] = mirror_info["min_lateral_offset"] @@ -238,6 +237,28 @@ def create_parameter_dict(*args): ], ) + blockage_diag_component = ComposableNode( + package="pointcloud_preprocessor", + plugin="pointcloud_preprocessor::BlockageDiagComponent", + name="blockage_diag", + remappings=[ + ("input", "pointcloud_raw_ex"), + ("output", "blockage_diag/pointcloud"), + ], + parameters=[ + { + "angle_range": LaunchConfiguration("angle_range"), + "horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"), + "vertical_bins": LaunchConfiguration("vertical_bins"), + "is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"), + "max_distance_range": LaunchConfiguration("max_range"), + "horizontal_resolution": LaunchConfiguration("horizontal_resolution"), + } + ] + + [load_composable_node_param("blockage_diagnostics_param_file")], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + target_container = ( container if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) @@ -249,8 +270,13 @@ def create_parameter_dict(*args): target_container=target_container, condition=IfCondition(LaunchConfiguration("launch_driver")), ) + blockage_diag_loader = LoadComposableNodes( + composable_node_descriptions=[blockage_diag_component], + target_container=target_container, + condition=IfCondition(LaunchConfiguration("launch_blockage_diag")), + ) - return [container, component_loader, driver_component_loader] + return [container, component_loader, driver_component_loader,blockage_diag_loader] def generate_launch_description(): @@ -290,6 +316,15 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("use_pointcloud_container", "false") add_launch_arg("container_name", "nebula_node_container") + add_launch_arg("angle_range", "[0.0, 360]") + add_launch_arg("horizontal_ring_id", "64") + add_launch_arg("vertical_bins", "128") + add_launch_arg("is_channel_order_top2down", "true") + add_launch_arg( + "blockage_diagnostics_param_file", + [FindPackageShare("common_sensor_launch"), "/config/blockage_diagnostics_param_file.yaml"], + ) + set_container_executable = SetLaunchConfiguration( "container_executable", "component_container", From 8e3ac8b8585d59abef564c65f4425363af8f011c Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 26 Dec 2023 20:07:26 +0900 Subject: [PATCH 02/11] fix: xx1 launch Signed-off-by: badai-nguyen --- aip_xx1_launch/launch/lidar.launch.xml | 10 +++++----- .../config/blockage_diagnostics_param_file.yaml | 2 -- .../launch/nebula_node_container.launch.py | 11 ++++++----- 3 files changed, 11 insertions(+), 12 deletions(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index f39e90c9..efd97805 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -7,7 +7,7 @@ - + @@ -30,7 +30,7 @@ - + @@ -54,7 +54,7 @@ - + @@ -78,7 +78,7 @@ - + @@ -102,7 +102,7 @@ - + diff --git a/common_sensor_launch/config/blockage_diagnostics_param_file.yaml b/common_sensor_launch/config/blockage_diagnostics_param_file.yaml index e8409a50..b8b62b50 100644 --- a/common_sensor_launch/config/blockage_diagnostics_param_file.yaml +++ b/common_sensor_launch/config/blockage_diagnostics_param_file.yaml @@ -9,5 +9,3 @@ dust_kernel_size: 2 dust_buffering_frames: 10 dust_buffering_interval: 1 - distance_coefficient: 327.67 - horizontal_resolution: 0.4 diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index c4c2dc50..8d31fbde 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -55,12 +55,11 @@ def get_vehicle_info(context): return p - def launch_setup(context, *args, **kwargs): def load_composable_node_param(param_path): with open(LaunchConfiguration(param_path).perform(context), "r") as f: return yaml.safe_load(f)["/**"]["ros__parameters"] - + def create_parameter_dict(*args): result = {} for x in args: @@ -273,10 +272,10 @@ def create_parameter_dict(*args): blockage_diag_loader = LoadComposableNodes( composable_node_descriptions=[blockage_diag_component], target_container=target_container, - condition=IfCondition(LaunchConfiguration("launch_blockage_diag")), + condition=IfCondition(LaunchConfiguration("enable_blockage_diag")), ) - return [container, component_loader, driver_component_loader,blockage_diag_loader] + return [container, component_loader, driver_component_loader, blockage_diag_loader] def generate_launch_description(): @@ -315,11 +314,13 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication") add_launch_arg("use_pointcloud_container", "false") add_launch_arg("container_name", "nebula_node_container") - + + add_launch_arg("enable_blockage_diag", "true") add_launch_arg("angle_range", "[0.0, 360]") add_launch_arg("horizontal_ring_id", "64") add_launch_arg("vertical_bins", "128") add_launch_arg("is_channel_order_top2down", "true") + add_launch_arg("horizontal_resolution", "0.4") add_launch_arg( "blockage_diagnostics_param_file", [FindPackageShare("common_sensor_launch"), "/config/blockage_diagnostics_param_file.yaml"], From 4748c456d41c7099f913cecca7b31aecb9abf1e7 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 26 Dec 2023 20:18:18 +0900 Subject: [PATCH 03/11] fix: x2 launch Signed-off-by: badai-nguyen --- aip_x2_launch/launch/lidar.launch.xml | 33 +++++++++++++++++++ .../launch/pandar_node_container.launch.py | 6 +++- 2 files changed, 38 insertions(+), 1 deletion(-) diff --git a/aip_x2_launch/launch/lidar.launch.xml b/aip_x2_launch/launch/lidar.launch.xml index 6f478053..89375e8c 100644 --- a/aip_x2_launch/launch/lidar.launch.xml +++ b/aip_x2_launch/launch/lidar.launch.xml @@ -7,6 +7,7 @@ + @@ -26,6 +27,10 @@ + + + + @@ -46,6 +51,10 @@ + + + + @@ -68,6 +77,10 @@ + + + + @@ -89,6 +102,10 @@ + + + + @@ -112,6 +129,10 @@ + + + + @@ -133,6 +154,10 @@ + + + + @@ -156,6 +181,10 @@ + + + + @@ -177,6 +206,10 @@ + + + + diff --git a/aip_x2_launch/launch/pandar_node_container.launch.py b/aip_x2_launch/launch/pandar_node_container.launch.py index cfb39cc4..c6f1da37 100644 --- a/aip_x2_launch/launch/pandar_node_container.launch.py +++ b/aip_x2_launch/launch/pandar_node_container.launch.py @@ -245,7 +245,9 @@ def create_parameter_dict(*args): "angle_range": LaunchConfiguration("angle_range"), "horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"), "vertical_bins": LaunchConfiguration("vertical_bins"), - "model": LaunchConfiguration("model"), + "is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"), + "max_distance_range": LaunchConfiguration("max_distance_range"), + "horizontal_resolution": LaunchConfiguration("horizontal_resolution"), } ] + [load_composable_node_param("blockage_diagnostics_param_file")], @@ -323,6 +325,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_frame", LaunchConfiguration("base_frame")) add_launch_arg("output_frame", LaunchConfiguration("base_frame")) add_launch_arg("dual_return_filter_param_file") + add_launch_arg("horizontal_resolution", "0.4") + add_launch_arg("max_distance_range", "200.0") add_launch_arg( "blockage_diagnostics_param_file", [FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"], From 2bfc94c75d5282da4c0c07e000269a8bd275fac1 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 26 Dec 2023 11:19:39 +0000 Subject: [PATCH 04/11] ci(pre-commit): autofix --- common_sensor_launch/launch/nebula_node_container.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index 8d31fbde..d26be92e 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -314,7 +314,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication") add_launch_arg("use_pointcloud_container", "false") add_launch_arg("container_name", "nebula_node_container") - + add_launch_arg("enable_blockage_diag", "true") add_launch_arg("angle_range", "[0.0, 360]") add_launch_arg("horizontal_ring_id", "64") From 15cb8e39ce51a211f2237cc284954249440026c0 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 28 Dec 2023 13:04:13 +0900 Subject: [PATCH 05/11] fix: remove duplicated angle_range param Signed-off-by: badai-nguyen --- aip_xx1_launch/launch/lidar.launch.xml | 4 ---- common_sensor_launch/launch/nebula_node_container.launch.py | 6 ++++-- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index efd97805..28900e0b 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -25,7 +25,6 @@ - @@ -49,7 +48,6 @@ - @@ -73,7 +71,6 @@ - @@ -97,7 +94,6 @@ - diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index d26be92e..ad12082c 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -246,7 +246,10 @@ def create_parameter_dict(*args): ], parameters=[ { - "angle_range": LaunchConfiguration("angle_range"), + "angle_range": [ + float(context.perform_substitution(LaunchConfiguration("cloud_min_angle"))), + float(context.perform_substitution(LaunchConfiguration("cloud_max_angle"))), + ], "horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"), "vertical_bins": LaunchConfiguration("vertical_bins"), "is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"), @@ -316,7 +319,6 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("container_name", "nebula_node_container") add_launch_arg("enable_blockage_diag", "true") - add_launch_arg("angle_range", "[0.0, 360]") add_launch_arg("horizontal_ring_id", "64") add_launch_arg("vertical_bins", "128") add_launch_arg("is_channel_order_top2down", "true") From fa935883bae2f973dbfc51f64f7ed4bc3f896b0e Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Thu, 28 Dec 2023 14:09:51 +0900 Subject: [PATCH 06/11] fix: remove x2 redundant param Signed-off-by: badai-nguyen --- aip_x2_launch/launch/lidar.launch.xml | 8 -------- aip_x2_launch/launch/pandar_node_container.launch.py | 8 ++++++-- 2 files changed, 6 insertions(+), 10 deletions(-) diff --git a/aip_x2_launch/launch/lidar.launch.xml b/aip_x2_launch/launch/lidar.launch.xml index 89375e8c..557304bb 100644 --- a/aip_x2_launch/launch/lidar.launch.xml +++ b/aip_x2_launch/launch/lidar.launch.xml @@ -28,7 +28,6 @@ - @@ -52,7 +51,6 @@ - @@ -78,7 +76,6 @@ - @@ -103,7 +100,6 @@ - @@ -130,7 +126,6 @@ - @@ -155,7 +150,6 @@ - @@ -182,7 +176,6 @@ - @@ -207,7 +200,6 @@ - diff --git a/aip_x2_launch/launch/pandar_node_container.launch.py b/aip_x2_launch/launch/pandar_node_container.launch.py index c6f1da37..ee0291d5 100644 --- a/aip_x2_launch/launch/pandar_node_container.launch.py +++ b/aip_x2_launch/launch/pandar_node_container.launch.py @@ -43,6 +43,10 @@ def get_pandar_monitor_info(): return p +def str2vector(string): + return [float(x) for x in string.strip("[]").split(",")] + + def get_vehicle_info(context): # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py @@ -232,6 +236,7 @@ def create_parameter_dict(*args): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) + distance_range = str2vector(context.perform_substitution(LaunchConfiguration("distance_range"))) blockage_diag_component = ComposableNode( package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::BlockageDiagComponent", @@ -246,7 +251,7 @@ def create_parameter_dict(*args): "horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"), "vertical_bins": LaunchConfiguration("vertical_bins"), "is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"), - "max_distance_range": LaunchConfiguration("max_distance_range"), + "max_distance_range": distance_range[1], "horizontal_resolution": LaunchConfiguration("horizontal_resolution"), } ] @@ -326,7 +331,6 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output_frame", LaunchConfiguration("base_frame")) add_launch_arg("dual_return_filter_param_file") add_launch_arg("horizontal_resolution", "0.4") - add_launch_arg("max_distance_range", "200.0") add_launch_arg( "blockage_diagnostics_param_file", [FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"], From 9b4b8ef8820a83273a636be4bd372fadc56391b9 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Mon, 19 Feb 2024 23:35:47 +0900 Subject: [PATCH 07/11] chore: update config file Signed-off-by: badai-nguyen --- common_sensor_launch/config/blockage_diagnostics_param_file.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/common_sensor_launch/config/blockage_diagnostics_param_file.yaml b/common_sensor_launch/config/blockage_diagnostics_param_file.yaml index b8b62b50..c6ce8e11 100644 --- a/common_sensor_launch/config/blockage_diagnostics_param_file.yaml +++ b/common_sensor_launch/config/blockage_diagnostics_param_file.yaml @@ -9,3 +9,4 @@ dust_kernel_size: 2 dust_buffering_frames: 10 dust_buffering_interval: 1 + blockage_kernel: 10 From fd4bc4a875dd6c7d52f2868152fc982772338186 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Tue, 27 Feb 2024 09:13:10 +0900 Subject: [PATCH 08/11] chore: disable xx1 blockage as default Signed-off-by: badai-nguyen --- aip_xx1_launch/launch/lidar.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 5b623fcc..709ae39b 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -7,7 +7,7 @@ - + From 57612b62c4cfafe3f3e8b4c05ae3ec4af6847bf4 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Fri, 15 Mar 2024 18:35:57 +0900 Subject: [PATCH 09/11] fix: velodyne launch Signed-off-by: badai-nguyen --- common_sensor_launch/launch/velodyne_VLP16.launch.xml | 10 ++++++++++ common_sensor_launch/launch/velodyne_VLP32C.launch.xml | 10 ++++++++++ common_sensor_launch/launch/velodyne_VLS128.launch.xml | 10 ++++++++++ 3 files changed, 30 insertions(+) diff --git a/common_sensor_launch/launch/velodyne_VLP16.launch.xml b/common_sensor_launch/launch/velodyne_VLP16.launch.xml index faa32305..a105b0a2 100644 --- a/common_sensor_launch/launch/velodyne_VLP16.launch.xml +++ b/common_sensor_launch/launch/velodyne_VLP16.launch.xml @@ -16,6 +16,11 @@ + + + + + @@ -34,6 +39,11 @@ + + + + + diff --git a/common_sensor_launch/launch/velodyne_VLP32C.launch.xml b/common_sensor_launch/launch/velodyne_VLP32C.launch.xml index c3db6428..3544d16e 100644 --- a/common_sensor_launch/launch/velodyne_VLP32C.launch.xml +++ b/common_sensor_launch/launch/velodyne_VLP32C.launch.xml @@ -16,6 +16,11 @@ + + + + + @@ -34,6 +39,11 @@ + + + + + diff --git a/common_sensor_launch/launch/velodyne_VLS128.launch.xml b/common_sensor_launch/launch/velodyne_VLS128.launch.xml index f1d32469..01c8affa 100644 --- a/common_sensor_launch/launch/velodyne_VLS128.launch.xml +++ b/common_sensor_launch/launch/velodyne_VLS128.launch.xml @@ -16,6 +16,11 @@ + + + + + @@ -34,6 +39,11 @@ + + + + + From 38eb0725b5c4012d5e9714c47826e6351b3ec6e7 Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Mon, 18 Mar 2024 23:58:36 +0900 Subject: [PATCH 10/11] Revert "fix: remove x2 redundant param" This reverts commit fa935883bae2f973dbfc51f64f7ed4bc3f896b0e. --- aip_x2_launch/launch/lidar.launch.xml | 8 ++++++++ aip_x2_launch/launch/pandar_node_container.launch.py | 8 ++------ 2 files changed, 10 insertions(+), 6 deletions(-) diff --git a/aip_x2_launch/launch/lidar.launch.xml b/aip_x2_launch/launch/lidar.launch.xml index 9ccf52af..a6bf2c3d 100644 --- a/aip_x2_launch/launch/lidar.launch.xml +++ b/aip_x2_launch/launch/lidar.launch.xml @@ -27,6 +27,7 @@ + @@ -50,6 +51,7 @@ + @@ -75,6 +77,7 @@ + @@ -99,6 +102,7 @@ + @@ -125,6 +129,7 @@ + @@ -149,6 +154,7 @@ + @@ -175,6 +181,7 @@ + @@ -199,6 +206,7 @@ + diff --git a/aip_x2_launch/launch/pandar_node_container.launch.py b/aip_x2_launch/launch/pandar_node_container.launch.py index ee0291d5..c6f1da37 100644 --- a/aip_x2_launch/launch/pandar_node_container.launch.py +++ b/aip_x2_launch/launch/pandar_node_container.launch.py @@ -43,10 +43,6 @@ def get_pandar_monitor_info(): return p -def str2vector(string): - return [float(x) for x in string.strip("[]").split(",")] - - def get_vehicle_info(context): # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py @@ -236,7 +232,6 @@ def create_parameter_dict(*args): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - distance_range = str2vector(context.perform_substitution(LaunchConfiguration("distance_range"))) blockage_diag_component = ComposableNode( package="pointcloud_preprocessor", plugin="pointcloud_preprocessor::BlockageDiagComponent", @@ -251,7 +246,7 @@ def create_parameter_dict(*args): "horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"), "vertical_bins": LaunchConfiguration("vertical_bins"), "is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"), - "max_distance_range": distance_range[1], + "max_distance_range": LaunchConfiguration("max_distance_range"), "horizontal_resolution": LaunchConfiguration("horizontal_resolution"), } ] @@ -331,6 +326,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("output_frame", LaunchConfiguration("base_frame")) add_launch_arg("dual_return_filter_param_file") add_launch_arg("horizontal_resolution", "0.4") + add_launch_arg("max_distance_range", "200.0") add_launch_arg( "blockage_diagnostics_param_file", [FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"], From d0e4c121090a9b9301abbe7561669bb38c89babc Mon Sep 17 00:00:00 2001 From: badai-nguyen Date: Mon, 18 Mar 2024 23:58:43 +0900 Subject: [PATCH 11/11] Revert "fix: x2 launch" This reverts commit 4748c456d41c7099f913cecca7b31aecb9abf1e7. --- aip_x2_launch/launch/lidar.launch.xml | 33 ------------------- .../launch/pandar_node_container.launch.py | 6 +--- 2 files changed, 1 insertion(+), 38 deletions(-) diff --git a/aip_x2_launch/launch/lidar.launch.xml b/aip_x2_launch/launch/lidar.launch.xml index a6bf2c3d..a1c8f5f6 100644 --- a/aip_x2_launch/launch/lidar.launch.xml +++ b/aip_x2_launch/launch/lidar.launch.xml @@ -6,7 +6,6 @@ - @@ -26,10 +25,6 @@ - - - - @@ -50,10 +45,6 @@ - - - - @@ -76,10 +67,6 @@ - - - - @@ -101,10 +88,6 @@ - - - - @@ -128,10 +111,6 @@ - - - - @@ -153,10 +132,6 @@ - - - - @@ -180,10 +155,6 @@ - - - - @@ -205,10 +176,6 @@ - - - - diff --git a/aip_x2_launch/launch/pandar_node_container.launch.py b/aip_x2_launch/launch/pandar_node_container.launch.py index c6f1da37..cfb39cc4 100644 --- a/aip_x2_launch/launch/pandar_node_container.launch.py +++ b/aip_x2_launch/launch/pandar_node_container.launch.py @@ -245,9 +245,7 @@ def create_parameter_dict(*args): "angle_range": LaunchConfiguration("angle_range"), "horizontal_ring_id": LaunchConfiguration("horizontal_ring_id"), "vertical_bins": LaunchConfiguration("vertical_bins"), - "is_channel_order_top2down": LaunchConfiguration("is_channel_order_top2down"), - "max_distance_range": LaunchConfiguration("max_distance_range"), - "horizontal_resolution": LaunchConfiguration("horizontal_resolution"), + "model": LaunchConfiguration("model"), } ] + [load_composable_node_param("blockage_diagnostics_param_file")], @@ -325,8 +323,6 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_frame", LaunchConfiguration("base_frame")) add_launch_arg("output_frame", LaunchConfiguration("base_frame")) add_launch_arg("dual_return_filter_param_file") - add_launch_arg("horizontal_resolution", "0.4") - add_launch_arg("max_distance_range", "200.0") add_launch_arg( "blockage_diagnostics_param_file", [FindPackageShare("aip_x2_launch"), "/config/blockage_diagnostics_param_file.yaml"],