Plane: don't run TECS update_speed_height() when in idle mode

This commit is contained in:
Andrew Tridgell 2024-09-10 08:36:38 +10:00
parent d27d34987c
commit 65e15f2bd9
1 changed files with 4 additions and 0 deletions

View File

@ -217,6 +217,10 @@ void Plane::update_speed_height(void)
}
#endif
if (auto_state.idle_mode) {
should_run_tecs = false;
}
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (mode_auto.in_pullup()) {
should_run_tecs = false;