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

BUGFIX - pwmReadRawRC was broken in

2d248676f5. MSP RX ignored rc channel
mapping.

Symptoms: power up FC using parallel PWM or PPM with no receiver
attached.  Connect GUI tool to view receiver data.  Observe that each
channel has a reading of '2' instead of somewhere near 'midrc'.

Symptoms: rxMsp ignored rc channel map, cli 'map' command had no effect.

This commit re-instates the code that checked to see if an rc channel
value was in the correct range but moved it into computeRC where it
really belongs.

Additionally to the code to remap rc channels was moved from the rx
implementations into the computeRc method.  This results in smaller code
size, no duplication of logic avoids having to pass rxConfig to each rx
read method and finally fixes rxMsp so that channel mapping can be used.

Failsafe still works as intended, verified by using parallel PWM, arming
and then pulling out the throttle PWM inpout cable.

This also improves code cleanliness since now each rawRawRc method in
the RX implementations does not have to remap the channels.  The methods
now do only what their name says.
This commit is contained in:
Dominic Clifton 2014-05-08 11:54:20 +01:00
parent 35f7ce06f3
commit 3ed979e88c
7 changed files with 35 additions and 21 deletions

View file

@ -86,13 +86,19 @@ bool isSerialRxFrameComplete(rxConfig_t *rxConfig)
return false; return false;
} }
uint8_t calculateChannelRemapping(uint8_t *rcmap, uint8_t channelToRemap) {
return rcmap[channelToRemap];
}
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{ {
uint8_t chan; uint8_t chan;
if (feature(FEATURE_SERIALRX)) { if (feature(FEATURE_SERIALRX)) {
for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
rcData[chan] = rcReadRawFunc(rxConfig, rxRuntimeConfig, chan); uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan);
rcData[chan] = rcReadRawFunc(rxRuntimeConfig, rawChannel);
}
} else { } else {
static int16_t rcSamples[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT], rcDataMean[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT]; static int16_t rcSamples[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT], rcDataMean[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT];
static uint8_t rcSampleIndex = 0; static uint8_t rcSampleIndex = 0;
@ -103,8 +109,16 @@ void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) { for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan);
// sample the channel // sample the channel
rcSamples[chan][currentSampleIndex] = rcReadRawFunc(rxConfig, rxRuntimeConfig, chan); uint16_t sample = rcReadRawFunc(rxRuntimeConfig, rawChannel);
// validate the range
if (sample < 750 || sample > 2250)
sample = rxConfig->midrc;
rcSamples[chan][currentSampleIndex] = sample;
// compute the average of recent samples // compute the average of recent samples
rcDataMean[chan] = 0; rcDataMean[chan] = 0;

View file

@ -38,7 +38,7 @@ typedef struct rxRuntimeConfig_s {
extern rxRuntimeConfig_t rxRuntimeConfig; extern rxRuntimeConfig_t rxRuntimeConfig;
typedef uint16_t (* rcReadRawDataPtr)(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data typedef uint16_t (* rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);

View file

@ -18,7 +18,7 @@ failsafe_t *failsafe;
static bool rxMspFrameDone = false; static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan) static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
return rcData[chan]; return rcData[chan];
} }

View file

@ -15,9 +15,9 @@
#include "rx_common.h" #include "rx_common.h"
#include "rx_pwm.h" #include "rx_pwm.h"
static uint16_t pwmReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan) static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
return pwmRead(rxConfig->rcmap[chan]); return pwmRead(chan);
} }
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback) void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback)

View file

@ -23,7 +23,7 @@
static bool sbusFrameDone = false; static bool sbusFrameDone = false;
static void sbusDataReceive(uint16_t c); static void sbusDataReceive(uint16_t c);
static uint16_t sbusReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL]; static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
@ -117,8 +117,8 @@ bool sbusFrameComplete(void)
return false; return false;
} }
static uint16_t sbusReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan) static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
return sbusChannelData[rxConfig->rcmap[chan]] / 2 + SBUS_OFFSET; return sbusChannelData[chan] / 2 + SBUS_OFFSET;
} }

View file

@ -31,7 +31,7 @@ static bool spekDataIncoming = false;
volatile uint8_t spekFrame[SPEK_FRAME_SIZE]; volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
static void spektrumDataReceive(uint16_t c); static void spektrumDataReceive(uint16_t c);
static uint16_t spektrumReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
failsafe_t *failsafe; failsafe_t *failsafe;
@ -88,7 +88,7 @@ bool spektrumFrameComplete(void)
return rcFrameComplete; return rcFrameComplete;
} }
static uint16_t spektrumReadRawRC(rxConfig_t*rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan) static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
uint16_t data; uint16_t data;
static uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT]; static uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
@ -104,13 +104,13 @@ static uint16_t spektrumReadRawRC(rxConfig_t*rxConfig, rxRuntimeConfig_t *rxRunt
} }
if (chan >= rxRuntimeConfig->channelCount || !spekDataIncoming) { if (chan >= rxRuntimeConfig->channelCount || !spekDataIncoming) {
data = rxConfig->midrc; return 0;
} else {
if (spekHiRes)
data = 988 + (spekChannelData[rxConfig->rcmap[chan]] >> 1); // 2048 mode
else
data = 988 + spekChannelData[rxConfig->rcmap[chan]]; // 1024 mode
} }
if (spekHiRes)
data = 988 + (spekChannelData[chan] >> 1); // 2048 mode
else
data = 988 + spekChannelData[chan]; // 1024 mode
return data; return data;
} }

View file

@ -22,7 +22,7 @@
static bool sumdFrameDone = false; static bool sumdFrameDone = false;
static void sumdDataReceive(uint16_t c); static void sumdDataReceive(uint16_t c);
static uint16_t sumdReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint32_t sumdChannelData[SUMD_MAX_CHANNEL]; static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
@ -89,7 +89,7 @@ bool sumdFrameComplete(void)
return false; return false;
} }
static uint16_t sumdReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan) static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
return sumdChannelData[rxConfig->rcmap[chan]] / 8; return sumdChannelData[chan] / 8;
} }