From 67954706c4b2fe6601e301a0c8f51c984d2a07f2 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 14 Aug 2024 23:58:01 +0900 Subject: [PATCH 01/12] feat: rework dual return outlier filter parameters Signed-off-by: vividf --- .../CMakeLists.txt | 2 +- ...dual_return_outlier_filter_node.param.yaml | 19 +++ ...pp => dual_return_outlier_filter_node.hpp} | 8 +- .../dual_return_outlier_filter.launch.xml | 20 ++- ...ual_return_outlier_filter_node.schema.json | 131 ++++++++++++++++++ ...pp => dual_return_outlier_filter_node.cpp} | 45 +++--- 6 files changed, 183 insertions(+), 42 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/config/dual_return_outlier_filter_node.param.yaml rename sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/{dual_return_outlier_filter_nodelet.hpp => dual_return_outlier_filter_node.hpp} (95%) create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json rename sensing/autoware_pointcloud_preprocessor/src/outlier_filter/{dual_return_outlier_filter_nodelet.cpp => dual_return_outlier_filter_node.cpp} (90%) diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 744bac480e058..8467078996f63 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -73,7 +73,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/outlier_filter/ring_outlier_filter_nodelet.cpp src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp - src/outlier_filter/dual_return_outlier_filter_nodelet.cpp + src/outlier_filter/dual_return_outlier_filter_node.cpp src/passthrough_filter/passthrough_filter_nodelet.cpp src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp src/passthrough_filter/passthrough_uint16.cpp diff --git a/sensing/autoware_pointcloud_preprocessor/config/dual_return_outlier_filter_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/dual_return_outlier_filter_node.param.yaml new file mode 100644 index 0000000000000..5454176d7f319 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/config/dual_return_outlier_filter_node.param.yaml @@ -0,0 +1,19 @@ +/**: + ros__parameters: + x_max: 18.0 + x_min: -12.0 + y_max: 2.0 + y_min: -2.0 + z_max: 10.0 + z_min: 0.0 + min_azimuth_deg: 135.0 + max_azimuth_deg: 225.0 + max_distance: 12.0 + vertical_bins: 128 + max_azimuth_diff: 50.0 + weak_first_distance_ratio: 1.004 + general_distance_ratio: 1.03 + weak_first_local_noise_threshold: 2 + roi_mode: "Fixed_xyz_ROI" + visibility_error_threshold: 0.5 + visibility_warn_threshold: 0.7 diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp similarity index 95% rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp index b8aba769b17a5..ef33e88ef5c98 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ +#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODE_HPP_ +#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODE_HPP_ #include "autoware/pointcloud_preprocessor/filter.hpp" @@ -94,5 +94,5 @@ class DualReturnOutlierFilterComponent : public autoware::pointcloud_preprocesso } // namespace autoware::pointcloud_preprocessor // clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ // NOLINT +#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODE_HPP_ // NOLINT // clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml index c65996fbcdc65..d0293ca140e4f 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml @@ -1,21 +1,17 @@ - + + + + + - - - - - - - + + + - - - - diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json new file mode 100644 index 0000000000000..1bb0eb0374501 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -0,0 +1,131 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Dual Return Outlier Filter Node", + "type": "object", + "definitions": { + "dual_return_outlier_filter": { + "type": "object", + "properties": { + "x_max": { + "type": "number", + "description": "Maximum of x for `Fixed_xyz_ROI` mode", + "default": "18.0" + }, + "x_min": { + "type": "number", + "description": "Minimum of x for `Fixed_xyz_ROI` mode", + "default": "-12.0" + }, + "y_max": { + "type": "number", + "description": "Maximum of y for `Fixed_xyz_ROI` mode", + "default": "2.0" + }, + "y_min": { + "type": "number", + "description": "Minimum of y for `Fixed_xyz_ROI` mode", + "default": "-2.0" + }, + "z_max": { + "type": "number", + "description": "Maximum of z for `Fixed_xyz_ROI` mode", + "default": "10.0" + }, + "z_min": { + "type": "number", + "description": "Minimum of z for `Fixed_xyz_ROI` mode", + "default": "0.0" + }, + "min_azimuth_deg": { + "type": "number", + "description": "The left limit of azimuth for `Fixed_azimuth_ROI` mode", + "default": "135.0" + }, + "max_azimuth_deg": { + "type": "number", + "description": "The right limit of azimuth for `Fixed_azimuth_ROI` mode", + "default": "225.0" + }, + "max_distance": { + "type": "number", + "description": "The limit distance for for `Fixed_azimuth_ROI` mode", + "default": "12.0" + }, + "vertical_bins": { + "type": "integer", + "description": "The number of vertical bin for visibility histogram", + "default": "128" + }, + "max_azimuth_diff": { + "type": "number", + "description": "Threshold for ring_outlier_filter", + "default": "50" + }, + "weak_first_distance_ratio": { + "type": "number", + "description": "Threshold for ring_outlier_filter", + "default": "1.004" + }, + "general_distance_ratio": { + "type": "number", + "description": "Threshold for ring_outlier_filter", + "default": "1.03" + }, + "weak_first_local_noise_threshold": { + "type": "integer", + "description": "The parameter for determining whether it is noise", + "default": "2" + }, + "roi_mode": { + "type": "string", + "description": "roi mode", + "default": "Fixed_xyz_ROI" + }, + "visibility_error_threshold": { + "type": "number", + "description": "When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR", + "default": "0.5" + }, + "visibility_warn_threshold": { + "type": "number", + "description": "When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN", + "default": "0.7" + } + }, + "required": [ + "x_max", + "x_min", + "y_max", + "y_min", + "z_max", + "z_min", + "min_azimuth_deg", + "max_azimuth_deg", + "max_distance", + "vertical_bins", + "max_azimuth_diff", + "weak_first_distance_ratio", + "general_distance_ratio", + "weak_first_local_noise_threshold", + "roi_mode", + "visibility_error_threshold", + "visibility_warn_threshold" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/dual_return_outlier_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp similarity index 90% rename from sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp rename to sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp index 5fd3262088d83..1734675c860ac 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp" +#include "autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp" #include "autoware_point_types/types.hpp" @@ -38,29 +38,24 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( { // set initial parameters { - x_max_ = static_cast(declare_parameter("x_max", 18.0)); - x_min_ = static_cast(declare_parameter("x_min", -12.0)); - y_max_ = static_cast(declare_parameter("y_max", 2.0)); - y_min_ = static_cast(declare_parameter("y_min", -2.0)); - z_max_ = static_cast(declare_parameter("z_max", 10.0)); - z_min_ = static_cast(declare_parameter("z_min", 0.0)); - min_azimuth_deg_ = static_cast(declare_parameter("min_azimuth_deg", 135.0)); - max_azimuth_deg_ = static_cast(declare_parameter("max_azimuth_deg", 225.0)); - max_distance_ = static_cast(declare_parameter("max_distance", 12.0)); - vertical_bins_ = static_cast(declare_parameter("vertical_bins", 128)); - max_azimuth_diff_ = static_cast(declare_parameter("max_azimuth_diff", 50.0)); - weak_first_distance_ratio_ = - static_cast(declare_parameter("weak_first_distance_ratio", 1.004)); - general_distance_ratio_ = - static_cast(declare_parameter("general_distance_ratio", 1.03)); - - weak_first_local_noise_threshold_ = - static_cast(declare_parameter("weak_first_local_noise_threshold", 2)); - roi_mode_ = static_cast(declare_parameter("roi_mode", "Fixed_xyz_ROI")); - visibility_error_threshold_ = - static_cast(declare_parameter("visibility_error_threshold", 0.5)); - visibility_warn_threshold_ = - static_cast(declare_parameter("visibility_warn_threshold", 0.7)); + x_max_ = declare_parameter("x_max"); + x_min_ = declare_parameter("x_min"); + y_max_ = declare_parameter("y_max"); + y_min_ = declare_parameter("y_min"); + z_max_ = declare_parameter("z_max"); + z_min_ = declare_parameter("z_min"); + min_azimuth_deg_ = declare_parameter("min_azimuth_deg"); + max_azimuth_deg_ = declare_parameter("max_azimuth_deg"); + max_distance_ = declare_parameter("max_distance"); + vertical_bins_ = declare_parameter("vertical_bins"); + max_azimuth_diff_ = declare_parameter("max_azimuth_diff"); + weak_first_distance_ratio_ = declare_parameter("weak_first_distance_ratio"); + general_distance_ratio_ = declare_parameter("general_distance_ratio"); + + weak_first_local_noise_threshold_ = declare_parameter("weak_first_local_noise_threshold"); + roi_mode_ = declare_parameter("roi_mode"); + visibility_error_threshold_ = declare_parameter("visibility_error_threshold"); + visibility_warn_threshold_ = declare_parameter("visibility_warn_threshold"); } updater_.setHardwareID("dual_return_outlier_filter"); updater_.add( From b03a5c5732c896133c598778ba434ad03739c745 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 15 Aug 2024 00:00:37 +0900 Subject: [PATCH 02/12] chore: fix readme Signed-off-by: vividf --- .../docs/dual-return-outlier-filter.md | 20 +------------------ 1 file changed, 1 insertion(+), 19 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md index 6c9a7ed14c2eb..8f4da273861a3 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -50,25 +50,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, ### Core Parameters -| Name | Type | Description | -| ---------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------- | -| `vertical_bins` | int | The number of vertical bin for visibility histogram | -| `max_azimuth_diff` | float | Threshold for ring_outlier_filter | -| `weak_first_distance_ratio` | double | Threshold for ring_outlier_filter | -| `general_distance_ratio` | double | Threshold for ring_outlier_filter | -| `weak_first_local_noise_threshold` | int | The parameter for determining whether it is noise | -| `visibility_error_threshold` | float | When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR | -| `visibility_warn_threshold` | float | When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN | -| `roi_mode` | string | The name of ROI mode for switching | -| `min_azimuth_deg` | float | The left limit of azimuth for `Fixed_azimuth_ROI` mode | -| `max_azimuth_deg` | float | The right limit of azimuth for `Fixed_azimuth_ROI` mode | -| `max_distance` | float | The limit distance for for `Fixed_azimuth_ROI` mode | -| `x_max` | float | Maximum of x for `Fixed_xyz_ROI` mode | -| `x_min` | float | Minimum of x for `Fixed_xyz_ROI` mode | -| `y_max` | float | Maximum of y for `Fixed_xyz_ROI` mode | -| `y_min` | float | Minimum of y for `Fixed_xyz_ROI` mode | -| `z_max` | float | Maximum of z for `Fixed_xyz_ROI` mode | -| `z_min` | float | Minimum of z for `Fixed_xyz_ROI` mode | +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json") }} ## Assumptions / Known limits From 17c147fa999a2670906aa0001f6130792ff6b2f4 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 15 Aug 2024 11:21:55 +0900 Subject: [PATCH 03/12] chore: change launch file name Signed-off-by: vividf --- ...lter.launch.xml => dual_return_outlier_filter_node.launch.xml} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename sensing/autoware_pointcloud_preprocessor/launch/{dual_return_outlier_filter.launch.xml => dual_return_outlier_filter_node.launch.xml} (100%) diff --git a/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter_node.launch.xml similarity index 100% rename from sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml rename to sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter_node.launch.xml From 9a6d34c1fa5bacaab0791e4eb4c29dd989c2f7e3 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 20 Aug 2024 18:01:50 +0900 Subject: [PATCH 04/12] chore: fix type Signed-off-by: vividf --- .../src/outlier_filter/dual_return_outlier_filter_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp index 1734675c860ac..d3f81473ed06f 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp @@ -54,8 +54,8 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( weak_first_local_noise_threshold_ = declare_parameter("weak_first_local_noise_threshold"); roi_mode_ = declare_parameter("roi_mode"); - visibility_error_threshold_ = declare_parameter("visibility_error_threshold"); - visibility_warn_threshold_ = declare_parameter("visibility_warn_threshold"); + visibility_error_threshold_ = declare_parameter("visibility_error_threshold"); + visibility_warn_threshold_ = declare_parameter("visibility_warn_threshold"); } updater_.setHardwareID("dual_return_outlier_filter"); updater_.add( From 1da8e1b330cedc69f2ad3dfbfee9ac5338995aaf Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 20 Aug 2024 18:09:38 +0900 Subject: [PATCH 05/12] chore: add boundary Signed-off-by: vividf --- ...ual_return_outlier_filter_node.schema.json | 30 ++++++++++++------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index 1bb0eb0374501..96ef76e3c6af2 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -39,42 +39,50 @@ "min_azimuth_deg": { "type": "number", "description": "The left limit of azimuth for `Fixed_azimuth_ROI` mode", - "default": "135.0" + "default": "135.0", + "minimum": 0 }, "max_azimuth_deg": { "type": "number", "description": "The right limit of azimuth for `Fixed_azimuth_ROI` mode", - "default": "225.0" + "default": "225.0", + "maximum": 0 }, "max_distance": { "type": "number", "description": "The limit distance for for `Fixed_azimuth_ROI` mode", - "default": "12.0" + "default": "12.0", + "minimum": 0 }, "vertical_bins": { "type": "integer", "description": "The number of vertical bin for visibility histogram", - "default": "128" + "default": "128", + "minimum": 0 }, "max_azimuth_diff": { "type": "number", "description": "Threshold for ring_outlier_filter", - "default": "50" + "default": "50", + "minimum": 0 }, "weak_first_distance_ratio": { "type": "number", "description": "Threshold for ring_outlier_filter", - "default": "1.004" + "default": "1.004", + "minimum": 0 }, "general_distance_ratio": { "type": "number", "description": "Threshold for ring_outlier_filter", - "default": "1.03" + "default": "1.03", + "minimum": 0 }, "weak_first_local_noise_threshold": { "type": "integer", "description": "The parameter for determining whether it is noise", - "default": "2" + "default": "2", + "minimum": 0 }, "roi_mode": { "type": "string", @@ -84,12 +92,14 @@ "visibility_error_threshold": { "type": "number", "description": "When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR", - "default": "0.5" + "default": "0.5", + "minimum": 0 }, "visibility_warn_threshold": { "type": "number", "description": "When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN", - "default": "0.7" + "default": "0.7", + "minimum": 0 } }, "required": [ From efbc23ced7b4e87026c81fe6181b6406d96e9d15 Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 20 Aug 2024 19:06:09 +0900 Subject: [PATCH 06/12] chore: change boundary Signed-off-by: vividf --- .../schema/dual_return_outlier_filter_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index 96ef76e3c6af2..ec72c80d07d0a 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -58,7 +58,7 @@ "type": "integer", "description": "The number of vertical bin for visibility histogram", "default": "128", - "minimum": 0 + "minimum": 1 }, "max_azimuth_diff": { "type": "number", From b122386103e1aae6985c89b30add9107e9fe077c Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 18 Sep 2024 10:01:05 +0900 Subject: [PATCH 07/12] chore: fix boundary Signed-off-by: vividf --- .../schema/dual_return_outlier_filter_node.schema.json | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index ec72c80d07d0a..96372e5ce2d33 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -40,13 +40,15 @@ "type": "number", "description": "The left limit of azimuth for `Fixed_azimuth_ROI` mode", "default": "135.0", - "minimum": 0 + "minimum": 0, + "maximum": 360 }, "max_azimuth_deg": { "type": "number", "description": "The right limit of azimuth for `Fixed_azimuth_ROI` mode", "default": "225.0", - "maximum": 0 + "minimum": 0, + "maximum": 360 }, "max_distance": { "type": "number", From 10e77aa3c7fc4e30054ce57bc62d44dbacf8f362 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 18 Sep 2024 11:21:13 +0900 Subject: [PATCH 08/12] chore: fix json schema Signed-off-by: vividf --- ...ual_return_outlier_filter_node.schema.json | 37 ++++++++++--------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index 96372e5ce2d33..50a8f782e1439 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -8,51 +8,51 @@ "properties": { "x_max": { "type": "number", - "description": "Maximum of x for `Fixed_xyz_ROI` mode", + "description": "Maximum of x in meters for `Fixed_xyz_ROI` mode", "default": "18.0" }, "x_min": { "type": "number", - "description": "Minimum of x for `Fixed_xyz_ROI` mode", + "description": "Minimum of x in meters for `Fixed_xyz_ROI` mode", "default": "-12.0" }, "y_max": { "type": "number", - "description": "Maximum of y for `Fixed_xyz_ROI` mode", + "description": "Maximum of y in meters for `Fixed_xyz_ROI` mode", "default": "2.0" }, "y_min": { "type": "number", - "description": "Minimum of y for `Fixed_xyz_ROI` mode", + "description": "Minimum of y in meters for `Fixed_xyz_ROI` mode", "default": "-2.0" }, "z_max": { "type": "number", - "description": "Maximum of z for `Fixed_xyz_ROI` mode", + "description": "Maximum of z in meters for `Fixed_xyz_ROI` mode", "default": "10.0" }, "z_min": { "type": "number", - "description": "Minimum of z for `Fixed_xyz_ROI` mode", + "description": "Minimum of z in meters for `Fixed_xyz_ROI` mode", "default": "0.0" }, "min_azimuth_deg": { "type": "number", - "description": "The left limit of azimuth for `Fixed_azimuth_ROI` mode", + "description": "The left limit of azimuth in degrees for `Fixed_azimuth_ROI` mode", "default": "135.0", "minimum": 0, "maximum": 360 }, "max_azimuth_deg": { "type": "number", - "description": "The right limit of azimuth for `Fixed_azimuth_ROI` mode", + "description": "The right limit of azimuth in degrees for `Fixed_azimuth_ROI` mode", "default": "225.0", "minimum": 0, "maximum": 360 }, "max_distance": { "type": "number", - "description": "The limit distance for for `Fixed_azimuth_ROI` mode", + "description": "The limit distance for in meters `Fixed_azimuth_ROI` mode", "default": "12.0", "minimum": 0 }, @@ -64,19 +64,19 @@ }, "max_azimuth_diff": { "type": "number", - "description": "Threshold for ring_outlier_filter", + "description": "The azimuth difference threshold in degrees for ring_outlier_filter", "default": "50", "minimum": 0 }, "weak_first_distance_ratio": { "type": "number", - "description": "Threshold for ring_outlier_filter", + "description": "The maximum allowed ratio between consecutive weak point distances", "default": "1.004", "minimum": 0 }, "general_distance_ratio": { "type": "number", - "description": "Threshold for ring_outlier_filter", + "description": "The maximum allowed ratio between consecutive normal point distances", "default": "1.03", "minimum": 0 }, @@ -89,19 +89,22 @@ "roi_mode": { "type": "string", "description": "roi mode", - "default": "Fixed_xyz_ROI" + "default": "Fixed_xyz_ROI", + "enum": ["Fixed_xyz_ROI", "No_ROI", "Fixed_azimuth_ROI"] }, "visibility_error_threshold": { "type": "number", - "description": "When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR", + "description": "When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR", "default": "0.5", - "minimum": 0 + "minimum": 0, + "maximum": 1 }, "visibility_warn_threshold": { "type": "number", - "description": "When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN", + "description": "When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN", "default": "0.7", - "minimum": 0 + "minimum": 0, + "maximum": 1 } }, "required": [ From ea0e636f7cedb83392ae0a577cd0863b249d08d8 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 18 Sep 2024 15:34:16 +0900 Subject: [PATCH 09/12] Update sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json Co-authored-by: Kenzo Lobos Tsunekawa --- .../schema/dual_return_outlier_filter_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index 50a8f782e1439..c608241c4dd62 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -58,7 +58,7 @@ }, "vertical_bins": { "type": "integer", - "description": "The number of vertical bin for visibility histogram", + "description": "The number of vertical bins for the visibility histogram", "default": "128", "minimum": 1 }, From 0d6b0bf74ad5ac6e83d5461c7e6d7479fe06e11f Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 18 Sep 2024 15:39:34 +0900 Subject: [PATCH 10/12] chore: fix grammar error Signed-off-by: vividf --- .../schema/dual_return_outlier_filter_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index c608241c4dd62..30b69f1e0fe74 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -52,7 +52,7 @@ }, "max_distance": { "type": "number", - "description": "The limit distance for in meters `Fixed_azimuth_ROI` mode", + "description": "The limit distance in meters for `Fixed_azimuth_ROI` mode", "default": "12.0", "minimum": 0 }, From 76f9ef6e8564a85bab3f28361c1496aa4afb1534 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 18 Sep 2024 16:49:51 +0900 Subject: [PATCH 11/12] chore: fix description for weak_first_local_noise_threshold Signed-off-by: vividf --- .../schema/dual_return_outlier_filter_node.schema.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index 30b69f1e0fe74..e875f821c04b0 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -82,7 +82,7 @@ }, "weak_first_local_noise_threshold": { "type": "integer", - "description": "The parameter for determining whether it is noise", + "description": "If the number of outliers among weak points is less than the weak_first_local_noise_threshold in the (max_azimuth - min_azimuth) / horizontal_bins interval, all points within the interval will not be filtered out.", "default": "2", "minimum": 0 }, From 2941451580ff37836864dec9e85eb42afd8a6bd4 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 30 Sep 2024 15:45:02 +0900 Subject: [PATCH 12/12] chore: change minimum and maximum to float Signed-off-by: vividf --- ...dual_return_outlier_filter_node.schema.json | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json index e875f821c04b0..baaa0fa1f4604 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json @@ -54,7 +54,7 @@ "type": "number", "description": "The limit distance in meters for `Fixed_azimuth_ROI` mode", "default": "12.0", - "minimum": 0 + "minimum": 0.0 }, "vertical_bins": { "type": "integer", @@ -65,20 +65,20 @@ "max_azimuth_diff": { "type": "number", "description": "The azimuth difference threshold in degrees for ring_outlier_filter", - "default": "50", - "minimum": 0 + "default": "50.0", + "minimum": 0.0 }, "weak_first_distance_ratio": { "type": "number", "description": "The maximum allowed ratio between consecutive weak point distances", "default": "1.004", - "minimum": 0 + "minimum": 0.0 }, "general_distance_ratio": { "type": "number", "description": "The maximum allowed ratio between consecutive normal point distances", "default": "1.03", - "minimum": 0 + "minimum": 0.0 }, "weak_first_local_noise_threshold": { "type": "integer", @@ -96,15 +96,15 @@ "type": "number", "description": "When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR", "default": "0.5", - "minimum": 0, - "maximum": 1 + "minimum": 0.0, + "maximum": 1.0 }, "visibility_warn_threshold": { "type": "number", "description": "When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN", "default": "0.7", - "minimum": 0, - "maximum": 1 + "minimum": 0.0, + "maximum": 1.0 } }, "required": [