ArduPlane: Send default airspeed to estimators

This commit is contained in:
Paul Riseborough 2020-03-10 17:50:05 +11:00 committed by Andrew Tridgell
parent 22c2ea7cbf
commit 0efdb2b66b
1 changed files with 2 additions and 0 deletions

View File

@ -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((float)((aparm.airspeed_min + aparm.airspeed_max)/2));
// sync MAVLink system ID
mavlink_system.sysid = g.sysid_this_mav;