1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 09:45:37 +03:00

Merge pull request #1190 from ProDrone/pr995_modifications_1

RX - Corrections to RX fail detection, hold and preset, when using a PWM connection
This commit is contained in:
Dominic Clifton 2015-08-12 00:31:55 +01:00
commit f510fe88b7
4 changed files with 50 additions and 22 deletions

View file

@ -339,8 +339,15 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr)
timerChConfigCallbacks(timerHardwarePtr, &self->edgeCb, &self->overflowCb); timerChConfigCallbacks(timerHardwarePtr, &self->edgeCb, &self->overflowCb);
} }
uint16_t pwmRead(uint8_t channel) uint16_t ppmRead(uint8_t channel)
{ {
return captures[channel]; return captures[channel];
} }
uint16_t pwmRead(uint8_t channel)
{
uint16_t capture = captures[channel];
captures[channel] = PPM_RCVR_TIMEOUT;
return capture;
}

View file

@ -30,6 +30,7 @@ void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel); void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel);
uint16_t pwmRead(uint8_t channel); uint16_t pwmRead(uint8_t channel);
uint16_t ppmRead(uint8_t channel);
bool isPPMDataBeingReceived(void); bool isPPMDataBeingReceived(void);
void resetPPMDataReceivedState(void); void resetPPMDataReceivedState(void);

View file

@ -34,23 +34,29 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/pwm.h" #include "rx/pwm.h"
static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan) static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t channel)
{ {
UNUSED(rxRuntimeConfigPtr); UNUSED(rxRuntimeConfigPtr);
return pwmRead(chan); return pwmRead(channel);
}
static uint16_t ppmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t channel)
{
UNUSED(rxRuntimeConfigPtr);
return ppmRead(channel);
} }
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfigPtr, rcReadRawDataPtr *callback) void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfigPtr, rcReadRawDataPtr *callback)
{ {
UNUSED(rxRuntimeConfigPtr); UNUSED(rxRuntimeConfigPtr);
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled // configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
*callback = pwmReadRawRC;
if (feature(FEATURE_RX_PARALLEL_PWM)) { if (feature(FEATURE_RX_PARALLEL_PWM)) {
rxRuntimeConfigPtr->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT; rxRuntimeConfigPtr->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT;
*callback = pwmReadRawRC;
} }
if (feature(FEATURE_RX_PPM)) { if (feature(FEATURE_RX_PPM)) {
rxRuntimeConfigPtr->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT; rxRuntimeConfigPtr->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
*callback = ppmReadRawRC;
} }
} }

View file

@ -96,7 +96,7 @@ void useRxConfig(rxConfig_t *rxConfigToUse)
static uint8_t validFlightChannelMask; static uint8_t validFlightChannelMask;
STATIC_UNIT_TESTED void rxResetFlightChannelStatus(void) { STATIC_UNIT_TESTED void rxResetFlightChannelStatus(void) {
validFlightChannelMask = 0; validFlightChannelMask = REQUIRED_CHANNEL_MASK;
} }
STATIC_UNIT_TESTED bool rxHaveValidFlightChannels(void) STATIC_UNIT_TESTED bool rxHaveValidFlightChannels(void)
@ -108,11 +108,11 @@ STATIC_UNIT_TESTED bool rxHaveValidFlightChannels(void)
STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration) STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration)
{ {
if (channel < NON_AUX_CHANNEL_COUNT && if (channel < NON_AUX_CHANNEL_COUNT &&
pulseDuration >= rxConfig->rx_min_usec && (pulseDuration < rxConfig->rx_min_usec ||
pulseDuration <= rxConfig->rx_max_usec pulseDuration > rxConfig->rx_max_usec)
) { ) {
// if signal is valid - mark channel as OK // if signal is invalid - mark channel as BAD
validFlightChannelMask |= (1 << channel); validFlightChannelMask &= ~(1 << channel);
} }
} }
@ -135,6 +135,10 @@ void rxInit(rxConfig_t *rxConfig)
rcData[i] = rxConfig->midrc; rcData[i] = rxConfig->midrc;
} }
if (!feature(FEATURE_3D)) {
rcData[0] = rxConfig->rx_min_usec;
}
#ifdef SERIAL_RX #ifdef SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) { if (feature(FEATURE_RX_SERIAL)) {
serialRxInit(rxConfig); serialRxInit(rxConfig);
@ -362,7 +366,7 @@ STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChanne
void processRxChannels(void) void processRxChannels(void)
{ {
uint8_t chan; uint8_t channel;
if (feature(FEATURE_RX_MSP)) { if (feature(FEATURE_RX_MSP)) {
return; // rcData will have already been updated by MSP_SET_RAW_RC return; // rcData will have already been updated by MSP_SET_RAW_RC
@ -370,33 +374,39 @@ void processRxChannels(void)
rxResetFlightChannelStatus(); rxResetFlightChannelStatus();
for (chan = 0; chan < rxRuntimeConfig.channelCount; chan++) { for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
if (!rcReadRawFunc) { if (!rcReadRawFunc) {
rcData[chan] = getRxfailValue(chan); rcData[channel] = getRxfailValue(channel);
continue; continue;
} }
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, REMAPPABLE_CHANNEL_COUNT, chan); uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);
// sample the channel // sample the channel
uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel); uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel);
// apply the rx calibration // apply the rx calibration
if (chan < NON_AUX_CHANNEL_COUNT) { if (channel < NON_AUX_CHANNEL_COUNT) {
sample = applyRxChannelRangeConfiguraton(sample, rxConfig->channelRanges[chan]); sample = applyRxChannelRangeConfiguraton(sample, rxConfig->channelRanges[channel]);
} }
rxUpdateFlightChannelStatus(chan, sample); rxUpdateFlightChannelStatus(channel, sample);
if (!rxHaveValidFlightChannels()) {
// 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.
break;
}
if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) { if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) {
sample = getRxfailValue(chan); sample = getRxfailValue(channel);
} }
if (isRxDataDriven()) { if (isRxDataDriven()) {
rcData[chan] = sample; rcData[channel] = sample;
} else { } else {
rcData[chan] = calculateNonDataDrivenChannel(chan, sample); rcData[channel] = calculateNonDataDrivenChannel(channel, sample);
} }
} }
@ -410,8 +420,12 @@ void processRxChannels(void)
rxSignalReceived = false; rxSignalReceived = false;
} }
for (chan = 0; chan < rxRuntimeConfig.channelCount; chan++) { for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
rcData[chan] = getRxfailValue(chan); if (isRxDataDriven()) {
rcData[channel] = getRxfailValue(channel);
} else {
rcData[channel] = calculateNonDataDrivenChannel(channel, getRxfailValue(channel));
}
} }
} }
} }