mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: fixed a division by zero
if min airspeed is zero
This commit is contained in:
parent
5ad64b8656
commit
f02db254b7
@ -696,7 +696,7 @@ void Plane::update_load_factor(void)
|
||||
}
|
||||
|
||||
|
||||
float max_load_factor = smoothed_airspeed / aparm.airspeed_min;
|
||||
float max_load_factor = smoothed_airspeed / MAX(aparm.airspeed_min, 1);
|
||||
if (max_load_factor <= 1) {
|
||||
// our airspeed is below the minimum airspeed. Limit roll to
|
||||
// 25 degrees
|
||||
|
Loading…
Reference in New Issue
Block a user