diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
index f39e45d4ea72e..47c50e1c96bc8 100644
--- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
+++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
@@ -83,7 +83,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/distortion_corrector/distortion_corrector_node.cpp
src/blockage_diag/blockage_diag_node.cpp
src/polygon_remover/polygon_remover.cpp
- src/vector_map_filter/vector_map_inside_area_filter.cpp
+ src/vector_map_filter/vector_map_inside_area_filter_node.cpp
src/utility/geometry.cpp
)
diff --git a/sensing/autoware_pointcloud_preprocessor/config/vector_map_inside_area_filter_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/vector_map_inside_area_filter_node.param.yaml
new file mode 100644
index 0000000000000..e7df8c9641a8b
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/config/vector_map_inside_area_filter_node.param.yaml
@@ -0,0 +1,5 @@
+/**:
+ ros__parameters:
+ polygon_type: "no_obstacle_segmentation_area"
+ use_z_filter: false
+ z_threshold: 0.0
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md
index 1b6f86a7e4f27..64310ed56f0c3 100644
--- a/sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md
+++ b/sensing/autoware_pointcloud_preprocessor/docs/vector-map-inside-area-filter.md
@@ -33,10 +33,6 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,
### Core Parameters
-| Name | Type | Description |
-| -------------- | ------ | --------------------------- |
-| `polygon_type` | string | polygon type to be filtered |
-| `use_z` | bool | use z value for filtering |
-| `z_threshold` | float | z threshold for filtering |
+{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/vector_map_inside_area_filter_node.schema.json") }}
## Assumptions / Known limits
diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp
similarity index 91%
rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp
rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp
index fef3c8da79714..690be042dcd37 100644
--- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp
+++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_
-#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_
+#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_NODE_HPP_ // NOLINT
+#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_NODE_HPP_ // NOLINT
#include "autoware/pointcloud_preprocessor/filter.hpp"
#include "autoware/pointcloud_preprocessor/utility/geometry.hpp"
@@ -58,4 +58,6 @@ class VectorMapInsideAreaFilterComponent : public autoware::pointcloud_preproces
} // namespace autoware::pointcloud_preprocessor
-#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_HPP_
+// clang-format off
+#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__VECTOR_MAP_INSIDE_AREA_FILTER_NODE_HPP_ // NOLINT
+// clang-format on
diff --git a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml
new file mode 100644
index 0000000000000..21eded98595ba
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml
@@ -0,0 +1,14 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/schema/vector_map_inside_area_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/vector_map_inside_area_filter_node.schema.json
new file mode 100644
index 0000000000000..a7e971583f72a
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/schema/vector_map_inside_area_filter_node.schema.json
@@ -0,0 +1,43 @@
+{
+ "$schema": "http://json-schema.org/draft-07/schema#",
+ "title": "Parameters for Vector Map Inside Area Filter Node",
+ "type": "object",
+ "definitions": {
+ "vector_map_inside_area_filter": {
+ "type": "object",
+ "properties": {
+ "polygon_type": {
+ "type": "string",
+ "description": "polygon type to be filtered",
+ "default": "no_obstacle_segmentation_area"
+ },
+ "use_z_filter": {
+ "type": "boolean",
+ "description": "use z value for filtering",
+ "default": "false"
+ },
+ "z_threshold": {
+ "type": "number",
+ "description": "z threshold for filtering",
+ "default": "0.0"
+ }
+ },
+ "required": ["polygon_type", "use_z_filter", "z_threshold"],
+ "additionalProperties": false
+ }
+ },
+ "properties": {
+ "/**": {
+ "type": "object",
+ "properties": {
+ "ros__parameters": {
+ "$ref": "#/definitions/vector_map_inside_area_filter"
+ }
+ },
+ "required": ["ros__parameters"],
+ "additionalProperties": false
+ }
+ },
+ "required": ["/**"],
+ "additionalProperties": false
+}
diff --git a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp
similarity index 94%
rename from sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp
rename to sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp
index 81baa173e76ce..6fdf7791601cf 100644
--- a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp
+++ b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp
@@ -1,4 +1,4 @@
-// Copyright 2022 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/vector_map_filter/vector_map_inside_area_filter.hpp"
+#include "autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp"
namespace
{
@@ -67,8 +67,7 @@ VectorMapInsideAreaFilterComponent::VectorMapInsideAreaFilterComponent(
const rclcpp::NodeOptions & node_options)
: Filter("VectorMapInsideAreaFilter", node_options)
{
- polygon_type_ =
- static_cast(declare_parameter("polygon_type", "no_obstacle_segmentation_area"));
+ polygon_type_ = declare_parameter("polygon_type");
using std::placeholders::_1;
// Set subscriber
@@ -77,8 +76,8 @@ VectorMapInsideAreaFilterComponent::VectorMapInsideAreaFilterComponent(
std::bind(&VectorMapInsideAreaFilterComponent::mapCallback, this, _1));
// Set parameters
- use_z_filter_ = declare_parameter("use_z_filter", false);
- z_threshold_ = declare_parameter("z_threshold", 0.0f); // defined in the base_link frame
+ use_z_filter_ = declare_parameter("use_z_filter");
+ z_threshold_ = declare_parameter("z_threshold"); // defined in the base_link frame
// Set tf
{