diff --git a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
index ad6217663f..58bca93758 100644
--- a/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
+++ b/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml
@@ -3,8 +3,8 @@
delay_compensation_time: 0.17
enable_smooth_stop: true
- enable_overshoot_emergency: true
- enable_large_tracking_error_emergency: true
+ enable_overshoot_emergency: false
+ enable_large_tracking_error_emergency: false
enable_slope_compensation: true
enable_keep_stopped_until_steer_convergence: true
diff --git a/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml
index 70afd9d31b..1e9e1d63f0 100644
--- a/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/object_filter/object_position_filter.param.yaml
@@ -10,7 +10,7 @@
BICYCLE : false
PEDESTRIAN : false
- upper_bound_x: 100.0
+ upper_bound_x: 50.0
lower_bound_x: 0.0
upper_bound_y: 10.0
lower_bound_y: -10.0
diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml
index 69328a9b79..ad471ce323 100644
--- a/autoware_launch/config/planning/preset/default_preset.yaml
+++ b/autoware_launch/config/planning/preset/default_preset.yaml
@@ -43,7 +43,7 @@ launch:
default: "true"
- arg:
name: launch_traffic_light_module
- default: "true"
+ default: "false"
- arg:
name: launch_intersection_module
default: "true"
@@ -73,7 +73,7 @@ launch:
default: "true"
- arg:
name: launch_speed_bump_module
- default: "false"
+ default: "true"
- arg:
name: launch_out_of_lane_module
default: "true"
@@ -100,7 +100,7 @@ launch:
- arg:
name: motion_stop_planner_type
- default: obstacle_stop_planner
+ default: obstacle_cruise_planner
# option: obstacle_stop_planner
# obstacle_cruise_planner
# none
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml
index ef61bdb743..aadef7200f 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/speed_bump.param.yaml
@@ -9,5 +9,5 @@
speed_calculation:
min_height: 0.05 # [m]
max_height: 0.30 # [m]
- min_speed: 1.39 # [m/s] = [5 kph]
- max_speed: 2.78 # [m/s] = [10 kph]
+ min_speed: 2.5 # [m/s] = [9 kph]
+ max_speed: 3.34 # [m/s] = [12 kph]
diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml
index a5daf3dd16..d5d4d712e2 100644
--- a/autoware_launch/launch/autoware.launch.xml
+++ b/autoware_launch/launch/autoware.launch.xml
@@ -39,10 +39,10 @@
-
+
-
+
diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml
index 3ccd98104d..72302f1ff7 100644
--- a/autoware_launch/launch/components/tier4_localization_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml
@@ -3,6 +3,7 @@
+
-
+