mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: allow arming in Drift and Sport modes
This commit is contained in:
parent
3751dbef91
commit
9e0cd7a5cf
@ -295,7 +295,7 @@ bool Copter::mode_has_manual_throttle(uint8_t mode) {
|
||||
// mode_allows_arming - returns true if vehicle can be armed in the specified mode
|
||||
// arming_from_gcs should be set to true if the arming request comes from the ground station
|
||||
bool Copter::mode_allows_arming(uint8_t mode, bool arming_from_gcs) {
|
||||
if (mode_has_manual_throttle(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || (arming_from_gcs && mode == GUIDED)) {
|
||||
if (mode_has_manual_throttle(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || mode == DRIFT || mode == SPORT || (arming_from_gcs && mode == GUIDED)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user