Skip to content

Commit

Permalink
Merge pull request #4639 from iNavFlight/dzikuvx-remove-mc-motor-stop
Browse files Browse the repository at this point in the history
MOTOR_STOP removed from Multirotors
  • Loading branch information
digitalentity authored Apr 24, 2019
2 parents c3a9be4 + 1d3d6f5 commit 5754cf7
Show file tree
Hide file tree
Showing 7 changed files with 13 additions and 61 deletions.
1 change: 0 additions & 1 deletion docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,6 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
| 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 |
| 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. |
| 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. |
| auto_disarm_delay | 5 | Delay before automatic disarming when using stick arming and MOTOR_STOP. This does not apply when using FIXED_WING |
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
| reboot_character | 82 | Special character used to trigger reboot |
Expand Down
10 changes: 10 additions & 0 deletions src/main/fc/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -305,6 +305,16 @@ void validateAndFixConfig(void)
gyroConfigMutable()->gyroSync = false;
#endif

/*
* MOTOR_STOP is no longer allowed on Multirotors and Tricopters
*/
if (
feature(FEATURE_MOTOR_STOP) &&
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)
) {
featureClear(FEATURE_MOTOR_STOP);
}

// Call target-specific validation function
validateAndFixTargetConfig();

Expand Down
49 changes: 0 additions & 49 deletions src/main/fc/fc_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,6 @@ int16_t headFreeModeHold;

uint8_t motorControlEnable = false;

static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero

static bool isRXDataNew;
static disarmReason_t lastDisarmReason = DISARM_NONE;

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

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

void processRx(timeUs_t currentTimeUs)
{
static bool armedBeeperOn = false;

// Calculate RPY channel data
calculateRxChannelsAndUpdateFailsafe(currentTimeUs);

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

const throttleStatus_e throttleStatus = calculateThrottleStatus();

// When armed and motors aren't spinning, do beeps and then disarm
// board after delay so users without buzzer won't lose fingers.
// mixTable constrains motor commands, so checking throttleStatus is enough
if (ARMING_FLAG(ARMED)
&& feature(FEATURE_MOTOR_STOP)
&& !STATE(FIXED_WING)
) {
if (isUsingSticksForArming()) {
if (throttleStatus == THROTTLE_LOW) {
if (armingConfig()->auto_disarm_delay != 0
&& (int32_t)(disarmAt - millis()) < 0
) {
// auto-disarm configured and delay is over
disarm(DISARM_TIMEOUT);
armedBeeperOn = false;
} else {
// still armed; do warning beeps while armed
beeper(BEEPER_ARMED);
armedBeeperOn = true;
}
} else {
// throttle is not low
if (armingConfig()->auto_disarm_delay != 0) {
// extend disarm time
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000;
}

if (armedBeeperOn) {
beeperSilence();
armedBeeperOn = false;
}
}
} else {
// arming is via AUX switch; beep while throttle low
if (throttleStatus == THROTTLE_LOW) {
beeper(BEEPER_ARMED);
armedBeeperOn = true;
} else if (armedBeeperOn) {
beeperSilence();
armedBeeperOn = false;
}
}
}

processRcStickPositions(throttleStatus);

updateActivatedModes();
Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -578,7 +578,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;

case MSP_ARMING_CONFIG:
sbufWriteU8(dst, armingConfig()->auto_disarm_delay);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, armingConfig()->disarm_kill_switch);
break;

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

case MSP_SET_ARMING_CONFIG:
if (dataSize >= 2) {
armingConfigMutable()->auto_disarm_delay = constrain(sbufReadU8(src), AUTO_DISARM_DELAY_MIN, AUTO_DISARM_DELAY_MAX);
sbufReadU8(src); //Swallow the first byte, used to be auto_disarm_delay
armingConfigMutable()->disarm_kill_switch = !!sbufReadU8(src);
} else
return MSP_RESULT_ERROR;
Expand Down
3 changes: 1 addition & 2 deletions src/main/fc/rc_controls.c
Original file line number Diff line number Diff line change
Expand Up @@ -79,12 +79,11 @@ PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
.deadband3d_throttle = 50
);

PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 2);

PG_RESET_TEMPLATE(armingConfig_t, armingConfig,
.fixed_wing_auto_arm = 0,
.disarm_kill_switch = 1,
.auto_disarm_delay = 5,
.switchDisarmDelayMs = DEFAULT_RC_SWITCH_DISARM_DELAY_MS,
);

Expand Down
4 changes: 0 additions & 4 deletions src/main/fc/rc_controls.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,6 @@

#include "config/parameter_group.h"

#define AUTO_DISARM_DELAY_MIN 0
#define AUTO_DISARM_DELAY_MAX 60

typedef enum rc_alias {
ROLL = 0,
PITCH,
Expand Down Expand Up @@ -84,7 +81,6 @@ PG_DECLARE(rcControlsConfig_t, rcControlsConfig);
typedef struct armingConfig_s {
uint8_t fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm
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
uint16_t switchDisarmDelayMs; // additional delay between ARM box going off and actual disarm
} armingConfig_t;

Expand Down
3 changes: 0 additions & 3 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -793,9 +793,6 @@ groups:
type: bool
- name: disarm_kill_switch
type: bool
- name: auto_disarm_delay
min: 0
max: 60
- name: switch_disarm_delay
field: switchDisarmDelayMs
min: 0
Expand Down

0 comments on commit 5754cf7

Please sign in to comment.