diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml
index 595cd8187609fc277934fa076010aceb73c5b01d..d8c522f305621fcc809ac17213263301dbc7bd0b 100644
--- a/nav2_bringup/bringup/params/nav2_params.yaml
+++ b/nav2_bringup/bringup/params/nav2_params.yaml
@@ -112,15 +112,15 @@ local_costmap:
       inflation_layer.cost_scaling_factor: 3.0
       obstacle_layer:
         enabled: True
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
       static_layer:
         map_subscribe_transient_local: True
       always_send_full_costmap: True
       observation_sources: scan
-      scan:
-        topic: /scan
-        max_obstacle_height: 2.0
-        clearing: True
-        marking: True
   local_costmap_client:
     ros__parameters:
       use_sim_time: True
@@ -135,15 +135,15 @@ global_costmap:
       robot_radius: 0.22
       obstacle_layer:
         enabled: True
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
       static_layer:
         map_subscribe_transient_local: True
       always_send_full_costmap: True
       observation_sources: scan
-      scan:
-        topic: /scan
-        max_obstacle_height: 2.0
-        clearing: True
-        marking: True
   global_costmap_client:
     ros__parameters:
       use_sim_time: True