Plane: reset target speed on disarm

allows for multiple auto missions with DO_CHANGE_SPEED
This commit is contained in:
Andrew Tridgell 2021-10-07 08:15:24 +11:00 committed by Randy Mackay
parent 4cdd244d9a
commit 109986bcee

View File

@ -262,6 +262,10 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec
} }
#endif #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"); gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed");
return true; return true;