Plane: reset target speed on disarm
allows for multiple auto missions with DO_CHANGE_SPEED
This commit is contained in:
parent
d0d6457b31
commit
493d8979d5
@ -279,6 +279,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;
|
||||||
|
Loading…
Reference in New Issue
Block a user