1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 17:25:20 +03:00

Merge pull request #852 from ProDrone/Failsafe_features_1

Failsafe - New failsafe functionality (Phase 1)
This commit is contained in:
Dominic Clifton 2015-09-05 22:50:34 +01:00
commit 0caf8a65ba
17 changed files with 542 additions and 251 deletions

View file

@ -454,10 +454,11 @@ static void detectAndApplySignalLossBehaviour(void)
rxFlightChannelsValid = rxHaveValidFlightChannels();
if (rxFlightChannelsValid) {
if ((rxFlightChannelsValid) && !IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
failsafeOnValidDataReceived();
} else {
rxSignalReceived = false;
failsafeOnValidDataFailed();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
rcData[channel] = getRxfailValue(channel);
@ -470,8 +471,6 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
{
rxUpdateAt = currentTime + DELAY_50_HZ;
failsafeOnRxCycleStarted();
if (!feature(FEATURE_RX_MSP)) {
// rcData will have already been updated by MSP_SET_RAW_RC
@ -487,7 +486,6 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
readRxChannelsApplyRanges();
detectAndApplySignalLossBehaviour();
}
void parseRcChannels(const char *input, rxConfig_t *rxConfig)