forked from Archive/PX4-Autopilot
sitl: loosen some timeouts
The typhoon_h480 model would not always complete takeoff in 30 seconds or finish the mission within 60 seconds.
This commit is contained in:
parent
5c1932dcca
commit
b5a3c58a95
|
@ -205,7 +205,7 @@ void AutopilotTester::wait_until_disarmed(std::chrono::seconds timeout_duration)
|
|||
|
||||
void AutopilotTester::wait_until_hovering()
|
||||
{
|
||||
wait_for_landed_state(Telemetry::LandedState::InAir, std::chrono::seconds(30));
|
||||
wait_for_landed_state(Telemetry::LandedState::InAir, std::chrono::seconds(45));
|
||||
}
|
||||
|
||||
void AutopilotTester::wait_until_altitude(float rel_altitude_m, std::chrono::seconds timeout)
|
||||
|
@ -265,7 +265,7 @@ void AutopilotTester::execute_mission()
|
|||
|
||||
// TODO: Adapt time limit based on mission size, flight speed, sim speed factor, etc.
|
||||
|
||||
wait_for_mission_finished(std::chrono::seconds(60));
|
||||
wait_for_mission_finished(std::chrono::seconds(90));
|
||||
}
|
||||
|
||||
void AutopilotTester::execute_mission_and_lose_gps()
|
||||
|
|
Loading…
Reference in New Issue