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/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml
deleted file mode 100644
index 3ff32bfbb7..0000000000
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid.param.yaml
+++ /dev/null
@@ -1,7 +0,0 @@
-/**:
- ros__parameters:
- input_frame: base_link
- output_frame: base_link
- voxel_size_x: 0.15
- voxel_size_y: 0.15
- voxel_size_z: 0.15
diff --git a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
index 2f3de2b789..26b027f007 100644
--- a/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/clustering/voxel_grid_based_euclidean_cluster.param.yaml
@@ -7,9 +7,11 @@
max_cluster_size: 3000
use_height: false
input_frame: "base_link"
- max_x: 70.0
- min_x: -70.0
- max_y: 70.0
- min_y: -70.0
- max_z: 4.5
- min_z: -4.5
+
+ # low height crop box filter param
+ max_x: 200.0
+ min_x: -200.0
+ max_y: 200.0
+ min_y: -200.0
+ max_z: 2.0
+ min_z: -10.0
diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
index 0423217582..62b3074c15 100644
--- a/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_filter/pointcloud_map_filter.param.yaml
@@ -1,7 +1,5 @@
/**:
ros__parameters:
- # use downsample filter before compare map
- use_down_sample_filter: False
# voxel size for downsample filter
down_sample_voxel_size: 0.1
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index dd39fb2141..97dee38d66 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -29,16 +29,11 @@
-
-