mirror of https://github.com/ArduPilot/ardupilot
Plane: fix ADSB stall speed units. Was accidently using meter/s instead of cm/s
This commit is contained in:
parent
fe99d3e217
commit
7f9bbc9cfd
|
@ -264,7 +264,7 @@ void Plane::one_second_loop()
|
|||
// make it possible to change orientation at runtime
|
||||
ahrs.update_orientation();
|
||||
#if HAL_ADSB_ENABLED
|
||||
adsb.set_stall_speed_cm(aparm.airspeed_min);
|
||||
adsb.set_stall_speed_cm(aparm.airspeed_min * 100); // convert m/s to cm/s
|
||||
adsb.set_max_speed(aparm.airspeed_max);
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue