Skip to content

Commit

Permalink
Plane: don't run TECS update_speed_height() when in idle mode
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Sep 10, 2024
1 parent d27d349 commit 65e15f2
Showing 1 changed file with 4 additions and 0 deletions.
4 changes: 4 additions & 0 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 65e15f2

Please sign in to comment.