Plane: Remove tecs_hgt_afe from the 50hz tecs update
This commit is contained in:
parent
f5749b44cd
commit
ef348473eb
@ -190,7 +190,7 @@ void Plane::update_speed_height(void)
|
||||
// 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(tecs_hgt_afe());
|
||||
SpdHgt_Controller->update_50hz();
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user