mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: run TECS 50Hz code when throttle suppressed
this fixes auto-launch detection using TECS
This commit is contained in:
parent
8428779558
commit
c3b5f20a45
@ -808,8 +808,10 @@ static void fast_loop()
|
||||
*/
|
||||
static void update_speed_height(void)
|
||||
{
|
||||
if (auto_throttle_mode && !throttle_suppressed) {
|
||||
// Call TECS 50Hz update
|
||||
if (auto_throttle_mode) {
|
||||
// Call TECS 50Hz update. Note that we call this regardless of
|
||||
// throttle suppressed, as this needs to be running for
|
||||
// takeoff detection
|
||||
SpdHgt_Controller->update_50hz(relative_altitude());
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user