Skip to content

Commit 60f9829

Browse files
authored
refactor(autoware_pointcloud_preprocessor): rework ring passthrough filter parameters (#8472)
* feat: rework ring passthrough parameters Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix cmake Signed-off-by: vividf <yihsiang.fang@tier4.jp> * feat: add schema Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix readme Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix parameter file name Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: add boundary Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix default parameter Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix default parameter in schema Signed-off-by: vividf <yihsiang.fang@tier4.jp> --------- Signed-off-by: vividf <yihsiang.fang@tier4.jp>
1 parent c99ea5d commit 60f9829

File tree

9 files changed

+94
-41
lines changed

9 files changed

+94
-41
lines changed

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -74,8 +74,8 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
7474
src/outlier_filter/voxel_grid_outlier_filter_node.cpp
7575
src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp
7676
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
77-
src/passthrough_filter/passthrough_filter_nodelet.cpp
78-
src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp
77+
src/passthrough_filter/passthrough_filter_node.cpp
78+
src/passthrough_filter/passthrough_filter_uint16_node.cpp
7979
src/passthrough_filter/passthrough_uint16.cpp
8080
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
8181
src/vector_map_filter/lanelet2_map_filter_node.cpp
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
/**:
2+
ros__parameters:
3+
filter_limit_min: 0
4+
filter_limit_max: 127
5+
filter_field_name: "channel"
6+
keep_organized: false
7+
filter_limit_negative: false

sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md

+2-7
Original file line numberDiff line numberDiff line change
@@ -25,13 +25,8 @@ The `passthrough_filter` is a node that removes points on the outside of a range
2525

2626
### Core Parameters
2727

28-
| Name | Type | Default Value | Description |
29-
| ----------------------- | ------ | ------------- | ------------------------------------------------------ |
30-
| `filter_limit_min` | int | 0 | minimum allowed field value |
31-
| `filter_limit_max` | int | 127 | maximum allowed field value |
32-
| `filter_field_name` | string | "ring" | filtering field name |
33-
| `keep_organized` | bool | false | flag to keep indices structure |
34-
| `filter_limit_negative` | bool | false | flag to return whether the data is inside limit or not |
28+
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json
29+
") }}
3530

3631
## Assumptions / Known limits
3732

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.
@@ -48,8 +48,8 @@
4848
*
4949
*/
5050

51-
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_
52-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_
51+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_
52+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_
5353

5454
#include "autoware/pointcloud_preprocessor/filter.hpp"
5555

@@ -77,4 +77,4 @@ class PassThroughFilterComponent : public autoware::pointcloud_preprocessor::Fil
7777
};
7878
} // namespace autoware::pointcloud_preprocessor
7979

80-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_
80+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_
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__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT
16-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT
15+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT
16+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT
1717

1818
#include "autoware/pointcloud_preprocessor/filter.hpp"
1919
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp"
@@ -46,5 +46,5 @@ class PassThroughFilterUInt16Component : public autoware::pointcloud_preprocesso
4646
} // namespace autoware::pointcloud_preprocessor
4747

4848
// clang-format off
49-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT
49+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT
5050
// clang-format on

sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml

+5-13
Original file line numberDiff line numberDiff line change
@@ -1,24 +1,16 @@
11
<launch>
22
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud_raw"/>
33
<arg name="output_topic_name" default="/sensing/lidar/top/ring_passthrough_filtered/pointcloud"/>
4-
5-
<arg name="filter_field_name" default="ring"/>
6-
<arg name="filter_limit_min" default="0"/>
7-
<arg name="filter_limit_max" default="127"/>
8-
<arg name="filter_limit_negative" default="False"/>
9-
<arg name="keep_organized" default="False"/>
104
<arg name="input_frame" default=""/>
115
<arg name="output_frame" default="base_link"/>
6+
<arg name="passthrough_filter_uint16_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/passthrough_filter_uint16_node.param.yaml"/>
7+
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
128

13-
<node pkg="autoware_pointcloud_preprocessor" exec="passthrough_filter_uint16_node" name="passthrough_filter">
9+
<node pkg="autoware_pointcloud_preprocessor" exec="passthrough_filter_uint16_node" name="ring_passthrough_filter">
10+
<param from="$(var passthrough_filter_uint16_param_file)"/>
11+
<param from="$(var filter_param_file)"/>
1412
<remap from="input" to="$(var input_topic_name)"/>
1513
<remap from="output" to="$(var output_topic_name)"/>
16-
17-
<param name="filter_field_name" value="$(var filter_field_name)"/>
18-
<param name="filter_limit_min" value="$(var filter_limit_min)"/>
19-
<param name="filter_limit_max" value="$(var filter_limit_max)"/>
20-
<param name="filter_limit_negative" value="$(var filter_limit_negative)"/>
21-
<param name="keep_organized" value="$(var keep_organized)"/>
2214
<param name="input_frame" value="$(var input_frame)"/>
2315
<param name="output_frame" value="$(var output_frame)"/>
2416
</node>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for Passthrough Filter UInt16 Node",
4+
"type": "object",
5+
"definitions": {
6+
"passthrough_filter_uint16": {
7+
"type": "object",
8+
"properties": {
9+
"filter_limit_min": {
10+
"type": "integer",
11+
"description": "minimum allowed field value",
12+
"default": "0",
13+
"minimum": 0
14+
},
15+
"filter_limit_max": {
16+
"type": "integer",
17+
"description": "maximum allowed field value",
18+
"default": "127",
19+
"minimum": 0
20+
},
21+
"filter_field_name": {
22+
"type": "string",
23+
"description": "filtering field name",
24+
"default": "channel"
25+
},
26+
"keep_organized": {
27+
"type": "boolean",
28+
"description": "flag to keep indices structure",
29+
"default": "false"
30+
},
31+
"filter_limit_negative": {
32+
"type": "boolean",
33+
"description": "flag to return whether the data is inside limit or not",
34+
"default": "false"
35+
}
36+
},
37+
"required": [
38+
"filter_limit_min",
39+
"filter_limit_max",
40+
"filter_field_name",
41+
"keep_organized",
42+
"filter_limit_negative"
43+
],
44+
"additionalProperties": false
45+
}
46+
},
47+
"properties": {
48+
"/**": {
49+
"type": "object",
50+
"properties": {
51+
"ros__parameters": {
52+
"$ref": "#/definitions/passthrough_filter_uint16"
53+
}
54+
},
55+
"required": ["ros__parameters"],
56+
"additionalProperties": false
57+
}
58+
},
59+
"required": ["/**"],
60+
"additionalProperties": false
61+
}

sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_nodelet.cpp sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_node.cpp

+2-2
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.
@@ -48,7 +48,7 @@
4848
*
4949
*/
5050

51-
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp"
51+
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_node.hpp"
5252

5353
#include <pcl/kdtree/kdtree_flann.h>
5454
#include <pcl/search/kdtree.h>

sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp sensing/autoware_pointcloud_preprocessor/src/passthrough_filter/passthrough_filter_uint16_node.cpp

+7-9
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/passthrough_filter/passthrough_filter_uint16_nodelet.hpp"
15+
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_node.hpp"
1616

1717
#include <pcl/kdtree/kdtree_flann.h>
1818
#include <pcl/search/kdtree.h>
@@ -29,15 +29,13 @@ PassThroughFilterUInt16Component::PassThroughFilterUInt16Component(
2929
{
3030
// set initial parameters
3131
{
32-
int filter_min = static_cast<int>(declare_parameter("filter_limit_min", 0));
33-
int filter_max = static_cast<int>(declare_parameter("filter_limit_max", 127));
32+
int filter_min = declare_parameter<int>("filter_limit_min");
33+
int filter_max = declare_parameter<int>("filter_limit_max");
3434
impl_.setFilterLimits(filter_min, filter_max);
3535

36-
impl_.setFilterFieldName(
37-
static_cast<std::string>(declare_parameter("filter_field_name", "ring")));
38-
impl_.setKeepOrganized(static_cast<bool>(declare_parameter("keep_organized", false)));
39-
impl_.setFilterLimitsNegative(
40-
static_cast<bool>(declare_parameter("filter_limit_negative", false)));
36+
impl_.setFilterFieldName(declare_parameter<std::string>("filter_field_name"));
37+
impl_.setKeepOrganized(declare_parameter<bool>("keep_organized"));
38+
impl_.setFilterLimitsNegative(declare_parameter<bool>("filter_limit_negative"));
4139
}
4240

4341
using std::placeholders::_1;

0 commit comments

Comments
 (0)