diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index d4af5ca78f..d073221fdf 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -33,7 +33,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @DisplayName: Transition time // @Description: Transition time in milliseconds after minimum airspeed is reached // @Units: ms - // @Range: 0 30000 + // @Range: 1 30000 // @User: Advanced AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000), @@ -1527,7 +1527,7 @@ void SLT_Transition::update() transition_low_airspeed_ms = 0; gcs().send_text(MAV_SEVERITY_INFO, "Transition done"); } - float trans_time_ms = (float)quadplane.transition_time_ms.get(); + float trans_time_ms = MAX((float)quadplane.transition_time_ms.get(),1); float transition_scale = (trans_time_ms - transition_timer_ms) / trans_time_ms; float throttle_scaled = last_throttle * transition_scale;