|
|
|
@ -275,12 +275,15 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
@@ -275,12 +275,15 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
|
|
|
|
|
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks) |
|
|
|
|
{ |
|
|
|
|
if (do_disarm_checks && |
|
|
|
|
method == AP_Arming::Method::RUDDER) { |
|
|
|
|
// don't allow rudder-disarming in flight:
|
|
|
|
|
(method == AP_Arming::Method::MAVLINK || |
|
|
|
|
method == AP_Arming::Method::RUDDER)) { |
|
|
|
|
if (plane.is_flying()) { |
|
|
|
|
// obviously this could happen in-flight so we can't warn about it
|
|
|
|
|
// don't allow mavlink or rudder disarm while flying
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (do_disarm_checks && method == AP_Arming::Method::RUDDER) { |
|
|
|
|
// option must be enabled:
|
|
|
|
|
if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) { |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Rudder disarm: disabled"); |
|
|
|
|