diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 8a727950df215..de009477ce6fc 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -262,6 +262,8 @@ void Plane::one_second_loop() adsb.set_stall_speed_cm(aparm.airspeed_min); adsb.set_max_speed(aparm.airspeed_max); + ahrs.writeDefaultAirSpeed(0.01f * (float)((aparm.airspeed_min + aparm.airspeed_max)/2)); + // sync MAVLink system ID mavlink_system.sysid = g.sysid_this_mav;