mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: check G_Dt to catch startup errors
this catches cases where constructors lead to G_Dt being incorrect
This commit is contained in:
parent
3e89e32d8a
commit
25e317d6b1
@ -334,6 +334,13 @@ void Plane::one_second_loop()
|
||||
// reset the landing altitude correction
|
||||
landing.alt_offset = 0;
|
||||
}
|
||||
|
||||
// this ensures G_Dt is correct, catching startup issues with constructors
|
||||
// calling the scheduler methods
|
||||
if (!is_equal(1.0f/scheduler.get_loop_rate_hz(), scheduler.get_loop_period_s()) ||
|
||||
!is_equal(G_Dt, scheduler.get_loop_period_s())) {
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||
}
|
||||
}
|
||||
|
||||
void Plane::three_hz_loop()
|
||||
|
Loading…
Reference in New Issue
Block a user