diff --git a/autoware_launch/config/localization/ar_tag_based_localizer.param.yaml b/autoware_launch/config/localization/ar_tag_based_localizer.param.yaml
new file mode 100644
index 0000000000..e8f9016537
--- /dev/null
+++ b/autoware_launch/config/localization/ar_tag_based_localizer.param.yaml
@@ -0,0 +1,40 @@
+/**:
+ ros__parameters:
+ # marker_size
+ marker_size: 0.6
+
+ # target_tag_ids
+ target_tag_ids: ['0','1','2','3','4','5','6']
+
+ # base_covariance
+ # This value is dynamically scaled according to the distance at which AR tags are detected.
+ base_covariance: [0.2, 0.0, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 0.2, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.2, 0.0, 0.0, 0.0,
+ 0.0, 0.0, 0.0, 0.02, 0.0, 0.0,
+ 0.0, 0.0, 0.0, 0.0, 0.02, 0.0,
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.02]
+
+ # Detect AR-Tags within this range and publish the pose of ego vehicle
+ distance_threshold: 13.0 # [m]
+
+ # consider_orientation
+ consider_orientation: false
+
+ # Detector parameters
+ # See https://github.com/pal-robotics/aruco_ros/blob/7787a6794d30c248bc546d1582e65dd47bc40c12/aruco/include/aruco/markerdetector.h#L106-L126
+ detection_mode: "DM_NORMAL" # select from [DM_NORMAL, DM_FAST, DM_VIDEO_FAST]
+ min_marker_size: 0.02
+
+ # Parameters for comparison with EKF Pose
+ # If the difference between the EKF pose and the current pose is within the range of values set below, the current pose is published.
+ # [How to determine the value]
+ # * ekf_time_tolerance: Since it is abnormal if the data comes too old from EKF, the tentative tolerance value is set at 5 seconds.
+ # This value is assumed to be unaffected even if it is increased or decreased by some amount.
+ # * ekf_position_tolerance: Since it is possible that multiple AR tags with the same ID could be placed, the tolerance should be as small as possible.
+ # And if the vehicle is running only on odometry in a section without AR tags,
+ # it is possible that self-position estimation could be off by a few meters.
+ # it should be fixed by AR tag detection, so tolerance should not be smaller than 10 meters.
+ # Therefore, the tolerance is set at 10 meters.
+ ekf_time_tolerance: 5.0 # [s]
+ ekf_position_tolerance: 10.0 # [m]
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
index 6d82e7790d..66542e1bf1 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/goal_planner/goal_planner.param.yaml
@@ -39,6 +39,9 @@
object_recognition_collision_check_max_extra_stopping_margin: 1.0
th_moving_object_velocity: 1.0
detection_bound_offset: 15.0
+ outer_road_detection_offset: 1.0
+ inner_road_detection_offset: 0.0
+
# pull over
pull_over:
diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
index 8e42255f67..6de22a67dc 100644
--- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
+++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml
@@ -41,7 +41,7 @@
ego_pass_first_margin_y: [3.0] # [[s]] time to vehicle margin vector for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition)
ego_pass_first_additional_margin: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering
ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
- ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
+ ego_pass_later_margin_y: [13.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition)
ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering
no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk
diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml
index c5117009d2..3ccd98104d 100644
--- a/autoware_launch/launch/components/tier4_localization_component.launch.xml
+++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml
@@ -52,6 +52,9 @@
+
+
+
diff --git a/autoware_launch/launch/planning_simulator.launch.xml b/autoware_launch/launch/planning_simulator.launch.xml
index cf56413121..63443c928f 100644
--- a/autoware_launch/launch/planning_simulator.launch.xml
+++ b/autoware_launch/launch/planning_simulator.launch.xml
@@ -13,6 +13,8 @@
+
+