Skip to content

Commit 1d4e949

Browse files
authored
refactor(autoware_pointcloud_preprocessor): rework ring outlier filter parameters (#8468)
* feat: rework ring outlier parameters Signed-off-by: vividf <[email protected]> * chore: add explicit cast Signed-off-by: vividf <[email protected]> * chore: add boundary Signed-off-by: vividf <[email protected]> * chore: remove filter.param Signed-off-by: vividf <[email protected]> * chore: set default frame Signed-off-by: vividf <[email protected]> * chore: add maximum boundary Signed-off-by: vividf <[email protected]> * chore: boundary to float type Signed-off-by: vividf <[email protected]> --------- Signed-off-by: vividf <[email protected]>
1 parent 90ba42b commit 1d4e949

File tree

7 files changed

+165
-36
lines changed

7 files changed

+165
-36
lines changed

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
7070
src/downsample_filter/random_downsample_filter_node.cpp
7171
src/downsample_filter/approximate_downsample_filter_nodelet.cpp
7272
src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp
73-
src/outlier_filter/ring_outlier_filter_nodelet.cpp
73+
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
7676
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
distance_ratio: 1.03
4+
object_length_threshold: 0.1
5+
num_points_threshold: 4
6+
max_rings_num: 128
7+
max_points_num_per_ring: 4000
8+
publish_outlier_pointcloud: false
9+
min_azimuth_deg: 0.0
10+
max_azimuth_deg: 360.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
horizontal_bins: 36
14+
noise_threshold: 2

sensing/autoware_pointcloud_preprocessor/docs/ring-outlier-filter.md

+1-14
Original file line numberDiff line numberDiff line change
@@ -56,20 +56,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,
5656

5757
### Core Parameters
5858

59-
| Name | Type | Default Value | Description |
60-
| ---------------------------- | ------- | ------------- | ----------------------------------------------------------------------------------------------------------------------------- |
61-
| `distance_ratio` | double | 1.03 | |
62-
| `object_length_threshold` | double | 0.1 | |
63-
| `num_points_threshold` | int | 4 | |
64-
| `max_rings_num` | uint_16 | 128 | |
65-
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
66-
| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments. |
67-
| `min_azimuth_deg` | float | 0.0 | The left limit of azimuth for visibility score calculation |
68-
| `max_azimuth_deg` | float | 360.0 | The right limit of azimuth for visibility score calculation |
69-
| `max_distance` | float | 12.0 | The limit distance for visibility score calculation |
70-
| `vertical_bins` | int | 128 | The number of vertical bin for visibility histogram |
71-
| `horizontal_bins` | int | 36 | The number of horizontal bin for visibility histogram |
72-
| `noise_threshold` | int | 2 | The threshold value for distinguishing noise from valid points in the frequency image |
59+
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/ring_outlier_filter_node.schema.json") }} |
7360

7461
## Assumptions / Known limits
7562

Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2020 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__RING_OUTLIER_FILTER_NODELET_HPP_
16-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_
15+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_
16+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_
1717

1818
#include "autoware/pointcloud_preprocessor/filter.hpp"
1919
#include "autoware/pointcloud_preprocessor/transform_info.hpp"
@@ -108,4 +108,4 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil
108108
};
109109

110110
} // namespace autoware::pointcloud_preprocessor
111-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_
111+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<launch>
2+
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud_raw_ex"/>
3+
<arg name="output_topic_name" default="/sensing/lidar/top/pointcloud_ring_filtered"/>
4+
<arg name="input_frame" default=""/>
5+
<arg name="output_frame" default=""/>
6+
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
7+
<arg name="ring_outlier_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/ring_outlier_filter_node.param.yaml"/>
8+
<node pkg="autoware_pointcloud_preprocessor" exec="ring_outlier_filter_node" name="ring_outlier_filter_node">
9+
<param from="$(var ring_outlier_filter_param_file)"/>
10+
<param from="$(var filter_param_file)"/>
11+
<remap from="input" to="$(var input_topic_name)"/>
12+
<remap from="output" to="$(var output_topic_name)"/>
13+
<param name="input_frame" value="$(var input_frame)"/>
14+
<param name="output_frame" value="$(var output_frame)"/>
15+
</node>
16+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,113 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for Ring Outlier Filter Node",
4+
"type": "object",
5+
"definitions": {
6+
"ring_outlier_filter": {
7+
"type": "object",
8+
"properties": {
9+
"distance_ratio": {
10+
"type": "number",
11+
"description": "distance_ratio",
12+
"default": "1.03",
13+
"minimum": 0.0
14+
},
15+
"object_length_threshold": {
16+
"type": "number",
17+
"description": "object_length_threshold",
18+
"default": "0.1",
19+
"minimum": 0.0
20+
},
21+
"num_points_threshold": {
22+
"type": "integer",
23+
"description": "num_points_threshold",
24+
"default": "4",
25+
"minimum": 0
26+
},
27+
"max_rings_num": {
28+
"type": "integer",
29+
"description": "max_rings_num",
30+
"default": "128",
31+
"minimum": 1
32+
},
33+
"max_points_num_per_ring": {
34+
"type": "integer",
35+
"description": "Set this value large enough such that HFoV / resolution < max_points_num_per_ring",
36+
"default": "4000",
37+
"minimum": 0
38+
},
39+
"publish_outlier_pointcloud": {
40+
"type": "boolean",
41+
"description": "Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments.",
42+
"default": "false"
43+
},
44+
"min_azimuth_deg": {
45+
"type": "number",
46+
"description": "The left limit of azimuth for visibility score calculation",
47+
"default": "0.0",
48+
"minimum": 0.0
49+
},
50+
"max_azimuth_deg": {
51+
"type": "number",
52+
"description": "The right limit of azimuth for visibility score calculation",
53+
"default": "360.0",
54+
"minimum": 0.0,
55+
"maximum": 360.0
56+
},
57+
"max_distance": {
58+
"type": "number",
59+
"description": "The limit distance for visibility score calculation",
60+
"default": "12.0",
61+
"minimum": 0.0
62+
},
63+
"vertical_bins": {
64+
"type": "integer",
65+
"description": "The number of vertical bin for visibility histogram",
66+
"default": "128",
67+
"minimum": 1
68+
},
69+
"horizontal_bins": {
70+
"type": "integer",
71+
"description": "The number of horizontal bin for visibility histogram",
72+
"default": "36",
73+
"minimum": 1
74+
},
75+
"noise_threshold": {
76+
"type": "integer",
77+
"description": "The threshold value for distinguishing noise from valid points in the frequency image",
78+
"default": "2",
79+
"minimum": 0
80+
}
81+
},
82+
"required": [
83+
"distance_ratio",
84+
"object_length_threshold",
85+
"num_points_threshold",
86+
"max_rings_num",
87+
"max_points_num_per_ring",
88+
"publish_outlier_pointcloud",
89+
"min_azimuth_deg",
90+
"max_azimuth_deg",
91+
"max_distance",
92+
"vertical_bins",
93+
"horizontal_bins",
94+
"noise_threshold"
95+
],
96+
"additionalProperties": false
97+
}
98+
},
99+
"properties": {
100+
"/**": {
101+
"type": "object",
102+
"properties": {
103+
"ros__parameters": {
104+
"$ref": "#/definitions/ring_outlier_filter"
105+
}
106+
},
107+
"required": ["ros__parameters"],
108+
"additionalProperties": false
109+
}
110+
},
111+
"required": ["/**"],
112+
"additionalProperties": false
113+
}

sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp renamed to sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp

+16-17
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2020 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/ring_outlier_filter_nodelet.hpp"
15+
#include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp"
1616

1717
#include "autoware_point_types/types.hpp"
1818

@@ -47,22 +47,21 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
4747

4848
// set initial parameters
4949
{
50-
distance_ratio_ = static_cast<double>(declare_parameter("distance_ratio", 1.03));
51-
object_length_threshold_ =
52-
static_cast<double>(declare_parameter("object_length_threshold", 0.1));
53-
num_points_threshold_ = static_cast<int>(declare_parameter("num_points_threshold", 4));
54-
max_rings_num_ = static_cast<uint16_t>(declare_parameter("max_rings_num", 128));
50+
distance_ratio_ = declare_parameter<double>("distance_ratio");
51+
object_length_threshold_ = declare_parameter<double>("object_length_threshold");
52+
num_points_threshold_ = declare_parameter<int>("num_points_threshold");
53+
max_rings_num_ = static_cast<uint16_t>(declare_parameter<int64_t>("max_rings_num"));
5554
max_points_num_per_ring_ =
56-
static_cast<size_t>(declare_parameter("max_points_num_per_ring", 4000));
57-
publish_outlier_pointcloud_ =
58-
static_cast<bool>(declare_parameter("publish_outlier_pointcloud", false));
59-
60-
min_azimuth_deg_ = static_cast<float>(declare_parameter("min_azimuth_deg", 0.0));
61-
max_azimuth_deg_ = static_cast<float>(declare_parameter("max_azimuth_deg", 360.0));
62-
max_distance_ = static_cast<float>(declare_parameter("max_distance", 12.0));
63-
vertical_bins_ = static_cast<int>(declare_parameter("vertical_bins", 128));
64-
horizontal_bins_ = static_cast<int>(declare_parameter("horizontal_bins", 36));
65-
noise_threshold_ = static_cast<int>(declare_parameter("noise_threshold", 2));
55+
static_cast<size_t>(declare_parameter<int64_t>("max_points_num_per_ring"));
56+
57+
publish_outlier_pointcloud_ = declare_parameter<bool>("publish_outlier_pointcloud");
58+
59+
min_azimuth_deg_ = declare_parameter<float>("min_azimuth_deg");
60+
max_azimuth_deg_ = declare_parameter<float>("max_azimuth_deg");
61+
max_distance_ = declare_parameter<float>("max_distance");
62+
vertical_bins_ = declare_parameter<int>("vertical_bins");
63+
horizontal_bins_ = declare_parameter<int>("horizontal_bins");
64+
noise_threshold_ = declare_parameter<int>("noise_threshold");
6665
}
6766

6867
using std::placeholders::_1;

0 commit comments

Comments
 (0)