Merge branch 'aux_failsafe' into betaflight

Conflicts:
	src/main/config/config.c
This commit is contained in:
borisbstyle 2015-09-25 15:34:57 +02:00
commit b9e16ef243
2 changed files with 3 additions and 6 deletions

View File

@ -410,7 +410,7 @@ static void resetConf(void)
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->mode = RX_FAILSAFE_MODE_AUTO;
channelFailsafeConfiguration->step = (i == THROTTLE) ? masterConfig.rxConfig.rx_min_usec : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
}

View File

@ -378,16 +378,13 @@ static uint16_t getRxfailValue(uint8_t channel)
switch(channelFailsafeConfiguration->mode) {
case RX_FAILSAFE_MODE_AUTO:
switch (channel) {
case ROLL:
case PITCH:
case YAW:
return rxConfig->midrc;
case THROTTLE:
if (feature(FEATURE_3D))
return rxConfig->midrc;
else
return rxConfig->rx_min_usec;
default:
return rxConfig->midrc;
}
/* no break */