mirror of https://github.com/ArduPilot/ardupilot
Plane: don't run TECS update_speed_height() when in idle mode
This commit is contained in:
parent
d27d34987c
commit
65e15f2bd9
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue