diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml
deleted file mode 100644
index 3dd303464a..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/compare_map.param.yaml
+++ /dev/null
@@ -1,20 +0,0 @@
-/**:
- ros__parameters:
-
- # distance threshold for compare compare
- distance_threshold: 0.5
-
- # publish voxelized map pointcloud for debug
- publish_debug_pcd: False
-
- # use dynamic map loading
- use_dynamic_map_loading: True
-
- # time interval to check dynamic map loading
- timer_interval_ms: 100
-
- # distance threshold for dynamic map update
- map_update_distance_threshold: 10.0
-
- # radius map for dynamic map loading
- map_loader_radius: 150.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml
deleted file mode 100644
index 1962fba1f3..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/outlier.param.yaml
+++ /dev/null
@@ -1,8 +0,0 @@
-/**:
- ros__parameters:
- input_frame: base_link
- output_frame: base_link
- voxel_size_x: 0.3
- voxel_size_y: 0.3
- voxel_size_z: 100.0
- voxel_points_threshold: 3
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index 65b8ac20bd..580b8b81a4 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -21,16 +21,11 @@
-
-