From f29e0ba43617e864663918555c6f040a93e80259 Mon Sep 17 00:00:00 2001
From: batuhanbeytekin <batuhanbeytekin@gmail.com>
Date: Fri, 28 Jun 2024 14:16:33 +0300
Subject: [PATCH] refactor(detected_object_validation): rework parameters

Signed-off-by: batuhanbeytekin batuhanbeytekin@gmail.com
---
 .../detected_object_validation/README.md      |  18 +++
 .../occupancy_grid_based_validator.param.yaml |   2 +
 .../launch/object_lanelet_filter.launch.xml   |  23 ++--
 .../launch/object_position_filter.launch.xml  |  19 ++-
 ...acle_pointcloud_based_validator.launch.xml |  21 ++-
 .../occupancy_grid_based_validator.launch.xml |  47 ++++---
 .../schema/object_lanelet_filter.schema.json  | 121 ++++++++++++++++++
 .../schema/object_position_filter.schema.json | 109 ++++++++++++++++
 ...cle_pointcloud_based_validator.schema.json |  68 ++++++++++
 ...occupancy_grid_based_validator.schema.json |  41 ++++++
 .../src/object_lanelet_filter.cpp             |  16 +--
 .../src/object_position_filter.cpp            |  24 ++--
 .../obstacle_pointcloud_based_validator.cpp   |   2 +-
 .../src/occupancy_grid_based_validator.cpp    |   4 +-
 14 files changed, 434 insertions(+), 81 deletions(-)
 create mode 100644 perception/detected_object_validation/schema/object_lanelet_filter.schema.json
 create mode 100644 perception/detected_object_validation/schema/object_position_filter.schema.json
 create mode 100644 perception/detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json
 create mode 100644 perception/detected_object_validation/schema/occupancy_grid_based_validator.schema.json

diff --git a/perception/detected_object_validation/README.md b/perception/detected_object_validation/README.md
index 12fad4ad9759f..8715b9ba983b4 100644
--- a/perception/detected_object_validation/README.md
+++ b/perception/detected_object_validation/README.md
@@ -10,3 +10,21 @@ The purpose of this package is to eliminate obvious false positives of DetectedO
 - [Occupancy grid based validator](occupancy-grid-based-validator.md)
 - [Object lanelet filter](object-lanelet-filter.md)
 - [Object position filter](object-position-filter.md)
+
+### Node Parameters
+
+#### object_lanelet_filter
+
+{{ json_to_markdown("perception/detected_object_validation/schema/object_lanelet_filter.schema.json") }}
+
+#### object_position_filter
+
+{{ json_to_markdown("perception/detected_object_validation/schema/object_position_filter.schema.json") }}
+
+#### obstacle_pointcloud_based_validator
+
+{{ json_to_markdown("perception/detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json") }}
+
+#### occupancy_grid_based_validator
+
+{{ json_to_markdown("perception/detected_object_validation/schema/occupancy_grid_based_validator.schema.json") }}
diff --git a/perception/detected_object_validation/config/occupancy_grid_based_validator.param.yaml b/perception/detected_object_validation/config/occupancy_grid_based_validator.param.yaml
index fc5c634735e23..073c148b21910 100644
--- a/perception/detected_object_validation/config/occupancy_grid_based_validator.param.yaml
+++ b/perception/detected_object_validation/config/occupancy_grid_based_validator.param.yaml
@@ -1,3 +1,5 @@
 /**:
   ros__parameters:
+    mean_threshold: 0.6
     enable_debug: false
+    
diff --git a/perception/detected_object_validation/launch/object_lanelet_filter.launch.xml b/perception/detected_object_validation/launch/object_lanelet_filter.launch.xml
index 2cccc4f3bb526..8f16fbc7ed57e 100644
--- a/perception/detected_object_validation/launch/object_lanelet_filter.launch.xml
+++ b/perception/detected_object_validation/launch/object_lanelet_filter.launch.xml
@@ -1,14 +1,13 @@
-<?xml version="1.0"?>
+<?xml version="1.0" encoding="UTF-8"?>
 <launch>
-  <arg name="vector_map_topic" default="/map/vector_map"/>
-  <arg name="input/object" default="in_objects"/>
-  <arg name="output/object" default="out_objects"/>
-  <arg name="filtering_range_param" default="$(find-pkg-share detected_object_validation)/config/object_lanelet_filter.param.yaml"/>
-
-  <node pkg="detected_object_validation" exec="object_lanelet_filter_node" name="object_lanelet_filter" output="screen">
-    <remap from="input/vector_map" to="$(var vector_map_topic)"/>
-    <remap from="input/object" to="$(var input/object)"/>
-    <remap from="output/object" to="$(var output/object)"/>
-    <param from="$(var filtering_range_param)"/>
-  </node>
+	<arg name="object_lanelet_filter_param_file" default="$(find-pkg-share detected_object_validation)/config/object_lanelet_filter.param.yaml" />
+	<arg name="vector_map_topic" default="/map/vector_map" />
+	<arg name="input/object" default="in_objects" />
+	<arg name="output/object" default="out_objects" />
+	<node pkg="detected_object_validation" exec="object_lanelet_filter_node" name="object_lanelet_filter" output="screen">
+		<remap from="input/vector_map" to="$(var vector_map_topic)" />
+		<remap from="input/object" to="$(var input/object)" />
+		<remap from="output/object" to="$(var output/object)" />
+		<param from="$(var object_lanelet_filter_param_file)" />
+	</node>
 </launch>
diff --git a/perception/detected_object_validation/launch/object_position_filter.launch.xml b/perception/detected_object_validation/launch/object_position_filter.launch.xml
index 49aae282aa3c3..a744aab94661b 100644
--- a/perception/detected_object_validation/launch/object_position_filter.launch.xml
+++ b/perception/detected_object_validation/launch/object_position_filter.launch.xml
@@ -1,12 +1,11 @@
-<?xml version="1.0"?>
+<?xml version="1.0" encoding="UTF-8"?>
 <launch>
-  <arg name="input/object" default="in_objects"/>
-  <arg name="output/object" default="out_objects"/>
-  <arg name="filtering_range_param" default="$(find-pkg-share detected_object_validation)/config/object_position_filter.param.yaml"/>
-
-  <node pkg="detected_object_validation" exec="object_position_filter_node" name="object_position_filter" output="screen">
-    <remap from="input/object" to="$(var input/object)"/>
-    <remap from="output/object" to="$(var output/object)"/>
-    <param from="$(var filtering_range_param)"/>
-  </node>
+	<arg name="object_position_filter_param_file" default="$(find-pkg-share detected_object_validation)/config/object_position_filter.param.yaml" />
+	<arg name="input/object" default="in_objects" />
+	<arg name="output/object" default="out_objects" />
+	<node pkg="detected_object_validation" exec="object_position_filter_node" name="object_position_filter" output="screen">
+		<remap from="input/object" to="$(var input/object)" />
+		<remap from="output/object" to="$(var output/object)" />
+		<param from="$(var object_position_filter_param_file)" />
+	</node>
 </launch>
diff --git a/perception/detected_object_validation/launch/obstacle_pointcloud_based_validator.launch.xml b/perception/detected_object_validation/launch/obstacle_pointcloud_based_validator.launch.xml
index a1d941e66db4b..fe5690699ac42 100644
--- a/perception/detected_object_validation/launch/obstacle_pointcloud_based_validator.launch.xml
+++ b/perception/detected_object_validation/launch/obstacle_pointcloud_based_validator.launch.xml
@@ -1,14 +1,13 @@
 <?xml version="1.0" encoding="UTF-8"?>
 <launch>
-  <arg name="input/detected_objects" default="/perception/object_recognition/detection/objects"/>
-  <arg name="input/obstacle_pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>
-  <arg name="output/objects" default="/perception/object_recognition/detection/validation/obstacle_pointcloud_based/objects"/>
-  <arg name="obstacle_pointcloud_based_validator_param_path" default="$(find-pkg-share detected_object_validation)/config/obstacle_pointcloud_based_validator.param.yaml"/>
-
-  <node pkg="detected_object_validation" exec="obstacle_pointcloud_based_validator_node" name="obstacle_pointcloud_based_validator_node" output="screen">
-    <remap from="~/input/detected_objects" to="$(var input/detected_objects)"/>
-    <remap from="~/input/obstacle_pointcloud" to="$(var input/obstacle_pointcloud)"/>
-    <remap from="~/output/objects" to="$(var output/objects)"/>
-    <param from="$(var obstacle_pointcloud_based_validator_param_path)"/>
-  </node>
+	<arg name="obstacle_pointcloud_based_validator_param_file" default="$(find-pkg-share detected_object_validation)/config/obstacle_pointcloud_based_validator.param.yaml" />
+	<arg name="input/detected_objects" default="/perception/object_recognition/detection/objects" />
+	<arg name="input/obstacle_pointcloud" default="/perception/obstacle_segmentation/pointcloud" />
+	<arg name="output/objects" default="/perception/object_recognition/detection/validation/obstacle_pointcloud_based/objects" />
+	<node pkg="detected_object_validation" exec="obstacle_pointcloud_based_validator_node" name="obstacle_pointcloud_based_validator_node" output="screen">
+		<remap from="~/input/detected_objects" to="$(var input/detected_objects)" />
+		<remap from="~/input/obstacle_pointcloud" to="$(var input/obstacle_pointcloud)" />
+		<remap from="~/output/objects" to="$(var output/objects)" />
+		<param from="$(var obstacle_pointcloud_based_validator_param_file)" />
+	</node>
 </launch>
diff --git a/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml b/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml
index 3acb1f2d1907a..de09ae71a5f4d 100644
--- a/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml
+++ b/perception/detected_object_validation/launch/occupancy_grid_based_validator.launch.xml
@@ -1,28 +1,25 @@
 <?xml version="1.0" encoding="UTF-8"?>
 <launch>
-  <arg name="input/detected_objects" default="/perception/object_recognition/detection/objects"/>
-  <arg name="output/objects" default="/perception/object_recognition/detection/validation/occupancy_grid_based/objects"/>
-
-  <arg name="input/laserscan" default="/perception/occupancy_grid_map/virtual_scan/laserscan"/>
-  <arg name="input/occupancy_grid_map" default="/perception/object_recognition/detection/validation/occupancy_grid_based/single_frame_occupancy_grid_map"/>
-  <arg name="occupancy_grid_map_param_path" default="$(find-pkg-share probabilistic_occupancy_grid_map)/config/laserscan_based_occupancy_grid_map.param.yaml"/>
-  <arg name="occupancy_grid_map_updater_param_path" default="$(find-pkg-share probabilistic_occupancy_grid_map)/config/binary_bayes_filter_updater.param.yaml"/>
-  <arg name="occupancy_grid_based_validator_param_path" default="$(find-pkg-share detected_object_validation)/config/occupancy_grid_based_validator_param_path.param.yaml"/>
-
-  <node pkg="probabilistic_occupancy_grid_map" exec="laserscan_based_occupancy_grid_map_node" name="single_frame_laserscan_occupancy_grid_map" output="screen">
-    <remap from="~/input/laserscan" to="$(var input/laserscan)"/>
-    <remap from="~/output/occupancy_grid_map" to="$(var input/occupancy_grid_map)"/>
-    <param name="input_obstacle_pointcloud" value="false"/>
-    <param name="input_obstacle_and_raw_pointcloud" value="false"/>
-    <param name="updater_type" value="binary_bayes_filter"/>
-    <param from="$(var occupancy_grid_map_param_path)"/>
-    <param from="$(var occupancy_grid_map_updater_param_path)"/>
-  </node>
-
-  <node pkg="detected_object_validation" exec="occupancy_grid_based_validator_node" name="occupancy_grid_based_validator_node" output="screen">
-    <remap from="~/input/detected_objects" to="$(var input/detected_objects)"/>
-    <remap from="~/input/occupancy_grid_map" to="$(var input/occupancy_grid_map)"/>
-    <remap from="~/output/objects" to="$(var output/objects)"/>
-    <param from="$(var occupancy_grid_based_validator_param_path)"/>
-  </node>
+	<arg name="occupancy_grid_based_validator_param_file" default="$(find-pkg-share detected_object_validation)/config/occupancy_grid_based_validator.param.yaml" />
+	<arg name="input/detected_objects" default="/perception/object_recognition/detection/objects" />
+	<arg name="output/objects" default="/perception/object_recognition/detection/validation/occupancy_grid_based/objects" />
+	<arg name="input/laserscan" default="/perception/occupancy_grid_map/virtual_scan/laserscan" />
+	<arg name="input/occupancy_grid_map" default="/perception/object_recognition/detection/validation/occupancy_grid_based/single_frame_occupancy_grid_map" />
+	<arg name="occupancy_grid_map_param_path" default="$(find-pkg-share probabilistic_occupancy_grid_map)/config/laserscan_based_occupancy_grid_map.param.yaml" />
+	<arg name="occupancy_grid_map_updater_param_path" default="$(find-pkg-share probabilistic_occupancy_grid_map)/config/binary_bayes_filter_updater.param.yaml" />
+	<node pkg="probabilistic_occupancy_grid_map" exec="laserscan_based_occupancy_grid_map_node" name="single_frame_laserscan_occupancy_grid_map" output="screen">
+		<remap from="~/input/laserscan" to="$(var input/laserscan)" />
+		<remap from="~/output/occupancy_grid_map" to="$(var input/occupancy_grid_map)" />
+		<param name="input_obstacle_pointcloud" value="false" />
+		<param name="input_obstacle_and_raw_pointcloud" value="false" />
+		<param name="updater_type" value="binary_bayes_filter" />
+		<param from="$(var occupancy_grid_map_param_path)" />
+		<param from="$(var occupancy_grid_map_updater_param_path)" />
+	</node>
+	<node pkg="detected_object_validation" exec="occupancy_grid_based_validator_node" name="occupancy_grid_based_validator_node" output="screen">
+		<remap from="~/input/detected_objects" to="$(var input/detected_objects)" />
+		<remap from="~/input/occupancy_grid_map" to="$(var input/occupancy_grid_map)" />
+		<remap from="~/output/objects" to="$(var output/objects)" />
+		<param from="$(var occupancy_grid_based_validator_param_file)" />
+	</node>
 </launch>
diff --git a/perception/detected_object_validation/schema/object_lanelet_filter.schema.json b/perception/detected_object_validation/schema/object_lanelet_filter.schema.json
new file mode 100644
index 0000000000000..a08c71a55a020
--- /dev/null
+++ b/perception/detected_object_validation/schema/object_lanelet_filter.schema.json
@@ -0,0 +1,121 @@
+{
+  "$schema": "http://json-schema.org/draft-07/schema#",
+  "title": "Parameters for Object Lanelet Filter",
+  "type": "object",
+  "definitions": {
+    "object_lanelet_filter": {
+      "type": "object",
+      "properties": {
+        "filter_target_label": {
+          "type": "object",
+          "properties": {
+            "UNKNOWN": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, unknown objects are filtered."
+            },
+            "CAR": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, car objects are filtered."
+            },
+            "TRUCK": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, truck objects are filtered."
+            },
+            "BUS": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, bus objects are filtered."
+            },
+            "TRAILER": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, trailer objects are filtered."
+            },
+            "MOTORCYCLE": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, motorcycle objects are filtered."
+            },
+            "BICYCLE": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, bicycle objects are filtered."
+            },
+            "PEDESTRIAN": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, pedestrian objects are filtered."
+            }
+          },
+          "required": [
+            "UNKNOWN",
+            "CAR",
+            "TRUCK",
+            "BUS",
+            "TRAILER",
+            "MOTORCYCLE",
+            "BICYCLE",
+            "PEDESTRIAN"
+          ]
+        },
+        "filter_settings": {
+          "type": "object",
+          "properties": {
+            "polygon_overlap_filter": {
+              "type": "object",
+              "properties": {
+                "enabled": {
+                  "type": "boolean",
+                  "default": true,
+                  "description": "If true, objects that are not in the lanelet polygon are filtered."
+                }
+              },
+              "required": ["enabled"]
+            },
+            "lanelet_direction_filter": {
+              "type": "object",
+              "properties": {
+                "enabled": {
+                  "type": "boolean",
+                  "default": false,
+                  "description": "If true, objects that are not in the same direction as the lanelet are filtered."
+                },
+                "velocity_yaw_threshold": {
+                  "type": "number",
+                  "default": 0.785398,
+                  "description": "If the yaw difference between the object and the lanelet is greater than this value, the object is filtered."
+                },
+                "object_speed_threshold": {
+                  "type": "number",
+                  "default": 3.0,
+                  "description": "If the object speed is greater than this value, the object is filtered."
+                }
+              },
+              "required": ["enabled", "velocity_yaw_threshold", "object_speed_threshold"]
+            }
+          },
+          "required": ["polygon_overlap_filter", "lanelet_direction_filter"]
+        }
+      },
+      "required": ["filter_target_label", "filter_settings"],
+      "additionalProperties": false
+    }
+  },
+  "properties": {
+    "/**": {
+      "type": "object",
+      "properties": {
+        "ros__parameters": {
+          "$ref": "#/definitions/object_lanelet_filter"
+        }
+      },
+      "required": ["ros__parameters"],
+      "additionalProperties": false
+    }
+  },
+  "required": ["/**"],
+  "additionalProperties": false
+}
diff --git a/perception/detected_object_validation/schema/object_position_filter.schema.json b/perception/detected_object_validation/schema/object_position_filter.schema.json
new file mode 100644
index 0000000000000..c9e7c29e9a109
--- /dev/null
+++ b/perception/detected_object_validation/schema/object_position_filter.schema.json
@@ -0,0 +1,109 @@
+{
+  "$schema": "http://json-schema.org/draft-07/schema#",
+  "title": "Parameters for Object Position Filter",
+  "type": "object",
+  "definitions": {
+    "object_position_filter": {
+      "type": "object",
+      "properties": {
+        "upper_bound_x": {
+          "type": "number",
+          "default": 100.0,
+          "description": "Bound for filtering. Only used if filter_by_xy_position is true"
+        },
+        "upper_bound_y": {
+          "type": "number",
+          "default": 50.0,
+          "description": "Bound for filtering. Only used if filter_by_xy_position is true"
+        },
+        "lower_bound_x": {
+          "type": "number",
+          "default": 0.0,
+          "description": "Bound for filtering. Only used if filter_by_xy_position is true"
+        },
+        "lower_bound_y": {
+          "type": "number",
+          "default": -50.0,
+          "description": "Bound for filtering. Only used if filter_by_xy_position is true"
+        },
+        "filter_target_label": {
+          "type": "object",
+          "properties": {
+            "UNKNOWN": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, unknown objects are filtered."
+            },
+            "CAR": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, car objects are filtered."
+            },
+            "TRUCK": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, truck objects are filtered."
+            },
+            "BUS": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, bus objects are filtered."
+            },
+            "TRAILER": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, trailer objects are filtered."
+            },
+            "MOTORCYCLE": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, motorcycle objects are filtered."
+            },
+            "BICYCLE": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, bicycle objects are filtered."
+            },
+            "PEDESTRIAN": {
+              "type": "boolean",
+              "default": false,
+              "description": "If true, pedestrian objects are filtered."
+            }
+          },
+          "required": [
+            "UNKNOWN",
+            "CAR",
+            "TRUCK",
+            "BUS",
+            "TRAILER",
+            "MOTORCYCLE",
+            "BICYCLE",
+            "PEDESTRIAN"
+          ]
+        }
+      },
+      "required": [
+        "upper_bound_x",
+        "upper_bound_y",
+        "lower_bound_x",
+        "lower_bound_y",
+        "filter_target_label"
+      ],
+      "additionalProperties": false
+    }
+  },
+  "properties": {
+    "/**": {
+      "type": "object",
+      "properties": {
+        "ros__parameters": {
+          "$ref": "#/definitions/object_position_filter"
+        }
+      },
+      "required": ["ros__parameters"],
+      "additionalProperties": false
+    }
+  },
+  "required": ["/**"],
+  "additionalProperties": false
+}
diff --git a/perception/detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json b/perception/detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json
new file mode 100644
index 0000000000000..468cb237a24b9
--- /dev/null
+++ b/perception/detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json
@@ -0,0 +1,68 @@
+{
+  "$schema": "http://json-schema.org/draft-07/schema#",
+  "title": "Parameters for Obstacle Pointcloud Based Validator",
+  "type": "object",
+  "definitions": {
+    "obstacle_pointcloud_based_validator": {
+      "type": "object",
+      "properties": {
+        "min_points_num": {
+          "type": "array",
+          "items": {
+            "type": "integer"
+          },
+          "default": [10, 10, 10, 10, 10, 10, 10, 10],
+          "description": "The minimum number of obstacle point clouds in DetectedObjects"
+        },
+        "max_points_num": {
+          "type": "array",
+          "items": {
+            "type": "integer"
+          },
+          "default": [10, 10, 10, 10, 10, 10, 10, 10],
+          "description": "The max number of obstacle point clouds in DetectedObjects"
+        },
+        "min_points_and_distance_ratio": {
+          "type": "array",
+          "items": {
+            "type": "integer"
+          },
+          "default": [800, 800, 800, 800, 800, 800, 800, 800],
+          "description": "Threshold value of the number of point clouds per object when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink."
+        },
+        "using_2d_validator": {
+          "type": "boolean",
+          "default": false,
+          "description": "The xy-plane projected (2D) obstacle point clouds will be used for validation"
+        },
+        "enable_debugger": {
+          "type": "boolean",
+          "default": false,
+          "description": "Whether to create debug topics or not?"
+        }
+      },
+      "required": [
+        "min_points_num",
+        "max_points_num",
+        "min_points_and_distance_ratio",
+        "using_2d_validator",
+        "enable_debugger"
+      ],
+      "additionalProperties": false
+    }
+  },
+  "properties": {
+    "/**": {
+      "type": "object",
+      "properties": {
+        "ros__parameters": {
+          "$ref": "#/definitions/obstacle_pointcloud_based_validator"
+        }
+      },
+      "required": ["ros__parameters"],
+      "additionalProperties": false
+    }
+  },
+  "required": ["/**"],
+  "additionalProperties": false
+}
diff --git a/perception/detected_object_validation/schema/occupancy_grid_based_validator.schema.json b/perception/detected_object_validation/schema/occupancy_grid_based_validator.schema.json
new file mode 100644
index 0000000000000..a792a1e817ab9
--- /dev/null
+++ b/perception/detected_object_validation/schema/occupancy_grid_based_validator.schema.json
@@ -0,0 +1,41 @@
+{
+  "$schema": "http://json-schema.org/draft-07/schema#",
+  "title": "Parameters for Occupancy Grid Based Validator",
+  "type": "object",
+  "definitions": {
+    "occupancy_grid_based_validator": {
+      "type": "object",
+      "properties": {
+        "mean_threshold": {
+          "type": "number",
+          "default": 0.6,
+          "description": "The percentage threshold of allowed non-freespace."
+        },
+        "enable_debug": {
+          "type": "boolean",
+          "default": false,
+          "description": "Whether to display debug images or not?"
+        }
+      },
+      "required": [
+        "mean_threshold",
+        "enable_debug"
+      ],
+      "additionalProperties": false
+    }
+  },
+  "properties": {
+    "/**": {
+      "type": "object",
+      "properties": {
+        "ros__parameters": {
+          "$ref": "#/definitions/occupancy_grid_based_validator"
+        }
+      },
+      "required": ["ros__parameters"],
+      "additionalProperties": false
+    }
+  },
+  "required": ["/**"],
+  "additionalProperties": false
+}
diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp
index d1ba34f4a61b2..c9fc561879a2d 100644
--- a/perception/detected_object_validation/src/object_lanelet_filter.cpp
+++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp
@@ -35,14 +35,14 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod
   using std::placeholders::_1;
 
   // Set parameters
-  filter_target_.UNKNOWN = declare_parameter<bool>("filter_target_label.UNKNOWN", false);
-  filter_target_.CAR = declare_parameter<bool>("filter_target_label.CAR", false);
-  filter_target_.TRUCK = declare_parameter<bool>("filter_target_label.TRUCK", false);
-  filter_target_.BUS = declare_parameter<bool>("filter_target_label.BUS", false);
-  filter_target_.TRAILER = declare_parameter<bool>("filter_target_label.TRAILER", false);
-  filter_target_.MOTORCYCLE = declare_parameter<bool>("filter_target_label.MOTORCYCLE", false);
-  filter_target_.BICYCLE = declare_parameter<bool>("filter_target_label.BICYCLE", false);
-  filter_target_.PEDESTRIAN = declare_parameter<bool>("filter_target_label.PEDESTRIAN", false);
+  filter_target_.UNKNOWN = declare_parameter<bool>("filter_target_label.UNKNOWN");
+  filter_target_.CAR = declare_parameter<bool>("filter_target_label.CAR");
+  filter_target_.TRUCK = declare_parameter<bool>("filter_target_label.TRUCK");
+  filter_target_.BUS = declare_parameter<bool>("filter_target_label.BUS");
+  filter_target_.TRAILER = declare_parameter<bool>("filter_target_label.TRAILER");
+  filter_target_.MOTORCYCLE = declare_parameter<bool>("filter_target_label.MOTORCYCLE");
+  filter_target_.BICYCLE = declare_parameter<bool>("filter_target_label.BICYCLE");
+  filter_target_.PEDESTRIAN = declare_parameter<bool>("filter_target_label.PEDESTRIAN");
   // Set filter settings
   filter_settings_.polygon_overlap_filter =
     declare_parameter<bool>("filter_settings.polygon_overlap_filter.enabled");
diff --git a/perception/detected_object_validation/src/object_position_filter.cpp b/perception/detected_object_validation/src/object_position_filter.cpp
index dccff8a6ccc67..a1aa64cb48dc6 100644
--- a/perception/detected_object_validation/src/object_position_filter.cpp
+++ b/perception/detected_object_validation/src/object_position_filter.cpp
@@ -24,18 +24,18 @@ ObjectPositionFilterNode::ObjectPositionFilterNode(const rclcpp::NodeOptions & n
   using std::placeholders::_1;
 
   // Set parameters
-  upper_bound_x_ = declare_parameter<float>("upper_bound_x", 100.0);
-  upper_bound_y_ = declare_parameter<float>("upper_bound_y", 50.0);
-  lower_bound_x_ = declare_parameter<float>("lower_bound_x", 0.0);
-  lower_bound_y_ = declare_parameter<float>("lower_bound_y", -50.0);
-  filter_target_.UNKNOWN = declare_parameter<bool>("filter_target_label.UNKNOWN", false);
-  filter_target_.CAR = declare_parameter<bool>("filter_target_label.CAR", false);
-  filter_target_.TRUCK = declare_parameter<bool>("filter_target_label.TRUCK", false);
-  filter_target_.BUS = declare_parameter<bool>("filter_target_label.BUS", false);
-  filter_target_.TRAILER = declare_parameter<bool>("filter_target_label.TRAILER", false);
-  filter_target_.MOTORCYCLE = declare_parameter<bool>("filter_target_label.MOTORCYCLE", false);
-  filter_target_.BICYCLE = declare_parameter<bool>("filter_target_label.BICYCLE", false);
-  filter_target_.PEDESTRIAN = declare_parameter<bool>("filter_target_label.PEDESTRIAN", false);
+  upper_bound_x_ = declare_parameter<float>("upper_bound_x");
+  upper_bound_y_ = declare_parameter<float>("upper_bound_y");
+  lower_bound_x_ = declare_parameter<float>("lower_bound_x");
+  lower_bound_y_ = declare_parameter<float>("lower_bound_y");
+  filter_target_.UNKNOWN = declare_parameter<bool>("filter_target_label.UNKNOWN");
+  filter_target_.CAR = declare_parameter<bool>("filter_target_label.CAR");
+  filter_target_.TRUCK = declare_parameter<bool>("filter_target_label.TRUCK");
+  filter_target_.BUS = declare_parameter<bool>("filter_target_label.BUS");
+  filter_target_.TRAILER = declare_parameter<bool>("filter_target_label.TRAILER");
+  filter_target_.MOTORCYCLE = declare_parameter<bool>("filter_target_label.MOTORCYCLE");
+  filter_target_.BICYCLE = declare_parameter<bool>("filter_target_label.BICYCLE");
+  filter_target_.PEDESTRIAN = declare_parameter<bool>("filter_target_label.PEDESTRIAN");
 
   // Set publisher/subscriber
   object_sub_ = this->create_subscription<autoware_perception_msgs::msg::DetectedObjects>(
diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp
index fbb3f863be7c4..9eb79a2994ba8 100644
--- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp
+++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp
@@ -307,7 +307,7 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator(
   debug_publisher_ = std::make_unique<autoware::universe_utils::DebugPublisher>(
     this, "obstacle_pointcloud_based_validator");
 
-  const bool enable_debugger = declare_parameter<bool>("enable_debugger", false);
+  const bool enable_debugger = declare_parameter<bool>("enable_debugger");
   if (enable_debugger) debugger_ = std::make_shared<Debugger>(this);
   published_time_publisher_ =
     std::make_unique<autoware::universe_utils::PublishedTimePublisher>(this);
diff --git a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp
index b8682a6e56b3b..5538ce0dc7733 100644
--- a/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp
+++ b/perception/detected_object_validation/src/occupancy_grid_based_validator.cpp
@@ -50,8 +50,8 @@ OccupancyGridBasedValidator::OccupancyGridBasedValidator(const rclcpp::NodeOptio
   objects_pub_ = create_publisher<autoware_perception_msgs::msg::DetectedObjects>(
     "~/output/objects", rclcpp::QoS{1});
 
-  mean_threshold_ = declare_parameter<float>("mean_threshold", 0.6);
-  enable_debug_ = declare_parameter<bool>("enable_debug", false);
+  mean_threshold_ = declare_parameter<float>("mean_threshold");
+  enable_debug_ = declare_parameter<bool>("enable_debug");
   published_time_publisher_ =
     std::make_unique<autoware::universe_utils::PublishedTimePublisher>(this);
 }