1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

Updating the SerialRX drivers so they can report back a failsafe

condition.  Improve SumD driver, when a failsafe is detected the values
from the frame will be used (same behaviour as SBus when SBus RX reports
failsafe).
This commit is contained in:
Dominic Clifton 2015-03-14 23:28:38 +01:00
parent 0e2356bf00
commit 7d6e4aa390
13 changed files with 70 additions and 52 deletions

View file

@ -46,11 +46,12 @@ void rxMspFrameRecieve(void)
bool rxMspFrameComplete(void)
{
if (rxMspFrameDone) {
rxMspFrameDone = false;
return true;
if (!rxMspFrameDone) {
return false;
}
return false;
rxMspFrameDone = false;
return true;
}
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)

View file

@ -143,32 +143,32 @@ void serialRxInit(rxConfig_t *rxConfig)
}
}
bool isSerialRxFrameComplete(rxConfig_t *rxConfig)
uint8_t serialRxFrameStatus(rxConfig_t *rxConfig)
{
/**
* FIXME: Each of the xxxxFrameComplete() methods MUST be able to survive being called without the
* FIXME: Each of the xxxxFrameStatus() methods MUST be able to survive being called without the
* corresponding xxxInit() method having been called first.
*
* This situation arises when the cli or the msp changes the value of rxConfig->serialrx_provider
*
* A solution is for the ___Init() to configure the serialRxFrameComplete function pointer which
* A solution is for the ___Init() to configure the serialRxFrameStatus function pointer which
* should be used instead of the switch statement below.
*/
switch (rxConfig->serialrx_provider) {
case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048:
return spektrumFrameComplete();
return spektrumFrameStatus();
case SERIALRX_SBUS:
return sbusFrameComplete();
return sbusFrameStatus();
case SERIALRX_SUMD:
return sumdFrameComplete();
return sumdFrameStatus();
case SERIALRX_SUMH:
return sumhFrameComplete();
return sumhFrameStatus();
case SERIALRX_XBUS_MODE_B:
case SERIALRX_XBUS_MODE_B_RJ01:
return xBusFrameComplete();
return xBusFrameStatus();
}
return false;
return SERIAL_RX_FRAME_PENDING;
}
#endif
@ -181,6 +181,7 @@ uint8_t calculateChannelRemapping(uint8_t *channelMap, uint8_t channelMapEntryCo
}
static bool rcDataReceived = false;
static uint32_t rxUpdateAt = 0;
@ -189,18 +190,21 @@ void updateRx(void)
rcDataReceived = false;
#ifdef SERIAL_RX
// calculate rc stuff from serial-based receivers (spek/sbus)
if (feature(FEATURE_RX_SERIAL)) {
rcDataReceived = isSerialRxFrameComplete(rxConfig);
uint8_t frameStatus = serialRxFrameStatus(rxConfig);
if (frameStatus & SERIAL_RX_FRAME_COMPLETE) {
rcDataReceived = true;
if ((frameStatus & SERIAL_RX_FRAME_FAILSAFE) == 0 && feature(FEATURE_FAILSAFE)) {
failsafeReset();
}
}
}
#endif
if (feature(FEATURE_RX_MSP)) {
rcDataReceived = rxMspFrameComplete();
}
if (rcDataReceived) {
if (feature(FEATURE_FAILSAFE)) {
if (rcDataReceived && feature(FEATURE_FAILSAFE)) {
failsafeReset();
}
}
@ -217,7 +221,7 @@ static bool isRxDataDriven(void) {
static uint8_t rcSampleIndex = 0;
uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
{
static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT];
static int16_t rcDataMean[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT];
@ -245,7 +249,7 @@ uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
return rcDataMean[chan] / PPM_AND_PWM_SAMPLE_COUNT;
}
void processRxChannels(void)
static void processRxChannels(void)
{
uint8_t chan;
@ -288,18 +292,12 @@ void processRxChannels(void)
}
}
void processDataDrivenRx(void)
static void processDataDrivenRx(void)
{
if (rcDataReceived) {
failsafeReset();
}
processRxChannels();
rcDataReceived = false;
}
void processNonDataDrivenRx(void)
static void processNonDataDrivenRx(void)
{
rcSampleIndex++;

View file

@ -26,6 +26,12 @@
#define DEFAULT_SERVO_MIDDLE 1500
#define DEFAULT_SERVO_MAX 2000
typedef enum {
SERIAL_RX_FRAME_PENDING = 0,
SERIAL_RX_FRAME_COMPLETE = (1 << 0),
SERIAL_RX_FRAME_FAILSAFE = (1 << 1)
} serialrxFrameState_t;
typedef enum {
SERIALRX_SPEKTRUM1024 = 0,
SERIALRX_SPEKTRUM2048 = 1,
@ -93,6 +99,6 @@ bool shouldProcessRx(uint32_t currentTime);
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
bool isSerialRxFrameComplete(rxConfig_t *rxConfig);
uint8_t serialRxFrameStatus(rxConfig_t *rxConfig);
void updateRSSI(uint32_t currentTime);

View file

@ -168,10 +168,10 @@ static void sbusDataReceive(uint16_t c)
}
}
bool sbusFrameComplete(void)
uint8_t sbusFrameStatus(void)
{
if (!sbusFrameDone) {
return false;
return SERIAL_RX_FRAME_PENDING;
}
sbusFrameDone = false;
@ -222,13 +222,13 @@ bool sbusFrameComplete(void)
debug[0] = sbusStateFlags;
#endif
// RX *should* still be sending valid channel data, so use it.
return false;
return SERIAL_RX_FRAME_COMPLETE | SERIAL_RX_FRAME_FAILSAFE;
}
#ifdef DEBUG_SBUS_PACKETS
debug[0] = sbusStateFlags;
#endif
return true;
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View file

@ -17,4 +17,4 @@
#pragma once
bool sbusFrameComplete(void);
uint8_t sbusFrameStatus(void);

View file

@ -109,9 +109,9 @@ static void spektrumDataReceive(uint16_t c)
}
}
bool spektrumFrameComplete(void)
uint8_t spektrumFrameStatus(void)
{
return rcFrameComplete;
return rcFrameComplete ? SERIAL_RX_FRAME_COMPLETE : SERIAL_RX_FRAME_PENDING;
}
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View file

@ -20,4 +20,4 @@
#define SPEKTRUM_SAT_BIND_DISABLED 0
#define SPEKTRUM_SAT_BIND_MAX 10
bool spektrumFrameComplete(void);
uint8_t spektrumFrameStatus(void);

View file

@ -104,18 +104,31 @@ static void sumdDataReceive(uint16_t c)
#define SUMD_BYTES_PER_CHANNEL 2
bool sumdFrameComplete(void)
#define SUMD_FRAME_STATE_OK 0x01
#define SUMD_FRAME_STATE_FAILSAFE 0x81
uint8_t sumdFrameStatus(void)
{
uint8_t channelIndex;
uint8_t frameStatus = SERIAL_RX_FRAME_PENDING;
if (!sumdFrameDone) {
return false;
return frameStatus;
}
sumdFrameDone = false;
if (sumd[1] != 0x01) {
return false;
switch (sumd[1]) {
case SUMD_FRAME_STATE_FAILSAFE:
frameStatus = SERIAL_RX_FRAME_COMPLETE | SERIAL_RX_FRAME_FAILSAFE;
break;
case SUMD_FRAME_STATE_OK:
frameStatus = SERIAL_RX_FRAME_COMPLETE;
break;
default:
return frameStatus;
}
if (sumdChannelCount > SUMD_MAX_CHANNEL)
@ -127,7 +140,7 @@ bool sumdFrameComplete(void)
sumd[SUMD_BYTES_PER_CHANNEL * channelIndex + SUMD_OFFSET_CHANNEL_1_LOW]
);
}
return true;
return frameStatus;
}
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View file

@ -17,4 +17,4 @@
#pragma once
bool sumdFrameComplete(void);
uint8_t sumdFrameStatus(void);

View file

@ -97,18 +97,18 @@ static void sumhDataReceive(uint16_t c)
}
}
bool sumhFrameComplete(void)
uint8_t sumhFrameStatus(void)
{
uint8_t channelIndex;
if (!sumhFrameDone) {
return false;
return SERIAL_RX_FRAME_PENDING;
}
sumhFrameDone = false;
if (!((sumhFrame[0] == 0xA8) && (sumhFrame[SUMH_FRAME_SIZE - 2] == 0))) {
return false;
return SERIAL_RX_FRAME_PENDING;
}
for (channelIndex = 0; channelIndex < SUMH_MAX_CHANNEL_COUNT; channelIndex++) {
@ -116,7 +116,7 @@ bool sumhFrameComplete(void)
sumhChannels[channelIndex] = (((uint32_t)(sumhFrame[(channelIndex << 1) + 3]) << 8)
+ sumhFrame[(channelIndex << 1) + 4]) / 6.4 - 375;
}
return true;
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View file

@ -17,4 +17,4 @@
#pragma once
bool sumhFrameComplete(void);
uint8_t sumhFrameStatus(void);

View file

@ -292,9 +292,9 @@ static void xBusDataReceive(uint16_t c)
}
// Indicate time to read a frame from the data...
bool xBusFrameComplete(void)
uint8_t xBusFrameStatus(void)
{
return xBusFrameReceived;
return xBusFrameReceived ? SERIAL_RX_FRAME_COMPLETE : SERIAL_RX_FRAME_PENDING;
}
static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View file

@ -20,4 +20,4 @@
#include "rx/rx.h"
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
bool xBusFrameComplete(void);
uint8_t xBusFrameStatus(void);