diff --git a/px4_ros2_cpp/test/integration/global_navigation.cpp b/px4_ros2_cpp/test/integration/global_navigation.cpp index c057ec8..745f3ba 100644 --- a/px4_ros2_cpp/test/integration/global_navigation.cpp +++ b/px4_ros2_cpp/test/integration/global_navigation.cpp @@ -41,12 +41,21 @@ class GlobalPositionInterfaceTest : public BaseTest }); } - void resetFlags() + void waitUntilFlagsReset() { + auto start_time = _node->now(); + // Wait for PX4 to stop fusing external measurements while (_estimator_status_flags->cs_aux_gpos) { rclcpp::spin_some(_node); - std::this_thread::sleep_for(_k_sleep_interval); + rclcpp::sleep_for(kSleepInterval); + + const auto elapsed_time = _node->now() - start_time; + + if (elapsed_time >= kTimeoutDuration) { + FAIL() << "Timeout while waiting for PX4 estimator flags to reset."; + break; + } } _estimator_status_flags.reset(); @@ -57,7 +66,7 @@ class GlobalPositionInterfaceTest : public BaseTest const std::function & is_fused_getter ) { - auto start_time = std::chrono::steady_clock::now(); + auto start_time = _node->now(); // Wait for PX4 estimator flags to confirm proper measurement fusion while (!_estimator_status_flags || !is_fused_getter(_estimator_status_flags)) { @@ -70,13 +79,10 @@ class GlobalPositionInterfaceTest : public BaseTest rclcpp::spin_some(_node); - const auto current_time = std::chrono::steady_clock::now(); - const auto elapsed_time = std::chrono::duration_cast( - current_time - start_time - ); - // Check timeout - if (elapsed_time >= _k_timeout_duration) { + const auto elapsed_time = _node->now() - start_time; + + if (elapsed_time >= kTimeoutDuration) { ASSERT_NE(_estimator_status_flags, nullptr) << "Missing feedback from PX4: no estimator status flags published over /fmu/out/estimator_status_flags."; EXPECT_TRUE(is_fused_getter(_estimator_status_flags)) << @@ -84,10 +90,10 @@ class GlobalPositionInterfaceTest : public BaseTest break; } - std::this_thread::sleep_for(_k_sleep_interval); + rclcpp::sleep_for(kSleepInterval); } - resetFlags(); + waitUntilFlagsReset(); } std::shared_ptr _node; @@ -95,8 +101,8 @@ class GlobalPositionInterfaceTest : public BaseTest rclcpp::Subscription::SharedPtr _subscriber; EstimatorStatusFlags::UniquePtr _estimator_status_flags; - const std::chrono::seconds _k_timeout_duration = 60s; - const std::chrono::milliseconds _k_sleep_interval = 50ms; + static constexpr std::chrono::seconds kTimeoutDuration = 60s; + static constexpr std::chrono::milliseconds kSleepInterval = 50ms; }; TEST_F(GlobalPositionInterfaceTest, fuseAll) { diff --git a/px4_ros2_cpp/test/integration/local_navigation.cpp b/px4_ros2_cpp/test/integration/local_navigation.cpp index 4759ee1..d0f888b 100644 --- a/px4_ros2_cpp/test/integration/local_navigation.cpp +++ b/px4_ros2_cpp/test/integration/local_navigation.cpp @@ -46,14 +46,23 @@ class LocalPositionInterfaceTest : public BaseTest }); } - void resetFlags() + void waitUntilFlagsReset() { + auto start_time = _node->now(); + // Wait for PX4 to stop fusing external measurements while (_estimator_status_flags->cs_ev_pos || _estimator_status_flags->cs_ev_hgt || _estimator_status_flags->cs_ev_vel || _estimator_status_flags->cs_ev_yaw) { rclcpp::spin_some(_node); - std::this_thread::sleep_for(_k_sleep_interval); + rclcpp::sleep_for(kSleepInterval); + + const auto elapsed_time = _node->now() - start_time; + + if (elapsed_time >= kTimeoutDuration) { + FAIL() << "Timeout while waiting for PX4 estimator flags to reset."; + break; + } } _estimator_status_flags.reset(); @@ -64,7 +73,7 @@ class LocalPositionInterfaceTest : public BaseTest const std::function & is_fused_getter ) { - auto start_time = std::chrono::steady_clock::now(); + auto start_time = _node->now(); // Wait for PX4 estimator flags to confirm proper measurement fusion while (!_estimator_status_flags || !is_fused_getter(_estimator_status_flags)) { @@ -78,12 +87,9 @@ class LocalPositionInterfaceTest : public BaseTest rclcpp::spin_some(_node); // Check timeout - const auto current_time = std::chrono::steady_clock::now(); - const auto elapsed_time = std::chrono::duration_cast( - current_time - start_time - ); + const auto elapsed_time = _node->now() - start_time; - if (elapsed_time >= _k_timeout_duration) { + if (elapsed_time >= kTimeoutDuration) { ASSERT_NE(_estimator_status_flags, nullptr) << "Missing feedback from PX4: no estimator status flags published over /fmu/out/estimator_status_flags."; EXPECT_TRUE(is_fused_getter(_estimator_status_flags)) << @@ -91,10 +97,10 @@ class LocalPositionInterfaceTest : public BaseTest break; } - std::this_thread::sleep_for(_k_sleep_interval); + rclcpp::sleep_for(kSleepInterval); } - resetFlags(); + waitUntilFlagsReset(); } std::shared_ptr _node; @@ -102,8 +108,8 @@ class LocalPositionInterfaceTest : public BaseTest rclcpp::Subscription::SharedPtr _subscriber; EstimatorStatusFlags::UniquePtr _estimator_status_flags; - const std::chrono::seconds _k_timeout_duration = 60s; - const std::chrono::milliseconds _k_sleep_interval = 50ms; + static constexpr std::chrono::seconds kTimeoutDuration = 60s; + static constexpr std::chrono::milliseconds kSleepInterval = 50ms; }; TEST_F(LocalPositionInterfaceTest, fuseEvPos) {