Skip to content

Commit

Permalink
refactor(autoware_pointcloud_preprocessor): rework ring passthrough f…
Browse files Browse the repository at this point in the history
…ilter parameters (autowarefoundation#8472)

* feat: rework ring passthrough parameters

Signed-off-by: vividf <[email protected]>

* chore: fix cmake

Signed-off-by: vividf <[email protected]>

* feat: add schema

Signed-off-by: vividf <[email protected]>

* chore: fix readme

Signed-off-by: vividf <[email protected]>

* chore: fix parameter file name

Signed-off-by: vividf <[email protected]>

* chore: add boundary

Signed-off-by: vividf <[email protected]>

* chore: fix default parameter

Signed-off-by: vividf <[email protected]>

* chore: fix default parameter in schema

Signed-off-by: vividf <[email protected]>

---------

Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf authored Sep 9, 2024
1 parent c99ea5d commit 60f9829
Show file tree
Hide file tree
Showing 9 changed files with 94 additions and 41 deletions.
4 changes: 2 additions & 2 deletions sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/outlier_filter/voxel_grid_outlier_filter_node.cpp
src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp
src/passthrough_filter/passthrough_filter_node.cpp
src/passthrough_filter/passthrough_filter_uint16_node.cpp
src/passthrough_filter/passthrough_uint16.cpp
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
src/vector_map_filter/lanelet2_map_filter_node.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
filter_limit_min: 0
filter_limit_max: 127
filter_field_name: "channel"
keep_organized: false
filter_limit_negative: false
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,8 @@ The `passthrough_filter` is a node that removes points on the outside of a range

### Core Parameters

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

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 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.
Expand Down Expand Up @@ -48,8 +48,8 @@
*
*/

#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_

#include "autoware/pointcloud_preprocessor/filter.hpp"

Expand Down Expand Up @@ -77,4 +77,4 @@ class PassThroughFilterComponent : public autoware::pointcloud_preprocessor::Fil
};
} // namespace autoware::pointcloud_preprocessor

#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODELET_HPP_
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_NODE_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 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.
Expand All @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT

#include "autoware/pointcloud_preprocessor/filter.hpp"
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_uint16.hpp"
Expand Down Expand Up @@ -46,5 +46,5 @@ class PassThroughFilterUInt16Component : public autoware::pointcloud_preprocesso
} // namespace autoware::pointcloud_preprocessor

// clang-format off
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODELET_HPP_ // NOLINT
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__PASSTHROUGH_FILTER__PASSTHROUGH_FILTER_UINT16_NODE_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
@@ -1,24 +1,16 @@
<launch>
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud_raw"/>
<arg name="output_topic_name" default="/sensing/lidar/top/ring_passthrough_filtered/pointcloud"/>

<arg name="filter_field_name" default="ring"/>
<arg name="filter_limit_min" default="0"/>
<arg name="filter_limit_max" default="127"/>
<arg name="filter_limit_negative" default="False"/>
<arg name="keep_organized" default="False"/>
<arg name="input_frame" default=""/>
<arg name="output_frame" default="base_link"/>
<arg name="passthrough_filter_uint16_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/passthrough_filter_uint16_node.param.yaml"/>
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>

<node pkg="autoware_pointcloud_preprocessor" exec="passthrough_filter_uint16_node" name="passthrough_filter">
<node pkg="autoware_pointcloud_preprocessor" exec="passthrough_filter_uint16_node" name="ring_passthrough_filter">
<param from="$(var passthrough_filter_uint16_param_file)"/>
<param from="$(var filter_param_file)"/>
<remap from="input" to="$(var input_topic_name)"/>
<remap from="output" to="$(var output_topic_name)"/>

<param name="filter_field_name" value="$(var filter_field_name)"/>
<param name="filter_limit_min" value="$(var filter_limit_min)"/>
<param name="filter_limit_max" value="$(var filter_limit_max)"/>
<param name="filter_limit_negative" value="$(var filter_limit_negative)"/>
<param name="keep_organized" value="$(var keep_organized)"/>
<param name="input_frame" value="$(var input_frame)"/>
<param name="output_frame" value="$(var output_frame)"/>
</node>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Passthrough Filter UInt16 Node",
"type": "object",
"definitions": {
"passthrough_filter_uint16": {
"type": "object",
"properties": {
"filter_limit_min": {
"type": "integer",
"description": "minimum allowed field value",
"default": "0",
"minimum": 0
},
"filter_limit_max": {
"type": "integer",
"description": "maximum allowed field value",
"default": "127",
"minimum": 0
},
"filter_field_name": {
"type": "string",
"description": "filtering field name",
"default": "channel"
},
"keep_organized": {
"type": "boolean",
"description": "flag to keep indices structure",
"default": "false"
},
"filter_limit_negative": {
"type": "boolean",
"description": "flag to return whether the data is inside limit or not",
"default": "false"
}
},
"required": [
"filter_limit_min",
"filter_limit_max",
"filter_field_name",
"keep_organized",
"filter_limit_negative"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/passthrough_filter_uint16"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 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.
Expand Down Expand Up @@ -48,7 +48,7 @@
*
*/

#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_node.hpp"

#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/kdtree.h>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 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.
Expand All @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/passthrough_filter/passthrough_filter_uint16_node.hpp"

#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/kdtree.h>
Expand All @@ -29,15 +29,13 @@ PassThroughFilterUInt16Component::PassThroughFilterUInt16Component(
{
// set initial parameters
{
int filter_min = static_cast<int>(declare_parameter("filter_limit_min", 0));
int filter_max = static_cast<int>(declare_parameter("filter_limit_max", 127));
int filter_min = declare_parameter<int>("filter_limit_min");
int filter_max = declare_parameter<int>("filter_limit_max");
impl_.setFilterLimits(filter_min, filter_max);

impl_.setFilterFieldName(
static_cast<std::string>(declare_parameter("filter_field_name", "ring")));
impl_.setKeepOrganized(static_cast<bool>(declare_parameter("keep_organized", false)));
impl_.setFilterLimitsNegative(
static_cast<bool>(declare_parameter("filter_limit_negative", false)));
impl_.setFilterFieldName(declare_parameter<std::string>("filter_field_name"));
impl_.setKeepOrganized(declare_parameter<bool>("keep_organized"));
impl_.setFilterLimitsNegative(declare_parameter<bool>("filter_limit_negative"));
}

using std::placeholders::_1;
Expand Down

0 comments on commit 60f9829

Please sign in to comment.