diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index e3a769a83..d68f547c3 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -482,7 +482,7 @@ bool processRx(timeUs_t currentTimeUs) } } - processRcStickPositions(throttleStatus); + processRcStickPositions(); if (feature(FEATURE_INFLIGHT_ACC_CAL)) { updateInflightCalibrationState(); diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 2173f4c88..3c4124fbb 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -79,11 +79,10 @@ PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, .yaw_control_reversed = false, ); -PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 0); +PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 1); PG_RESET_TEMPLATE(armingConfig_t, armingConfig, .gyro_cal_on_first_arm = 0, // TODO - Cleanup retarded arm support - .disarm_kill_switch = 1, .auto_disarm_delay = 5 ); @@ -129,7 +128,7 @@ throttleStatus_e calculateThrottleStatus(void) rcDelayMs -= (t); \ doNotRepeat = false; \ } -void processRcStickPositions(throttleStatus_e throttleStatus) +void processRcStickPositions() { // time the sticks are maintained static int16_t rcDelayMs; @@ -178,11 +177,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus) if (ARMING_FLAG(ARMED) && rxIsReceivingSignal() && !failsafeIsActive() ) { rcDisarmTicks++; if (rcDisarmTicks > 3) { - if (armingConfig()->disarm_kill_switch) { - disarm(); - } else if (throttleStatus == THROTTLE_LOW) { - disarm(); - } + disarm(); } } } diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 2238631d7..06df4ae4c 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -100,7 +100,6 @@ PG_DECLARE(flight3DConfig_t, flight3DConfig); typedef struct armingConfig_s { uint8_t gyro_cal_on_first_arm; // allow disarm/arm on throttle down + roll left/right - uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0 } armingConfig_t; @@ -110,7 +109,7 @@ bool areUsingSticksToArm(void); bool areSticksInApModePosition(uint16_t ap_mode); throttleStatus_e calculateThrottleStatus(void); -void processRcStickPositions(throttleStatus_e throttleStatus); +void processRcStickPositions(); bool isUsingSticksForArming(void); diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index b8827dcca..3b3480a29 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -875,7 +875,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) case MSP_ARMING_CONFIG: sbufWriteU8(dst, armingConfig()->auto_disarm_delay); - sbufWriteU8(dst, armingConfig()->disarm_kill_switch); + sbufWriteU8(dst, 0); sbufWriteU8(dst, imuConfig()->small_angle); break; @@ -1414,7 +1414,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) break; case MSP_SET_ARMING_CONFIG: armingConfigMutable()->auto_disarm_delay = sbufReadU8(src); - armingConfigMutable()->disarm_kill_switch = sbufReadU8(src); + sbufReadU8(src); // reserved if (sbufBytesRemaining(src)) { imuConfigMutable()->small_angle = sbufReadU8(src); } diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 9e3039345..49a209beb 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -568,7 +568,6 @@ const clivalue_t valueTable[] = { // PG_ARMING_CONFIG { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 60 }, PG_ARMING_CONFIG, offsetof(armingConfig_t, auto_disarm_delay) }, - { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ARMING_CONFIG, offsetof(armingConfig_t, disarm_kill_switch) }, { "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ARMING_CONFIG, offsetof(armingConfig_t, gyro_cal_on_first_arm) },