mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Merge branch 'master' into betaflight
Conflicts: src/main/drivers/system.c src/main/rx/rx.h
This commit is contained in:
commit
febee3fb90
26 changed files with 812 additions and 320 deletions
|
@ -71,6 +71,7 @@ static bool rxFlightChannelsValid = false;
|
|||
|
||||
static uint32_t rxUpdateAt = 0;
|
||||
static uint32_t needRxSignalBefore = 0;
|
||||
static uint8_t skipRxSamples = 0;
|
||||
|
||||
int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
|
@ -79,6 +80,8 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
|||
|
||||
#define DELAY_50_HZ (1000000 / 50)
|
||||
#define DELAY_10_HZ (1000000 / 10)
|
||||
#define SKIP_RC_SAMPLES_ON_SUSPEND 75 // approx. 1.5 seconds of samples at 50Hz
|
||||
#define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements
|
||||
|
||||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
static rxConfig_t *rxConfig;
|
||||
|
@ -271,6 +274,16 @@ static void resetRxSignalReceivedFlagIfNeeded(uint32_t currentTime)
|
|||
}
|
||||
}
|
||||
|
||||
void suspendRxSignal(void)
|
||||
{
|
||||
skipRxSamples = SKIP_RC_SAMPLES_ON_SUSPEND;
|
||||
}
|
||||
|
||||
void resumeRxSignal(void)
|
||||
{
|
||||
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
|
||||
}
|
||||
|
||||
void updateRx(uint32_t currentTime)
|
||||
{
|
||||
resetRxSignalReceivedFlagIfNeeded(currentTime);
|
||||
|
@ -356,27 +369,29 @@ static uint16_t getRxfailValue(uint8_t channel)
|
|||
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig->failsafe_channel_configurations[channel];
|
||||
|
||||
switch(channelFailsafeConfiguration->mode) {
|
||||
default:
|
||||
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;
|
||||
}
|
||||
// fall though to HOLD if there's nothing specific to do.
|
||||
/* no break */
|
||||
|
||||
default:
|
||||
case RX_FAILSAFE_MODE_INVALID:
|
||||
case RX_FAILSAFE_MODE_HOLD:
|
||||
return rcData[channel];
|
||||
|
||||
case RX_FAILSAFE_MODE_SET:
|
||||
return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfiguration_t range)
|
||||
|
@ -451,10 +466,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);
|
||||
|
@ -467,8 +483,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
|
||||
|
||||
|
@ -477,9 +491,13 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
|
|||
}
|
||||
}
|
||||
|
||||
if (skipRxSamples) {
|
||||
skipRxSamples--;
|
||||
return;
|
||||
}
|
||||
|
||||
readRxChannelsApplyRanges();
|
||||
detectAndApplySignalLossBehaviour();
|
||||
|
||||
}
|
||||
|
||||
void parseRcChannels(const char *input, rxConfig_t *rxConfig)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue