mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Copter: allow arming in GUIDED only from GCS
Also changed mode_allows_arming function to accept arming_from_gcs param Also remove AUTOTUNE from arming list
This commit is contained in:
parent
2b0cffda29
commit
9d4107f1fc
@ -267,8 +267,10 @@ static bool manual_flight_mode(uint8_t mode) {
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool mode_allows_arming(uint8_t mode) {
|
||||
if (manual_flight_mode(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || mode == AUTOTUNE || mode == GUIDED) {
|
||||
// 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
|
||||
static bool mode_allows_arming(uint8_t mode, bool arming_from_gcs) {
|
||||
if (manual_flight_mode(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || (arming_from_gcs && mode == GUIDED)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -504,10 +504,10 @@ static bool pre_arm_gps_checks(bool display_failure)
|
||||
|
||||
// arm_checks - perform final checks before arming
|
||||
// always called just before arming. Return true if ok to arm
|
||||
static bool arm_checks(bool display_failure, bool request_from_gcs)
|
||||
static bool arm_checks(bool display_failure, bool arming_from_gcs)
|
||||
{
|
||||
// always check if the current mode allows arming
|
||||
if (!mode_allows_arming(control_mode) || (!request_from_gcs && control_mode == GUIDED)) {
|
||||
if (!mode_allows_arming(control_mode, arming_from_gcs)) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Mode not armable"));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user