mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: Set default airspeed variance using airspeed range
This commit is contained in:
parent
0a052d20ea
commit
f5f13b9a47
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user