Browse Source

Plane: reset target speed on disarm

allows for multiple auto missions with DO_CHANGE_SPEED
zr-v5.1
Andrew Tridgell 3 years ago committed by Randy Mackay
parent
commit
4107eee94f
  1. 4
      ArduPlane/AP_Arming.cpp

4
ArduPlane/AP_Arming.cpp

@ -262,6 +262,10 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec @@ -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;

Loading…
Cancel
Save