diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml
index 2cd493a5687eaf3caac95dd69dadd491dcb3d244..d8acf8ae94b02b605c614e494db2ed1295349bcd 100644
--- a/nav2_bringup/params/nav2_params.yaml
+++ b/nav2_bringup/params/nav2_params.yaml
@@ -51,6 +51,10 @@ bt_navigator:
     use_sim_time: True
     bt_xml_filename: "bt_navigator.xml"
 
+bt_navigator_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
 controller_server:
   ros__parameters:
     use_sim_time: True
@@ -89,6 +93,10 @@ controller_server:
     GoalDist.scale: 24.0
     RotateToGoal.scale: 32.0
 
+controller_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
 local_costmap:
   local_costmap:
     ros__parameters:
@@ -148,13 +156,13 @@ map_server:
     use_sim_time: True
     yaml_filename: "turtlebot3_world.yaml"
 
-navfn_planner:
+planner_server:
   ros__parameters:
     use_sim_time: True
     tolerance: 0.0
     use_astar: false
 
-navfn_planner_GetCostmap_client:
+planner_server_rclcpp_node:
   ros__parameters:
     use_sim_time: True