diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
index 15634187900f9..f8f9db4e68b07 100644
--- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
+++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
@@ -77,7 +77,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
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/pointcloud_accumulator/pointcloud_accumulator_node.cpp
src/vector_map_filter/lanelet2_map_filter_node.cpp
src/distortion_corrector/distortion_corrector.cpp
src/distortion_corrector/distortion_corrector_node.cpp
diff --git a/sensing/autoware_pointcloud_preprocessor/config/pointcloud_accumulator_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/pointcloud_accumulator_node.param.yaml
new file mode 100644
index 0000000000000..37ce94696db42
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/config/pointcloud_accumulator_node.param.yaml
@@ -0,0 +1,4 @@
+/**:
+ ros__parameters:
+ accumulation_time_sec: 2.0
+ pointcloud_buffer_size: 50
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md b/sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md
index d9fa56ca9c995..0ae2d80a8b392 100644
--- a/sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md
+++ b/sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md
@@ -24,10 +24,7 @@ The `pointcloud_accumulator` is a node that accumulates pointclouds for a given
### Core Parameters
-| Name | Type | Default Value | Description |
-| ------------------------ | ------ | ------------- | ----------------------- |
-| `accumulation_time_sec` | double | 2.0 | accumulation period [s] |
-| `pointcloud_buffer_size` | int | 50 | buffer size |
+{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/pointcloud_accumulator_node.schema.json") }}
## Assumptions / Known limits
diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp
similarity index 90%
rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp
rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp
index 6646426a29b99..920aff7270801 100644
--- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp
+++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp
@@ -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.
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
-#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
+#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
+#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
#include "autoware/pointcloud_preprocessor/filter.hpp"
@@ -46,5 +46,5 @@ class PointcloudAccumulatorComponent : public autoware::pointcloud_preprocessor:
} // namespace autoware::pointcloud_preprocessor
// clang-format off
-#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
+#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
// clang-format on
diff --git a/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml
new file mode 100644
index 0000000000000..3f132a1586a36
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/schema/pointcloud_accumulator_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/pointcloud_accumulator_node.schema.json
new file mode 100644
index 0000000000000..bcc18c8f0b013
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/schema/pointcloud_accumulator_node.schema.json
@@ -0,0 +1,40 @@
+{
+ "$schema": "http://json-schema.org/draft-07/schema#",
+ "title": "Parameters for Pointcloud Accumulator Node",
+ "type": "object",
+ "definitions": {
+ "pointcloud_accumulator": {
+ "type": "object",
+ "properties": {
+ "accumulation_time_sec": {
+ "type": "number",
+ "description": "accumulation period [s]",
+ "default": "2.0",
+ "minimum": 0
+ },
+ "pointcloud_buffer_size": {
+ "type": "integer",
+ "description": "buffer size",
+ "default": "50",
+ "minimum": 0
+ }
+ },
+ "required": ["accumulation_time_sec", "pointcloud_buffer_size"],
+ "additionalProperties": false
+ }
+ },
+ "properties": {
+ "/**": {
+ "type": "object",
+ "properties": {
+ "ros__parameters": {
+ "$ref": "#/definitions/pointcloud_accumulator"
+ }
+ },
+ "required": ["ros__parameters"],
+ "additionalProperties": false
+ }
+ },
+ "required": ["/**"],
+ "additionalProperties": false
+}
diff --git a/sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_node.cpp
similarity index 91%
rename from sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
rename to sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_node.cpp
index 9502add4b38ce..30eeada6d5a2a 100644
--- a/sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
+++ b/sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_node.cpp
@@ -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.
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp"
+#include "autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp"
#include
@@ -23,9 +23,9 @@ PointcloudAccumulatorComponent::PointcloudAccumulatorComponent(const rclcpp::Nod
{
// set initial parameters
{
- accumulation_time_sec_ = static_cast(declare_parameter("accumulation_time_sec", 2.0));
+ accumulation_time_sec_ = declare_parameter("accumulation_time_sec");
pointcloud_buffer_.set_capacity(
- static_cast(declare_parameter("pointcloud_buffer_size", 50)));
+ static_cast(declare_parameter("pointcloud_buffer_size")));
}
using std::placeholders::_1;