diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 057bec9238..dd86879c51 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -262,6 +262,10 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec } #endif + // re-initialize speed variable used in AUTO and GUIDED for + // DO_CHANGE_SPEED commands + plane.new_airspeed_cm = -1; + gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed"); return true;