From d7abf27ec28e9722c9f901cd8dda64bb98d3504b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Feb 2019 16:23:53 +1100 Subject: [PATCH] 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. --- ArduPlane/radio.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index f0ae98d3d1..a170ba021b 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -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()) {