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

Large code re-organization which separates some key tasks in the rx

code.

Tested with X8R in SBus and PWM, and Spek Sat, GR-24 PPM, PWM and SUMD,
Spek PPM
This commit is contained in:
Dominic Clifton 2015-08-18 06:25:30 +01:00
parent 5142ff032a
commit 2c79b9777e
8 changed files with 140 additions and 89 deletions

View file

@ -227,6 +227,17 @@ static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture
#define MAX_MISSED_PWM_EVENTS 10 #define MAX_MISSED_PWM_EVENTS 10
bool isPWMDataBeingReceived(void)
{
int channel;
for (channel = 0; channel < PWM_PORTS_OR_PPM_CAPTURE_COUNT; channel++) {
if (captures[channel] != PPM_RCVR_TIMEOUT) {
return true;
}
}
return false;
}
static void pwmOverflowCallback(timerOvrHandlerRec_t* cbRec, captureCompare_t capture) static void pwmOverflowCallback(timerOvrHandlerRec_t* cbRec, captureCompare_t capture)
{ {
UNUSED(capture); UNUSED(capture);
@ -346,8 +357,6 @@ uint16_t ppmRead(uint8_t channel)
uint16_t pwmRead(uint8_t channel) uint16_t pwmRead(uint8_t channel)
{ {
uint16_t capture = captures[channel]; return captures[channel];
captures[channel] = PPM_RCVR_TIMEOUT;
return capture;
} }

View file

@ -36,3 +36,5 @@ bool isPPMDataBeingReceived(void);
void resetPPMDataReceivedState(void); void resetPPMDataReceivedState(void);
void pwmRxInit(inputFilteringMode_e initialInputFilteringMode); void pwmRxInit(inputFilteringMode_e initialInputFilteringMode);
bool isPWMDataBeingReceived(void);

View file

@ -206,7 +206,13 @@ void updateTicker(void)
void updateRxStatus(void) void updateRxStatus(void)
{ {
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 2, 0); i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 2, 0);
i2c_OLED_send_char(rxIsReceivingSignal() ? 'R' : '!'); char rxStatus = '!';
if (rxIsReceivingSignal()) {
rxStatus = 'r';
} if (rxAreFlightChannelsValid()) {
rxStatus = 'R';
}
i2c_OLED_send_char(rxStatus);
} }
void updateFailsafeStatus(void) void updateFailsafeStatus(void)

View file

@ -67,11 +67,12 @@ uint16_t rssi = 0; // range: [0;1023]
static bool rxDataReceived = false; static bool rxDataReceived = false;
static bool rxSignalReceived = false; static bool rxSignalReceived = false;
static bool shouldCheckPulse = true; static bool rxFlightChannelsValid = false;
static uint32_t rxUpdateAt = 0; static uint32_t rxUpdateAt = 0;
static uint32_t needRxSignalBefore = 0; static uint32_t needRxSignalBefore = 0;
int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000] int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
#define PPM_AND_PWM_SAMPLE_COUNT 4 #define PPM_AND_PWM_SAMPLE_COUNT 4
@ -79,11 +80,18 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
#define DELAY_50_HZ (1000000 / 50) #define DELAY_50_HZ (1000000 / 50)
#define DELAY_10_HZ (1000000 / 10) #define DELAY_10_HZ (1000000 / 10)
static rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
rxRuntimeConfig_t rxRuntimeConfig; rxRuntimeConfig_t rxRuntimeConfig;
static rxConfig_t *rxConfig; static rxConfig_t *rxConfig;
static uint16_t nullReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) {
UNUSED(rxRuntimeConfig);
UNUSED(channel);
return PPM_RCVR_TIMEOUT;
}
static rcReadRawDataPtr rcReadRawFunc = nullReadRawRC;
void serialRxInit(rxConfig_t *rxConfig); void serialRxInit(rxConfig_t *rxConfig);
void useRxConfig(rxConfig_t *rxConfigToUse) void useRxConfig(rxConfig_t *rxConfigToUse)
@ -104,13 +112,16 @@ STATIC_UNIT_TESTED bool rxHaveValidFlightChannels(void)
return (validFlightChannelMask == REQUIRED_CHANNEL_MASK); return (validFlightChannelMask == REQUIRED_CHANNEL_MASK);
} }
// pulse duration is in micro seconds (usec) STATIC_UNIT_TESTED bool isPulseValid(uint16_t pulseDuration)
STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration)
{ {
if (channel < NON_AUX_CHANNEL_COUNT && return pulseDuration >= rxConfig->rx_min_usec &&
(pulseDuration < rxConfig->rx_min_usec || pulseDuration <= rxConfig->rx_max_usec;
pulseDuration > rxConfig->rx_max_usec) }
) {
// pulse duration is in micro seconds (usec)
STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, bool valid)
{
if (channel < NON_AUX_CHANNEL_COUNT && !valid) {
// if signal is invalid - mark channel as BAD // if signal is invalid - mark channel as BAD
validFlightChannelMask &= ~(1 << channel); validFlightChannelMask &= ~(1 << channel);
} }
@ -182,7 +193,7 @@ void serialRxInit(rxConfig_t *rxConfig)
if (!enabled) { if (!enabled) {
featureClear(FEATURE_RX_SERIAL); featureClear(FEATURE_RX_SERIAL);
rcReadRawFunc = NULL; rcReadRawFunc = nullReadRawRC;
} }
} }
@ -228,24 +239,37 @@ bool rxIsReceivingSignal(void)
return rxSignalReceived; return rxSignalReceived;
} }
bool rxAreFlightChannelsValid(void)
{
return rxFlightChannelsValid;
}
static bool isRxDataDriven(void) { static bool isRxDataDriven(void) {
return !(feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM)); return !(feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM));
} }
static void resetRxSignalReceivedFlagIfNeeded(uint32_t currentTime)
{
if (!rxSignalReceived) {
return;
}
if (((int32_t)(currentTime - needRxSignalBefore) >= 0)) {
rxSignalReceived = false;
#ifdef DEBUG_RX_SIGNAL_LOSS
debug[0]++;
#endif
}
}
void updateRx(uint32_t currentTime) void updateRx(uint32_t currentTime)
{ {
rxDataReceived = false; resetRxSignalReceivedFlagIfNeeded(currentTime);
shouldCheckPulse = true;
if (rxSignalReceived) { if (isRxDataDriven()) {
if (((int32_t)(currentTime - needRxSignalBefore) >= 0)) { rxDataReceived = false;
rxSignalReceived = false;
#ifdef DEBUG_RX_SIGNAL_LOSS
debug[0]++;
#endif
}
} }
#ifdef SERIAL_RX #ifdef SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) { if (feature(FEATURE_RX_SERIAL)) {
uint8_t frameStatus = serialRxFrameStatus(rxConfig); uint8_t frameStatus = serialRxFrameStatus(rxConfig);
@ -253,29 +277,15 @@ void updateRx(uint32_t currentTime)
if (frameStatus & SERIAL_RX_FRAME_COMPLETE) { if (frameStatus & SERIAL_RX_FRAME_COMPLETE) {
rxDataReceived = true; rxDataReceived = true;
rxSignalReceived = (frameStatus & SERIAL_RX_FRAME_FAILSAFE) == 0; rxSignalReceived = (frameStatus & SERIAL_RX_FRAME_FAILSAFE) == 0;
if (rxSignalReceived && feature(FEATURE_FAILSAFE)) {
shouldCheckPulse = false;
failsafeOnValidDataReceived();
}
} else {
shouldCheckPulse = false;
} }
} }
#endif #endif
if (feature(FEATURE_RX_MSP)) { if (feature(FEATURE_RX_MSP)) {
rxDataReceived = rxMspFrameComplete(); rxDataReceived = rxMspFrameComplete();
if (rxDataReceived) {
if (feature(FEATURE_FAILSAFE)) {
failsafeOnValidDataReceived();
}
}
} }
if ((feature(FEATURE_RX_SERIAL | FEATURE_RX_MSP) && rxDataReceived) if (feature(FEATURE_RX_SERIAL | FEATURE_RX_MSP) && rxDataReceived) {
|| feature(FEATURE_RX_PARALLEL_PWM)) {
needRxSignalBefore = currentTime + DELAY_10_HZ; needRxSignalBefore = currentTime + DELAY_10_HZ;
} }
@ -285,8 +295,15 @@ void updateRx(uint32_t currentTime)
needRxSignalBefore = currentTime + DELAY_10_HZ; needRxSignalBefore = currentTime + DELAY_10_HZ;
resetPPMDataReceivedState(); resetPPMDataReceivedState();
} }
shouldCheckPulse = rxSignalReceived;
} }
if (feature(FEATURE_RX_PARALLEL_PWM)) {
if (isPWMDataBeingReceived()) {
rxSignalReceived = true;
needRxSignalBefore = currentTime + DELAY_10_HZ;
}
}
} }
bool shouldProcessRx(uint32_t currentTime) bool shouldProcessRx(uint32_t currentTime)
@ -364,23 +381,12 @@ STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChanne
return sample; return sample;
} }
void processRxChannels(void) static void readRxChannelsApplyRanges(void)
{ {
uint8_t channel; uint8_t channel;
if (feature(FEATURE_RX_MSP)) {
return; // rcData will have already been updated by MSP_SET_RAW_RC
}
rxResetFlightChannelStatus();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) { for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
if (!rcReadRawFunc) {
rcData[channel] = getRxfailValue(channel);
continue;
}
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, REMAPPABLE_CHANNEL_COUNT, channel); uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);
// sample the channel // sample the channel
@ -391,18 +397,40 @@ void processRxChannels(void)
sample = applyRxChannelRangeConfiguraton(sample, rxConfig->channelRanges[channel]); sample = applyRxChannelRangeConfiguraton(sample, rxConfig->channelRanges[channel]);
} }
rxUpdateFlightChannelStatus(channel, sample); rcRaw[channel] = sample;
}
}
if (!rxHaveValidFlightChannels()) { static void processNonDataDrivenRx(void)
// abort on first indication of control channel failure to prevent aux channel changes {
// caused by rx's where aux channels are set to goto a predefined value on failsafe. rcSampleIndex++;
break; }
static void detectAndApplySignalLossBehaviour(void)
{
int channel;
rxResetFlightChannelStatus();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
uint16_t sample = rcRaw[channel];
if (!rxSignalReceived) {
if (isRxDataDriven() && rxDataReceived) {
// use the values from the RX
} else {
sample = PPM_RCVR_TIMEOUT;
}
} }
if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) { bool validPulse = isPulseValid(sample);
if (!validPulse) {
sample = getRxfailValue(channel); sample = getRxfailValue(channel);
} }
rxUpdateFlightChannelStatus(channel, validPulse);
if (isRxDataDriven()) { if (isRxDataDriven()) {
rcData[channel] = sample; rcData[channel] = sample;
} else { } else {
@ -410,36 +438,18 @@ void processRxChannels(void)
} }
} }
if (rxHaveValidFlightChannels()) { rxFlightChannelsValid = rxHaveValidFlightChannels();
if (shouldCheckPulse) {
failsafeOnValidDataReceived(); if (rxFlightChannelsValid) {
rxSignalReceived = true; failsafeOnValidDataReceived();
}
} else { } else {
if (feature(FEATURE_RX_PARALLEL_PWM)) { rxSignalReceived = false;
rxSignalReceived = false;
}
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) { for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
if (isRxDataDriven()) { rcData[channel] = getRxfailValue(channel);
rcData[channel] = getRxfailValue(channel);
} else {
rcData[channel] = calculateNonDataDrivenChannel(channel, getRxfailValue(channel));
}
} }
} }
}
static void processDataDrivenRx(void)
{
processRxChannels();
}
static void processNonDataDrivenRx(void)
{
rcSampleIndex++;
processRxChannels();
} }
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime) void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
@ -448,11 +458,17 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
failsafeOnRxCycleStarted(); failsafeOnRxCycleStarted();
if (isRxDataDriven()) { if (!feature(FEATURE_RX_MSP)) {
processDataDrivenRx(); // rcData will have already been updated by MSP_SET_RAW_RC
} else {
processNonDataDrivenRx(); if (!isRxDataDriven()) {
processNonDataDrivenRx();
}
} }
readRxChannelsApplyRanges();
detectAndApplySignalLossBehaviour();
} }
void parseRcChannels(const char *input, rxConfig_t *rxConfig) void parseRcChannels(const char *input, rxConfig_t *rxConfig)

View file

@ -129,6 +129,7 @@ typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t
void updateRx(uint32_t currentTime); void updateRx(uint32_t currentTime);
bool rxIsReceivingSignal(void); bool rxIsReceivingSignal(void);
bool rxAreFlightChannelsValid(void);
bool shouldProcessRx(uint32_t currentTime); bool shouldProcessRx(uint32_t currentTime);
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime); void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);

View file

@ -20,6 +20,7 @@
#include <stdlib.h> #include <stdlib.h>
#include "platform.h" #include "platform.h"
#include "debug.h"
#include "drivers/gpio.h" #include "drivers/gpio.h"
#include "drivers/system.h" #include "drivers/system.h"
@ -101,8 +102,10 @@ static void spektrumDataReceive(uint16_t c)
spekTime = micros(); spekTime = micros();
spekTimeInterval = spekTime - spekTimeLast; spekTimeInterval = spekTime - spekTimeLast;
spekTimeLast = spekTime; spekTimeLast = spekTime;
if (spekTimeInterval > 5000) if (spekTimeInterval > 5000) {
spekFramePosition = 0; spekFramePosition = 0;
}
spekFrame[spekFramePosition] = (uint8_t)c; spekFrame[spekFramePosition] = (uint8_t)c;
if (spekFramePosition == SPEK_FRAME_SIZE - 1) { if (spekFramePosition == SPEK_FRAME_SIZE - 1) {
rcFrameComplete = true; rcFrameComplete = true;

View file

@ -162,6 +162,11 @@ bool isPPMDataBeingReceived(void)
return false; return false;
} }
bool isPWMDataBeingReceived(void)
{
return false;
}
void resetPPMDataReceivedState(void) void resetPPMDataReceivedState(void)
{ {
} }

View file

@ -28,6 +28,7 @@ extern "C" {
void rxInit(rxConfig_t *rxConfig); void rxInit(rxConfig_t *rxConfig);
void rxResetFlightChannelStatus(void); void rxResetFlightChannelStatus(void);
bool rxHaveValidFlightChannels(void); bool rxHaveValidFlightChannels(void);
bool isPulseValid(uint16_t pulseDuration);
void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration); void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration);
} }
@ -36,6 +37,7 @@ extern "C" {
typedef struct testData_s { typedef struct testData_s {
bool isPPMDataBeingReceived; bool isPPMDataBeingReceived;
bool isPWMDataBeingReceived;
} testData_t; } testData_t;
static testData_t testData; static testData_t testData;
@ -58,7 +60,8 @@ TEST(RxTest, TestValidFlightChannels)
rxResetFlightChannelStatus(); rxResetFlightChannelStatus();
for (uint8_t channelIndex = 0; channelIndex < MAX_SUPPORTED_RC_CHANNEL_COUNT; channelIndex++) { for (uint8_t channelIndex = 0; channelIndex < MAX_SUPPORTED_RC_CHANNEL_COUNT; channelIndex++) {
rxUpdateFlightChannelStatus(channelIndex, 1500); bool validPulse = isPulseValid(1500);
rxUpdateFlightChannelStatus(channelIndex, validPulse);
} }
// then // then
@ -98,7 +101,8 @@ TEST(RxTest, TestInvalidFlightChannels)
// when // when
for (uint8_t channelIndex = 0; channelIndex < MAX_SUPPORTED_RC_CHANNEL_COUNT; channelIndex++) { for (uint8_t channelIndex = 0; channelIndex < MAX_SUPPORTED_RC_CHANNEL_COUNT; channelIndex++) {
rxUpdateFlightChannelStatus(channelIndex, channelPulses[channelIndex]); bool validPulse = isPulseValid(channelPulses[channelIndex]);
rxUpdateFlightChannelStatus(channelIndex, validPulse);
} }
// then // then
@ -114,7 +118,8 @@ TEST(RxTest, TestInvalidFlightChannels)
// when // when
for (uint8_t channelIndex = 0; channelIndex < MAX_SUPPORTED_RC_CHANNEL_COUNT; channelIndex++) { for (uint8_t channelIndex = 0; channelIndex < MAX_SUPPORTED_RC_CHANNEL_COUNT; channelIndex++) {
rxUpdateFlightChannelStatus(channelIndex, channelPulses[channelIndex]); bool validPulse = isPulseValid(channelPulses[channelIndex]);
rxUpdateFlightChannelStatus(channelIndex, validPulse);
} }
// then // then
@ -138,6 +143,10 @@ extern "C" {
return testData.isPPMDataBeingReceived; return testData.isPPMDataBeingReceived;
} }
bool isPWMDataBeingReceived(void) {
return testData.isPWMDataBeingReceived;
}
void resetPPMDataReceivedState(void) {} void resetPPMDataReceivedState(void) {}
bool rxMspFrameComplete(void) { return false; } bool rxMspFrameComplete(void) { return false; }