diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp
index cf78d49aa827d1d40d61076f225289f865df2c12..426f9b446d0860b2f6b1e6239b68cd72d90947ad 100644
--- a/nav2_bt_navigator/src/bt_navigator.cpp
+++ b/nav2_bt_navigator/src/bt_navigator.cpp
@@ -75,7 +75,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
     get_node_clock_interface(),
     get_node_logging_interface(),
     get_node_waitables_interface(),
-    "NavigateToPose", std::bind(&BtNavigator::navigateToPose, this), false);
+    "navigate_to_pose", std::bind(&BtNavigator::navigateToPose, this), false);
 
   // Get the libraries to pull plugins from
   plugin_lib_names_ = get_parameter("plugin_lib_names").as_string_array();
diff --git a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
index 5ca352b8f3e3555a28a1aa5292170dc66f48ae22..a6e300e77dab307e241c953ec9c4cdb2f123176d 100644
--- a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
+++ b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
@@ -38,7 +38,7 @@ LifecycleManagerClient::LifecycleManagerClient(const std::string & name)
   is_active_client_ = node_->create_client<std_srvs::srv::Trigger>(active_service_name_);
 
   navigate_action_client_ =
-    rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(node_, "NavigateToPose");
+    rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(node_, "navigate_to_pose");
 
   initial_pose_publisher_ =
     node_->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp
index 9707827db635573bac28b657ad1eea5c21d64ac5..88a166d156daa1bd7e5ad0364fad9803ff5ac349 100644
--- a/nav2_rviz_plugins/src/nav2_panel.cpp
+++ b/nav2_rviz_plugins/src/nav2_panel.cpp
@@ -76,7 +76,7 @@ Nav2Panel::Nav2Panel(QWidget * parent)
   initial_->assignProperty(navigation_mode_button_, "text", "Waypoint mode");
   initial_->assignProperty(navigation_mode_button_, "enabled", false);
 
-  // State entered when NavigateToPose is not active
+  // State entered when navigate_to_pose action is not active
   idle_ = new QState();
   idle_->setObjectName("idle");
   idle_->assignProperty(start_reset_button_, "text", "Reset");
@@ -91,7 +91,7 @@ Nav2Panel::Nav2Panel(QWidget * parent)
   idle_->assignProperty(navigation_mode_button_, "enabled", true);
   idle_->assignProperty(navigation_mode_button_, "toolTip", single_goal_msg);
 
-  // State entered when NavigateToPose is not active
+  // State entered when navigate_to_pose action is not active
   accumulating_ = new QState();
   accumulating_->setObjectName("accumulating");
   accumulating_->assignProperty(start_reset_button_, "text", "Reset");
@@ -108,7 +108,7 @@ Nav2Panel::Nav2Panel(QWidget * parent)
 
   accumulated_ = new QState();
 
-  // State entered to cancel the NavigateToPose action
+  // State entered to cancel the navigate_to_pose action
   canceled_ = new QState();
   canceled_->setObjectName("canceled");
 
@@ -116,7 +116,7 @@ Nav2Panel::Nav2Panel(QWidget * parent)
   reset_ = new QState();
   reset_->setObjectName("reset");
 
-  // State entered while the NavigateToPose action is active
+  // State entered while the navigate_to_pose action is active
   running_ = new QState();
   running_->setObjectName("running");
   running_->assignProperty(start_reset_button_, "text", "Cancel");
@@ -230,7 +230,7 @@ Nav2Panel::Nav2Panel(QWidget * parent)
   navigation_action_client_ =
     rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
     client_node_,
-    "NavigateToPose");
+    "navigate_to_pose");
   waypoint_follower_action_client_ =
     rclcpp_action::create_client<nav2_msgs::action::FollowWaypoints>(
     client_node_,
diff --git a/nav2_system_tests/src/system/tester_node.py b/nav2_system_tests/src/system/tester_node.py
index 2d1c03262939438923b549e9581f7ef332a3a0a5..901db89bf933c3952f38ce865a0c9a7fd7d3e3a9 100755
--- a/nav2_system_tests/src/system/tester_node.py
+++ b/nav2_system_tests/src/system/tester_node.py
@@ -59,7 +59,7 @@ class NavTester(Node):
         self.initial_pose_received = False
         self.initial_pose = initial_pose
         self.goal_pose = goal_pose
-        self.action_client = ActionClient(self, NavigateToPose, 'NavigateToPose')
+        self.action_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
 
     def info_msg(self, msg: str):
         self.get_logger().info('\033[1;37;44m' + msg + '\033[0m')
diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp
index cd84cea43e4b9b90c728d1f737ec860b2e24d0cc..978ecb834c0ad9c7d96399f4550b1f9a09a688e5 100644
--- a/nav2_waypoint_follower/src/waypoint_follower.cpp
+++ b/nav2_waypoint_follower/src/waypoint_follower.cpp
@@ -51,7 +51,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/)
     std::string(get_name()) + std::string("_client_node"));
 
   nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
-    client_node_, "NavigateToPose");
+    client_node_, "navigate_to_pose");
 
   action_server_ = std::make_unique<ActionServer>(
     get_node_base_interface(),
@@ -242,7 +242,7 @@ WaypointFollower::goalResponseCallback(
   if (!goal_handle) {
     RCLCPP_ERROR(
       get_logger(),
-      "NavigateToPose client failed to send goal to server.");
+      "navigate_to_pose action client failed to send goal to server.");
     current_goal_status_ = ActionStatus::FAILED;
   }
 }