mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Restore Original CF Failsafe
This commit is contained in:
parent
dbc2c15bf4
commit
4b7fd5a2de
2 changed files with 6 additions and 4 deletions
|
@ -165,8 +165,7 @@ void failsafeUpdateState(void)
|
|||
return;
|
||||
}
|
||||
|
||||
//bool receivingRxData = failsafeIsReceivingRxData(); // FIXME - Original check for received data
|
||||
bool receivingRxData = rxIsReceivingSignal() ? true : false; // FIXME - temporary workaround for the original CF failsafe. It works pretty well actuall
|
||||
bool receivingRxData = failsafeIsReceivingRxData(); // FIXME - Original check for received data
|
||||
bool armed = ARMING_FLAG(ARMED);
|
||||
bool failsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE);
|
||||
beeperMode_e beeperMode = BEEPER_SILENCE;
|
||||
|
|
|
@ -384,13 +384,16 @@ 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 */
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue