diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml
index 23a1201a84958..bdea584bd58ae 100644
--- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml
+++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml
@@ -27,10 +27,10 @@
-
+
diff --git a/localization/twist2accel/CMakeLists.txt b/localization/twist2accel/CMakeLists.txt
index 93b9546be0a36..59f23eacb2fb3 100644
--- a/localization/twist2accel/CMakeLists.txt
+++ b/localization/twist2accel/CMakeLists.txt
@@ -13,4 +13,5 @@ ament_target_dependencies(twist2accel)
ament_auto_package(
INSTALL_TO_SHARE
launch
+ config
)
diff --git a/localization/twist2accel/README.md b/localization/twist2accel/README.md
index ec73c34052f99..5a540dca895d4 100644
--- a/localization/twist2accel/README.md
+++ b/localization/twist2accel/README.md
@@ -21,10 +21,7 @@ This package is responsible for estimating acceleration using the output of `ekf
## Parameters
-| Name | Type | Description |
-| -------------------- | ------ | ------------------------------------------------------------------------- |
-| `use_odom` | bool | use odometry if true, else use twist input (default: true) |
-| `accel_lowpass_gain` | double | lowpass gain for lowpass filter in estimating acceleration (default: 0.9) |
+{{ json_to_markdown("localization/twist2accel/schema/twist2accel.schema.json") }}
## Future work
diff --git a/localization/twist2accel/config/twist2accel.param.yaml b/localization/twist2accel/config/twist2accel.param.yaml
new file mode 100644
index 0000000000000..e58e029248253
--- /dev/null
+++ b/localization/twist2accel/config/twist2accel.param.yaml
@@ -0,0 +1,4 @@
+/**:
+ ros__parameters:
+ use_odom: true
+ accel_lowpass_gain: 0.9
diff --git a/localization/twist2accel/launch/twist2accel.launch.xml b/localization/twist2accel/launch/twist2accel.launch.xml
index 47b8a95d13a08..c4c9a3ed50bfc 100644
--- a/localization/twist2accel/launch/twist2accel.launch.xml
+++ b/localization/twist2accel/launch/twist2accel.launch.xml
@@ -1,6 +1,6 @@
-
-
+
+
@@ -8,7 +8,6 @@
-
-
+
diff --git a/localization/twist2accel/schema/twist2accel.schema.json b/localization/twist2accel/schema/twist2accel.schema.json
new file mode 100644
index 0000000000000..6b3c2bd094166
--- /dev/null
+++ b/localization/twist2accel/schema/twist2accel.schema.json
@@ -0,0 +1,36 @@
+{
+ "$schema": "http://json-schema.org/draft-07/schema#",
+ "title": "Parameters for twist2accel Nodes",
+ "type": "object",
+ "definitions": {
+ "twist2accel": {
+ "type": "object",
+ "properties": {
+ "use_odom": {
+ "type": "boolean",
+ "default": true,
+ "description": "use odometry if true, else use twist input."
+ },
+ "accel_lowpass_gain": {
+ "type": "number",
+ "default": 0.9,
+ "minimum": 0.0,
+ "description": "lowpass gain for lowpass filter in estimating acceleration."
+ }
+ },
+ "required": ["use_odom", "accel_lowpass_gain"]
+ }
+ },
+ "properties": {
+ "/**": {
+ "type": "object",
+ "properties": {
+ "ros__parameters": {
+ "$ref": "#/definitions/twist2accel"
+ }
+ },
+ "required": ["ros__parameters"]
+ }
+ },
+ "required": ["/**"]
+}
diff --git a/localization/twist2accel/src/twist2accel.cpp b/localization/twist2accel/src/twist2accel.cpp
index a8a7d46f57056..68019f27e95fe 100644
--- a/localization/twist2accel/src/twist2accel.cpp
+++ b/localization/twist2accel/src/twist2accel.cpp
@@ -35,8 +35,8 @@ Twist2Accel::Twist2Accel(const std::string & node_name, const rclcpp::NodeOption
pub_accel_ = create_publisher("output/accel", 1);
prev_twist_ptr_ = nullptr;
- accel_lowpass_gain_ = declare_parameter("accel_lowpass_gain", 0.5);
- use_odom_ = declare_parameter("use_odom", true);
+ accel_lowpass_gain_ = declare_parameter("accel_lowpass_gain");
+ use_odom_ = declare_parameter("use_odom");
lpf_alx_ptr_ = std::make_shared(accel_lowpass_gain_);
lpf_aly_ptr_ = std::make_shared(accel_lowpass_gain_);