diff --git a/nav2_system_tests/src/localization/test_localization_node.cpp b/nav2_system_tests/src/localization/test_localization_node.cpp
index 6785d63bd6452ecd7221fb8492137c98fdaeac05..bf543f192888b300e62eac236a3caac103a95c94 100644
--- a/nav2_system_tests/src/localization/test_localization_node.cpp
+++ b/nav2_system_tests/src/localization/test_localization_node.cpp
@@ -51,7 +51,7 @@ public:
     initial_pose_pub_ = node->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
       "initialpose", rclcpp::SystemDefaultsQoS());
     subscription_ = node->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
-      "amcl_pose", rclcpp::SystemDefaultsQoS(),
+      "amcl_pose", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
       std::bind(&TestAmclPose::amcl_pose_callback, this, _1));
     initial_pose_pub_->publish(testPose_);
   }
@@ -85,7 +85,7 @@ bool TestAmclPose::defaultAmclTest()
   while (!pose_callback_) {
     // TODO(mhpanah): Initial pose should only be published once.
     initial_pose_pub_->publish(testPose_);
-    std::this_thread::sleep_for(100ms);
+    std::this_thread::sleep_for(1s);
     rclcpp::spin_some(node);
   }
   if (std::abs(amcl_pose_x - testPose_.pose.pose.position.x) < tol_ &&