Plane: allow arming in all auto-throttle modes

... except QRTL and QLAND which are now universally denied for arming.
This commit is contained in:
Peter Barker 2021-01-22 10:28:26 +11:00 committed by Andrew Tridgell
parent a9be4480b1
commit b6d0208287
2 changed files with 13 additions and 7 deletions

View File

@ -153,14 +153,11 @@ bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
check_failed(true, "Non-zero throttle");
return false;
}
}
// if not in a manual throttle mode and not in CRUISE or FBWB
// modes then disallow rudder arming/disarming
if (plane.control_mode->does_auto_throttle() &&
(plane.control_mode != &plane.mode_cruise && plane.control_mode != &plane.mode_fbwb)) {
check_failed(true, "Mode not rudder-armable");
return false;
}
if (!plane.control_mode->allows_arming()) {
check_failed(true, "Mode does not allow arming");
return false;
}
//are arming checks disabled?

View File

@ -63,6 +63,9 @@ public:
// returns a string for this flightmode, exactly 4 bytes
virtual const char *name4() const = 0;
// returns true if the vehicle can be armed in this mode
virtual bool allows_arming() const { return true; }
//
// methods that sub classes should override to affect movement of the vehicle in this mode
//
@ -320,6 +323,8 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override { }
bool allows_arming() const override { return false; }
bool allows_throttle_nudging() const override { return true; }
bool does_auto_throttle() const override { return true; }
@ -488,6 +493,8 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
bool allows_arming() const override { return false; }
protected:
bool _enter() override;
@ -506,6 +513,8 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
bool allows_arming() const override { return false; }
protected:
bool _enter() override;