Plane: fixed servo jitter due to airspeed estimate from throttle

when we have no other airspeed source and we are armed we get airspeed
from throttle. the default setting of k_throttle in the radio code
caused an oscillation of the value used in the airspeed estimate, each
time a RC frame came in.
This commit is contained in:
Andrew Tridgell 2019-02-20 16:23:53 +11:00
parent f23ff1c8e9
commit d7abf27ec2
1 changed files with 0 additions and 2 deletions

View File

@ -200,8 +200,6 @@ void Plane::read_radio()
control_failsafe();
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input());
if (g.throttle_nudge && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > 50 && geofence_stickmixing()) {
float nudge = (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) - 50) * 0.02f;
if (ahrs.airspeed_sensor_enabled()) {