diff --git a/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml
new file mode 100644
index 0000000000..cf4f73dc79
--- /dev/null
+++ b/autoware_launch/config/planning/scenario_planning/common/costmap_generator.param.yaml
@@ -0,0 +1,22 @@
+/**:
+ ros__parameters:
+ costmap_frame: "map"
+ vehicle_frame: "base_link"
+ map_frame: "map"
+ update_rate: 10.0
+ activate_by_scenario: False
+ grid_min_value: 0.0
+ grid_max_value: 1.0
+ grid_resolution: 0.2
+ grid_length_x: 70.0
+ grid_length_y: 70.0
+ grid_position_x: 0.0
+ grid_position_y: 0.0
+ maximum_lidar_height_thres: 0.3
+ minimum_lidar_height_thres: -2.2
+ use_wayarea: true
+ use_parkinglot: true
+ use_objects: true
+ use_points: true
+ expand_polygon_size: 1.0
+ size_of_expansion_kernel: 9
diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml
index 7a21273131..5f14006f7a 100644
--- a/autoware_launch/launch/components/tier4_planning_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml
@@ -17,6 +17,9 @@
+
+
+
@@ -25,6 +28,7 @@
+