Skip to content

Commit 5754cf7

Browse files
Merge pull request #4639 from iNavFlight/dzikuvx-remove-mc-motor-stop
MOTOR_STOP removed from Multirotors
2 parents c3a9be4 + 1d3d6f5 commit 5754cf7

File tree

7 files changed

+13
-61
lines changed

7 files changed

+13
-61
lines changed

docs/Cli.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,6 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
117117
| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED |
118118
| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_throttle, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
119119
| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. |
120-
| auto_disarm_delay | 5 | Delay before automatic disarming when using stick arming and MOTOR_STOP. This does not apply when using FIXED_WING |
121120
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
122121
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
123122
| reboot_character | 82 | Special character used to trigger reboot |

src/main/fc/config.c

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -305,6 +305,16 @@ void validateAndFixConfig(void)
305305
gyroConfigMutable()->gyroSync = false;
306306
#endif
307307

308+
/*
309+
* MOTOR_STOP is no longer allowed on Multirotors and Tricopters
310+
*/
311+
if (
312+
feature(FEATURE_MOTOR_STOP) &&
313+
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)
314+
) {
315+
featureClear(FEATURE_MOTOR_STOP);
316+
}
317+
308318
// Call target-specific validation function
309319
validateAndFixTargetConfig();
310320

src/main/fc/fc_core.c

Lines changed: 0 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -106,8 +106,6 @@ int16_t headFreeModeHold;
106106

107107
uint8_t motorControlEnable = false;
108108

109-
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
110-
111109
static bool isRXDataNew;
112110
static disarmReason_t lastDisarmReason = DISARM_NONE;
113111

@@ -395,7 +393,6 @@ void tryArm(void)
395393
blackboxStart();
396394
}
397395
#endif
398-
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
399396

400397
//beep to indicate arming
401398
#ifdef USE_NAV
@@ -418,8 +415,6 @@ void tryArm(void)
418415

419416
void processRx(timeUs_t currentTimeUs)
420417
{
421-
static bool armedBeeperOn = false;
422-
423418
// Calculate RPY channel data
424419
calculateRxChannelsAndUpdateFailsafe(currentTimeUs);
425420

@@ -440,50 +435,6 @@ void processRx(timeUs_t currentTimeUs)
440435

441436
const throttleStatus_e throttleStatus = calculateThrottleStatus();
442437

443-
// When armed and motors aren't spinning, do beeps and then disarm
444-
// board after delay so users without buzzer won't lose fingers.
445-
// mixTable constrains motor commands, so checking throttleStatus is enough
446-
if (ARMING_FLAG(ARMED)
447-
&& feature(FEATURE_MOTOR_STOP)
448-
&& !STATE(FIXED_WING)
449-
) {
450-
if (isUsingSticksForArming()) {
451-
if (throttleStatus == THROTTLE_LOW) {
452-
if (armingConfig()->auto_disarm_delay != 0
453-
&& (int32_t)(disarmAt - millis()) < 0
454-
) {
455-
// auto-disarm configured and delay is over
456-
disarm(DISARM_TIMEOUT);
457-
armedBeeperOn = false;
458-
} else {
459-
// still armed; do warning beeps while armed
460-
beeper(BEEPER_ARMED);
461-
armedBeeperOn = true;
462-
}
463-
} else {
464-
// throttle is not low
465-
if (armingConfig()->auto_disarm_delay != 0) {
466-
// extend disarm time
467-
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000;
468-
}
469-
470-
if (armedBeeperOn) {
471-
beeperSilence();
472-
armedBeeperOn = false;
473-
}
474-
}
475-
} else {
476-
// arming is via AUX switch; beep while throttle low
477-
if (throttleStatus == THROTTLE_LOW) {
478-
beeper(BEEPER_ARMED);
479-
armedBeeperOn = true;
480-
} else if (armedBeeperOn) {
481-
beeperSilence();
482-
armedBeeperOn = false;
483-
}
484-
}
485-
}
486-
487438
processRcStickPositions(throttleStatus);
488439

489440
updateActivatedModes();

src/main/fc/fc_msp.c

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -578,7 +578,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
578578
break;
579579

580580
case MSP_ARMING_CONFIG:
581-
sbufWriteU8(dst, armingConfig()->auto_disarm_delay);
581+
sbufWriteU8(dst, 0);
582582
sbufWriteU8(dst, armingConfig()->disarm_kill_switch);
583583
break;
584584

@@ -1547,7 +1547,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
15471547

15481548
case MSP_SET_ARMING_CONFIG:
15491549
if (dataSize >= 2) {
1550-
armingConfigMutable()->auto_disarm_delay = constrain(sbufReadU8(src), AUTO_DISARM_DELAY_MIN, AUTO_DISARM_DELAY_MAX);
1550+
sbufReadU8(src); //Swallow the first byte, used to be auto_disarm_delay
15511551
armingConfigMutable()->disarm_kill_switch = !!sbufReadU8(src);
15521552
} else
15531553
return MSP_RESULT_ERROR;

src/main/fc/rc_controls.c

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -79,12 +79,11 @@ PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
7979
.deadband3d_throttle = 50
8080
);
8181

82-
PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 1);
82+
PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 2);
8383

8484
PG_RESET_TEMPLATE(armingConfig_t, armingConfig,
8585
.fixed_wing_auto_arm = 0,
8686
.disarm_kill_switch = 1,
87-
.auto_disarm_delay = 5,
8887
.switchDisarmDelayMs = DEFAULT_RC_SWITCH_DISARM_DELAY_MS,
8988
);
9089

src/main/fc/rc_controls.h

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,6 @@
1919

2020
#include "config/parameter_group.h"
2121

22-
#define AUTO_DISARM_DELAY_MIN 0
23-
#define AUTO_DISARM_DELAY_MAX 60
24-
2522
typedef enum rc_alias {
2623
ROLL = 0,
2724
PITCH,
@@ -84,7 +81,6 @@ PG_DECLARE(rcControlsConfig_t, rcControlsConfig);
8481
typedef struct armingConfig_s {
8582
uint8_t fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm
8683
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
87-
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
8884
uint16_t switchDisarmDelayMs; // additional delay between ARM box going off and actual disarm
8985
} armingConfig_t;
9086

src/main/fc/settings.yaml

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -793,9 +793,6 @@ groups:
793793
type: bool
794794
- name: disarm_kill_switch
795795
type: bool
796-
- name: auto_disarm_delay
797-
min: 0
798-
max: 60
799796
- name: switch_disarm_delay
800797
field: switchDisarmDelayMs
801798
min: 0

0 commit comments

Comments
 (0)