mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Plane: prevent large G_Dt_max report on startup
This commit is contained in:
parent
00526359b0
commit
44ee1fcd3c
@ -839,15 +839,15 @@ void loop()
|
||||
|
||||
delta_us_fast_loop = timer - fast_loopTimer_us;
|
||||
G_Dt = delta_us_fast_loop * 1.0e-6f;
|
||||
fast_loopTimer_us = timer;
|
||||
|
||||
if (delta_us_fast_loop > G_Dt_max) {
|
||||
if (delta_us_fast_loop > G_Dt_max && fast_loopTimer_us != 0) {
|
||||
G_Dt_max = delta_us_fast_loop;
|
||||
}
|
||||
|
||||
if (delta_us_fast_loop < G_Dt_min || G_Dt_min == 0) {
|
||||
G_Dt_min = delta_us_fast_loop;
|
||||
}
|
||||
fast_loopTimer_us = timer;
|
||||
|
||||
mainLoop_count++;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user