Skip to content

Commit 6fccdf5

Browse files
vividfknzo25
andauthored
refactor(autoware_pointcloud_preprocessor): rework dual return outlier filter parameters (autowarefoundation#8475)
* feat: rework dual return outlier filter parameters Signed-off-by: vividf <[email protected]> * chore: fix readme Signed-off-by: vividf <[email protected]> * chore: change launch file name Signed-off-by: vividf <[email protected]> * chore: fix type Signed-off-by: vividf <[email protected]> * chore: add boundary Signed-off-by: vividf <[email protected]> * chore: change boundary Signed-off-by: vividf <[email protected]> * chore: fix boundary Signed-off-by: vividf <[email protected]> * chore: fix json schema Signed-off-by: vividf <[email protected]> * Update sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json Co-authored-by: Kenzo Lobos Tsunekawa <[email protected]> * chore: fix grammar error Signed-off-by: vividf <[email protected]> * chore: fix description for weak_first_local_noise_threshold Signed-off-by: vividf <[email protected]> * chore: change minimum and maximum to float Signed-off-by: vividf <[email protected]> --------- Signed-off-by: vividf <[email protected]> Co-authored-by: Kenzo Lobos Tsunekawa <[email protected]>
1 parent 6a24683 commit 6fccdf5

File tree

8 files changed

+208
-70
lines changed

8 files changed

+208
-70
lines changed

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
7373
src/outlier_filter/ring_outlier_filter_node.cpp
7474
src/outlier_filter/radius_search_2d_outlier_filter_node.cpp
7575
src/outlier_filter/voxel_grid_outlier_filter_node.cpp
76-
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
76+
src/outlier_filter/dual_return_outlier_filter_node.cpp
7777
src/passthrough_filter/passthrough_filter_node.cpp
7878
src/passthrough_filter/passthrough_filter_uint16_node.cpp
7979
src/passthrough_filter/passthrough_uint16.cpp
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
/**:
2+
ros__parameters:
3+
x_max: 18.0
4+
x_min: -12.0
5+
y_max: 2.0
6+
y_min: -2.0
7+
z_max: 10.0
8+
z_min: 0.0
9+
min_azimuth_deg: 135.0
10+
max_azimuth_deg: 225.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
max_azimuth_diff: 50.0
14+
weak_first_distance_ratio: 1.004
15+
general_distance_ratio: 1.03
16+
weak_first_local_noise_threshold: 2
17+
roi_mode: "Fixed_xyz_ROI"
18+
visibility_error_threshold: 0.5
19+
visibility_warn_threshold: 0.7

sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md

Lines changed: 1 addition & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -50,25 +50,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,
5050

5151
### Core Parameters
5252

53-
| Name | Type | Description |
54-
| ---------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------- |
55-
| `vertical_bins` | int | The number of vertical bin for visibility histogram |
56-
| `max_azimuth_diff` | float | Threshold for ring_outlier_filter |
57-
| `weak_first_distance_ratio` | double | Threshold for ring_outlier_filter |
58-
| `general_distance_ratio` | double | Threshold for ring_outlier_filter |
59-
| `weak_first_local_noise_threshold` | int | The parameter for determining whether it is noise |
60-
| `visibility_error_threshold` | float | When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR |
61-
| `visibility_warn_threshold` | float | When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN |
62-
| `roi_mode` | string | The name of ROI mode for switching |
63-
| `min_azimuth_deg` | float | The left limit of azimuth for `Fixed_azimuth_ROI` mode |
64-
| `max_azimuth_deg` | float | The right limit of azimuth for `Fixed_azimuth_ROI` mode |
65-
| `max_distance` | float | The limit distance for for `Fixed_azimuth_ROI` mode |
66-
| `x_max` | float | Maximum of x for `Fixed_xyz_ROI` mode |
67-
| `x_min` | float | Minimum of x for `Fixed_xyz_ROI` mode |
68-
| `y_max` | float | Maximum of y for `Fixed_xyz_ROI` mode |
69-
| `y_min` | float | Minimum of y for `Fixed_xyz_ROI` mode |
70-
| `z_max` | float | Maximum of z for `Fixed_xyz_ROI` mode |
71-
| `z_min` | float | Minimum of z for `Fixed_xyz_ROI` mode |
53+
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/dual_return_outlier_filter_node.schema.json") }}
7254

7355
## Assumptions / Known limits
7456

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2021 Tier IV, Inc.
1+
// Copyright 2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_
16-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_
15+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODE_HPP_
16+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODE_HPP_
1717

1818
#include "autoware/pointcloud_preprocessor/filter.hpp"
1919

@@ -94,5 +94,5 @@ class DualReturnOutlierFilterComponent : public autoware::pointcloud_preprocesso
9494
} // namespace autoware::pointcloud_preprocessor
9595

9696
// clang-format off
97-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_ // NOLINT
97+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODE_HPP_ // NOLINT
9898
// clang-format on

sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter.launch.xml

Lines changed: 0 additions & 21 deletions
This file was deleted.
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
<launch>
2+
<arg name="input_topic_name" default="/pointcloud"/>
3+
<arg name="output_topic_name" default="/pointcloud_filtered"/>
4+
<arg name="input_frame" default=""/>
5+
<arg name="output_frame" default=""/>
6+
<arg name="dual_return_outlier_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/dual_return_outlier_filter_node.param.yaml"/>
7+
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
8+
9+
<node pkg="autoware_pointcloud_preprocessor" exec="dual_return_outlier_filter_node" name="dual_return_outlier_filter_node">
10+
<param from="$(var dual_return_outlier_filter_param_file)"/>
11+
<param from="$(var filter_param_file)"/>
12+
<remap from="input" to="$(var input_topic_name)"/>
13+
<remap from="output" to="$(var output_topic_name)"/>
14+
<param name="input_frame" value="$(var input_frame)"/>
15+
<param name="output_frame" value="$(var output_frame)"/>
16+
</node>
17+
</launch>
Lines changed: 146 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,146 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for Dual Return Outlier Filter Node",
4+
"type": "object",
5+
"definitions": {
6+
"dual_return_outlier_filter": {
7+
"type": "object",
8+
"properties": {
9+
"x_max": {
10+
"type": "number",
11+
"description": "Maximum of x in meters for `Fixed_xyz_ROI` mode",
12+
"default": "18.0"
13+
},
14+
"x_min": {
15+
"type": "number",
16+
"description": "Minimum of x in meters for `Fixed_xyz_ROI` mode",
17+
"default": "-12.0"
18+
},
19+
"y_max": {
20+
"type": "number",
21+
"description": "Maximum of y in meters for `Fixed_xyz_ROI` mode",
22+
"default": "2.0"
23+
},
24+
"y_min": {
25+
"type": "number",
26+
"description": "Minimum of y in meters for `Fixed_xyz_ROI` mode",
27+
"default": "-2.0"
28+
},
29+
"z_max": {
30+
"type": "number",
31+
"description": "Maximum of z in meters for `Fixed_xyz_ROI` mode",
32+
"default": "10.0"
33+
},
34+
"z_min": {
35+
"type": "number",
36+
"description": "Minimum of z in meters for `Fixed_xyz_ROI` mode",
37+
"default": "0.0"
38+
},
39+
"min_azimuth_deg": {
40+
"type": "number",
41+
"description": "The left limit of azimuth in degrees for `Fixed_azimuth_ROI` mode",
42+
"default": "135.0",
43+
"minimum": 0,
44+
"maximum": 360
45+
},
46+
"max_azimuth_deg": {
47+
"type": "number",
48+
"description": "The right limit of azimuth in degrees for `Fixed_azimuth_ROI` mode",
49+
"default": "225.0",
50+
"minimum": 0,
51+
"maximum": 360
52+
},
53+
"max_distance": {
54+
"type": "number",
55+
"description": "The limit distance in meters for `Fixed_azimuth_ROI` mode",
56+
"default": "12.0",
57+
"minimum": 0.0
58+
},
59+
"vertical_bins": {
60+
"type": "integer",
61+
"description": "The number of vertical bins for the visibility histogram",
62+
"default": "128",
63+
"minimum": 1
64+
},
65+
"max_azimuth_diff": {
66+
"type": "number",
67+
"description": "The azimuth difference threshold in degrees for ring_outlier_filter",
68+
"default": "50.0",
69+
"minimum": 0.0
70+
},
71+
"weak_first_distance_ratio": {
72+
"type": "number",
73+
"description": "The maximum allowed ratio between consecutive weak point distances",
74+
"default": "1.004",
75+
"minimum": 0.0
76+
},
77+
"general_distance_ratio": {
78+
"type": "number",
79+
"description": "The maximum allowed ratio between consecutive normal point distances",
80+
"default": "1.03",
81+
"minimum": 0.0
82+
},
83+
"weak_first_local_noise_threshold": {
84+
"type": "integer",
85+
"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.",
86+
"default": "2",
87+
"minimum": 0
88+
},
89+
"roi_mode": {
90+
"type": "string",
91+
"description": "roi mode",
92+
"default": "Fixed_xyz_ROI",
93+
"enum": ["Fixed_xyz_ROI", "No_ROI", "Fixed_azimuth_ROI"]
94+
},
95+
"visibility_error_threshold": {
96+
"type": "number",
97+
"description": "When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR",
98+
"default": "0.5",
99+
"minimum": 0.0,
100+
"maximum": 1.0
101+
},
102+
"visibility_warn_threshold": {
103+
"type": "number",
104+
"description": "When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN",
105+
"default": "0.7",
106+
"minimum": 0.0,
107+
"maximum": 1.0
108+
}
109+
},
110+
"required": [
111+
"x_max",
112+
"x_min",
113+
"y_max",
114+
"y_min",
115+
"z_max",
116+
"z_min",
117+
"min_azimuth_deg",
118+
"max_azimuth_deg",
119+
"max_distance",
120+
"vertical_bins",
121+
"max_azimuth_diff",
122+
"weak_first_distance_ratio",
123+
"general_distance_ratio",
124+
"weak_first_local_noise_threshold",
125+
"roi_mode",
126+
"visibility_error_threshold",
127+
"visibility_warn_threshold"
128+
],
129+
"additionalProperties": false
130+
}
131+
},
132+
"properties": {
133+
"/**": {
134+
"type": "object",
135+
"properties": {
136+
"ros__parameters": {
137+
"$ref": "#/definitions/dual_return_outlier_filter"
138+
}
139+
},
140+
"required": ["ros__parameters"],
141+
"additionalProperties": false
142+
}
143+
},
144+
"required": ["/**"],
145+
"additionalProperties": false
146+
}
Lines changed: 20 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2021 Tier IV, Inc.
1+
// Copyright 2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp"
15+
#include "autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp"
1616

1717
#include "autoware_point_types/types.hpp"
1818

@@ -38,29 +38,24 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent(
3838
{
3939
// set initial parameters
4040
{
41-
x_max_ = static_cast<float>(declare_parameter("x_max", 18.0));
42-
x_min_ = static_cast<float>(declare_parameter("x_min", -12.0));
43-
y_max_ = static_cast<float>(declare_parameter("y_max", 2.0));
44-
y_min_ = static_cast<float>(declare_parameter("y_min", -2.0));
45-
z_max_ = static_cast<float>(declare_parameter("z_max", 10.0));
46-
z_min_ = static_cast<float>(declare_parameter("z_min", 0.0));
47-
min_azimuth_deg_ = static_cast<float>(declare_parameter("min_azimuth_deg", 135.0));
48-
max_azimuth_deg_ = static_cast<float>(declare_parameter("max_azimuth_deg", 225.0));
49-
max_distance_ = static_cast<float>(declare_parameter("max_distance", 12.0));
50-
vertical_bins_ = static_cast<int>(declare_parameter("vertical_bins", 128));
51-
max_azimuth_diff_ = static_cast<float>(declare_parameter("max_azimuth_diff", 50.0));
52-
weak_first_distance_ratio_ =
53-
static_cast<double>(declare_parameter("weak_first_distance_ratio", 1.004));
54-
general_distance_ratio_ =
55-
static_cast<double>(declare_parameter("general_distance_ratio", 1.03));
56-
57-
weak_first_local_noise_threshold_ =
58-
static_cast<int>(declare_parameter("weak_first_local_noise_threshold", 2));
59-
roi_mode_ = static_cast<std::string>(declare_parameter("roi_mode", "Fixed_xyz_ROI"));
60-
visibility_error_threshold_ =
61-
static_cast<float>(declare_parameter("visibility_error_threshold", 0.5));
62-
visibility_warn_threshold_ =
63-
static_cast<float>(declare_parameter("visibility_warn_threshold", 0.7));
41+
x_max_ = declare_parameter<float>("x_max");
42+
x_min_ = declare_parameter<float>("x_min");
43+
y_max_ = declare_parameter<float>("y_max");
44+
y_min_ = declare_parameter<float>("y_min");
45+
z_max_ = declare_parameter<float>("z_max");
46+
z_min_ = declare_parameter<float>("z_min");
47+
min_azimuth_deg_ = declare_parameter<float>("min_azimuth_deg");
48+
max_azimuth_deg_ = declare_parameter<float>("max_azimuth_deg");
49+
max_distance_ = declare_parameter<float>("max_distance");
50+
vertical_bins_ = declare_parameter<int>("vertical_bins");
51+
max_azimuth_diff_ = declare_parameter<float>("max_azimuth_diff");
52+
weak_first_distance_ratio_ = declare_parameter<double>("weak_first_distance_ratio");
53+
general_distance_ratio_ = declare_parameter<double>("general_distance_ratio");
54+
55+
weak_first_local_noise_threshold_ = declare_parameter<int>("weak_first_local_noise_threshold");
56+
roi_mode_ = declare_parameter<std::string>("roi_mode");
57+
visibility_error_threshold_ = declare_parameter<double>("visibility_error_threshold");
58+
visibility_warn_threshold_ = declare_parameter<double>("visibility_warn_threshold");
6459
}
6560
updater_.setHardwareID("dual_return_outlier_filter");
6661
updater_.add(

0 commit comments

Comments
 (0)