mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-13 11:37:34 +08:00
tests: increase timeout for px4 health checks
This commit is contained in:
@@ -85,7 +85,7 @@ void AutopilotTester::wait_until_ready()
|
||||
|
||||
// Wait until the system is healthy
|
||||
CHECK(poll_condition_with_timeout(
|
||||
[this]() { return _telemetry->health_all_ok(); }, std::chrono::seconds(30)));
|
||||
[this]() { return _telemetry->health_all_ok(); }, std::chrono::seconds(60)));
|
||||
|
||||
// Note: There is a known bug in MAVSDK (https://github.com/mavlink/MAVSDK/issues/1852),
|
||||
// where `health_all_ok()` returning true doesn't actually mean vehicle is ready to accept
|
||||
@@ -96,7 +96,7 @@ void AutopilotTester::wait_until_ready()
|
||||
|
||||
// Wait until we can arm
|
||||
CHECK(poll_condition_with_timeout(
|
||||
[this]() { return _telemetry->health().is_armable; }, std::chrono::seconds(30)));
|
||||
[this]() { return _telemetry->health().is_armable; }, std::chrono::seconds(60)));
|
||||
}
|
||||
|
||||
void AutopilotTester::store_home()
|
||||
|
||||
Reference in New Issue
Block a user