From f5f13b9a47d3af12df127f335547579f4a2868e2 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sat, 14 Nov 2020 20:52:39 +1100 Subject: [PATCH] Plane: Set default airspeed variance using airspeed range --- ArduPlane/ArduPlane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index dd3f79ffb7..8280e1a5a4 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -267,7 +267,8 @@ void Plane::one_second_loop() adsb.set_stall_speed_cm(aparm.airspeed_min); adsb.set_max_speed(aparm.airspeed_max); #endif - ahrs.writeDefaultAirSpeed((float)((aparm.airspeed_min + aparm.airspeed_max)/2)); + ahrs.writeDefaultAirSpeed((float)((aparm.airspeed_min + aparm.airspeed_max)/2), + (float)((aparm.airspeed_max - aparm.airspeed_min)/2)); // sync MAVLink system ID mavlink_system.sysid = g.sysid_this_mav;