diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 29a21725f5..e7ec3192b2 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -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