mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: prevent divide by zero in SITL
harmless on PX4
This commit is contained in:
parent
9e9a048016
commit
835235127c
@ -14,7 +14,7 @@ float Plane::get_speed_scaler(void)
|
|||||||
if (aspeed > auto_state.highest_airspeed) {
|
if (aspeed > auto_state.highest_airspeed) {
|
||||||
auto_state.highest_airspeed = aspeed;
|
auto_state.highest_airspeed = aspeed;
|
||||||
}
|
}
|
||||||
if (aspeed > 0) {
|
if (aspeed > 0.0001f) {
|
||||||
speed_scaler = g.scaling_speed / aspeed;
|
speed_scaler = g.scaling_speed / aspeed;
|
||||||
} else {
|
} else {
|
||||||
speed_scaler = 2.0;
|
speed_scaler = 2.0;
|
||||||
|
Loading…
Reference in New Issue
Block a user