diff --git a/autoware_launch/config/perception/object_recognition/detection/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/roi_sync.param.yaml
new file mode 100644
index 0000000000..21ba13787f
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/roi_sync.param.yaml
@@ -0,0 +1,5 @@
+/**:
+ ros__parameters:
+ input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0]
+ timeout_ms: 70.0
+ match_threshold_ms: 50.0
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml
index 68000747b7..bd1ccd2065 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_out/pull_out.param.yaml
@@ -4,15 +4,16 @@
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
+ th_blinker_on_lateral_offset: 1.0
collision_check_margin: 1.0
collision_check_distance_from_end: 1.0
# shift pull out
enable_shift_pull_out: true
shift_pull_out_velocity: 2.0
pull_out_sampling_num: 4
- minimum_shift_pull_out_distance: 20.0
+ minimum_shift_pull_out_distance: 0.0
maximum_lateral_jerk: 2.0
- minimum_lateral_jerk: 0.5
+ minimum_lateral_jerk: 0.1
deceleration_interval: 15.0
# geometric pull out
enable_geometric_pull_out: true
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
index af82a3461f..2e53b5d246 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/rtc_auto_mode_manager/rtc_auto_mode_manager.param.yaml
@@ -7,8 +7,6 @@
- "intersection"
- "no_stopping_area"
- "traffic_light"
- - "external_request_lane_change_left"
- - "external_request_lane_change_right"
- "lane_change_left"
- "lane_change_right"
- "avoidance_left"
diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml
index c0c2e4fc4c..4417dba4d8 100644
--- a/autoware_launch/launch/components/tier4_perception_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml
@@ -21,6 +21,7 @@
name="object_recognition_detection_pointcloud_map_filter_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml"
/>
+