1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Cleaned up RX initialisation. Updated Spektrum RX code to support 12

channels when using Spektrum 2048 - untested.  Renamed and extracted
core_t.numRCChannels to rxConfig.channelCount so that future commits can
clean up core_t further since core_t contains completely unrelated
properties.
This commit is contained in:
Dominic Clifton 2014-04-18 17:25:53 +01:00
parent d777bac39d
commit f68fc17627
16 changed files with 137 additions and 74 deletions

View file

@ -71,6 +71,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
gps_common.c \ gps_common.c \
runtime_config.c \ runtime_config.c \
rx_common.c \ rx_common.c \
rx_pwm.c \
rx_sbus.c \ rx_sbus.c \
rx_sumd.c \ rx_sumd.c \
rx_spektrum.c \ rx_spektrum.c \

View file

@ -159,7 +159,7 @@ int16_t servoMiddle(int nr)
{ {
// Normally, servo.middle is a value between 1000..2000, but for the purposes of stupid, if it's less than // Normally, servo.middle is a value between 1000..2000, but for the purposes of stupid, if it's less than
// the number of RC channels, it means the center value is taken FROM that RC channel (by its index) // the number of RC channels, it means the center value is taken FROM that RC channel (by its index)
if (cfg.servoConf[nr].middle < RC_CHANS && nr < MAX_SERVOS) if (cfg.servoConf[nr].middle < MAX_SUPPORTED_RC_CHANNEL_COUNT && nr < MAX_SERVOS)
return rcData[cfg.servoConf[nr].middle]; return rcData[cfg.servoConf[nr].middle];
else else
return cfg.servoConf[nr].middle; return cfg.servoConf[nr].middle;

View file

@ -78,14 +78,13 @@ static void gpsSetState(uint8_t state)
gpsData.state_ts = millis(); gpsData.state_ts = millis();
} }
// When using PWM input GPS usage reduces number of available channels by 2 - see pwm_common.c/pwmInit()
void gpsInit(uint8_t baudrateIndex) void gpsInit(uint8_t baudrateIndex)
{ {
portMode_t mode = MODE_RXTX; portMode_t mode = MODE_RXTX;
// init gpsData structure. if we're not actually enabled, don't bother doing anything else // init gpsData structure. if we're not actually enabled, don't bother doing anything else
gpsSetState(GPS_UNKNOWN); gpsSetState(GPS_UNKNOWN);
if (!feature(FEATURE_GPS))
return;
gpsData.baudrateIndex = baudrateIndex; gpsData.baudrateIndex = baudrateIndex;
gpsData.lastMessage = millis(); gpsData.lastMessage = millis();

View file

@ -3,9 +3,6 @@
#include "mw.h" #include "mw.h"
#include "gps_common.h" #include "gps_common.h"
#include "rx_sbus.h"
#include "rx_sumd.h"
#include "rx_spektrum.h"
#include "rx_common.h" #include "rx_common.h"
#include "telemetry_common.h" #include "telemetry_common.h"
#include "boardalignment.h" #include "boardalignment.h"
@ -53,7 +50,7 @@ int main(void)
pwm_params.airplane = true; pwm_params.airplane = true;
else else
pwm_params.airplane = false; pwm_params.airplane = false;
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SERIALRX); // spektrum/sbus support uses UART too pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SERIALRX); // serial rx support uses UART too
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
pwm_params.usePPM = feature(FEATURE_PPM); pwm_params.usePPM = feature(FEATURE_PPM);
pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum
@ -82,30 +79,12 @@ int main(void)
pwmInit(&pwm_params); pwmInit(&pwm_params);
// configure PWM/CPPM read function and max number of channels. spektrum or sbus below will override both of these, if enabled rxInit(&mcfg.rxConfig);
for (i = 0; i < RC_CHANS; i++)
rcData[i] = 1502;
rcReadRawFunc = pwmReadRawRC;
core.numRCChannels = MAX_INPUTS;
if (feature(FEATURE_SERIALRX)) { if (feature(FEATURE_GPS) && !feature(FEATURE_SERIALRX)) {
switch (mcfg.rxConfig.serialrx_type) {
case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048:
spektrumInit(&mcfg.rxConfig, &rcReadRawFunc);
break;
case SERIALRX_SBUS:
sbusInit(&mcfg.rxConfig, &rcReadRawFunc);
break;
case SERIALRX_SUMD:
sumdInit(&mcfg.rxConfig, &rcReadRawFunc);
break;
}
} else { // spektrum and GPS are mutually exclusive
// Optional GPS - available in both PPM and PWM input mode, in PWM input, reduces number of available channels by 2.
// gpsInit will return if FEATURE_GPS is not enabled.
gpsInit(mcfg.gps_baudrate); gpsInit(mcfg.gps_baudrate);
} }
#ifdef SONAR #ifdef SONAR
// sonar stuff only works with PPM // sonar stuff only works with PPM
if (feature(FEATURE_PPM)) { if (feature(FEATURE_PPM)) {

View file

@ -395,7 +395,7 @@ void loop(void)
if (((int32_t)(currentTime - rcTime) >= 0) || rcReady) { // 50Hz or data driven if (((int32_t)(currentTime - rcTime) >= 0) || rcReady) { // 50Hz or data driven
rcReady = false; rcReady = false;
rcTime = currentTime + 20000; rcTime = currentTime + 20000;
computeRC(&mcfg.rxConfig); computeRC(&mcfg.rxConfig, &rxRuntimeConfig);
// in 3D mode, we need to be able to disarm by switch at any time // in 3D mode, we need to be able to disarm by switch at any time
if (feature(FEATURE_3D)) { if (feature(FEATURE_3D)) {

View file

@ -54,7 +54,6 @@ typedef struct core_t {
serialPort_t *telemport; serialPort_t *telemport;
serialPort_t *rcvrport; serialPort_t *rcvrport;
uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver. uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver.
uint8_t numRCChannels; // number of rc channels as reported by current input driver
bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this
} core_t; } core_t;

View file

@ -9,47 +9,81 @@
#include "rx_common.h" #include "rx_common.h"
#include "config.h" #include "config.h"
#include "drivers/pwm_common.h" #include "rx_pwm.h"
#include "rx_sbus.h"
#include "rx_spektrum.h"
#include "rx_sumd.h"
const char rcChannelLetters[] = "AERT1234"; const char rcChannelLetters[] = "AERT1234";
int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
int16_t rcData[RC_CHANS]; // interval [1000;2000] int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
#define PPM_AND_PWM_SAMPLE_COUNT 4
rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers) rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
uint16_t pwmReadRawRC(rxConfig_t *rxConfig, uint8_t chan) rxRuntimeConfig_t rxRuntimeConfig;
void rxInit(rxConfig_t *rxConfig)
{ {
uint16_t data; uint8_t i;
data = pwmRead(rxConfig->rcmap[chan]); for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
if (data < 750 || data > 2250) rcData[i] = rxConfig->midrc;
data = rxConfig->midrc; }
return data; if (feature(FEATURE_SERIALRX)) {
serialRxInit(rxConfig);
} else {
pwmRxInit(&rxRuntimeConfig, &rcReadRawFunc);
}
}
void serialRxInit(rxConfig_t *rxConfig)
{
switch (rxConfig->serialrx_type) {
case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048:
spektrumInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break;
case SERIALRX_SBUS:
sbusInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break;
case SERIALRX_SUMD:
sumdInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
break;
}
} }
void computeRC(rxConfig_t *rxConfig) 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 < 8; chan++) for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++)
rcData[chan] = rcReadRawFunc(rxConfig, chan); rcData[chan] = rcReadRawFunc(rxConfig, rxRuntimeConfig, chan);
} else { } else {
static int16_t rcData4Values[8][4], rcDataMean[8]; 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 rc4ValuesIndex = 0; static uint8_t rcSampleIndex = 0;
uint8_t a; uint8_t a;
rc4ValuesIndex++; rcSampleIndex++;
for (chan = 0; chan < 8; chan++) { uint8_t currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
rcData4Values[chan][rc4ValuesIndex % 4] = rcReadRawFunc(rxConfig, chan);
rcDataMean[chan] = 0; for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
for (a = 0; a < 4; a++)
rcDataMean[chan] += rcData4Values[chan][a]; // sample the channel
rcSamples[chan][currentSampleIndex] = rcReadRawFunc(rxConfig, rxRuntimeConfig, chan);
// compute the average of recent samples
rcDataMean[chan] = 0;
for (a = 0; a < PPM_AND_PWM_SAMPLE_COUNT; a++)
rcDataMean[chan] += rcSamples[chan][a];
rcDataMean[chan] = (rcDataMean[chan] + 2) / PPM_AND_PWM_SAMPLE_COUNT;
rcDataMean[chan] = (rcDataMean[chan] + 2) / 4;
if (rcDataMean[chan] < rcData[chan] - 3) if (rcDataMean[chan] < rcData[chan] - 3)
rcData[chan] = rcDataMean[chan] + 2; rcData[chan] = rcDataMean[chan] + 2;
if (rcDataMean[chan] > rcData[chan] + 3) if (rcDataMean[chan] > rcData[chan] + 3)

View file

@ -31,9 +31,10 @@ typedef enum {
SERIALRX_SUMD = 3, SERIALRX_SUMD = 3,
} SerialRXType; } SerialRXType;
#define RC_CHANS (18) #define MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT 8
#define MAX_SUPPORTED_RC_CHANNEL_COUNT (18)
extern int16_t rcData[RC_CHANS]; // interval [1000;2000] extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
typedef struct rxConfig_s { typedef struct rxConfig_s {
uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order
@ -52,15 +53,23 @@ typedef struct controlRateConfig_s {
uint8_t yawRate; uint8_t yawRate;
} controlRateConfig_t; } controlRateConfig_t;
typedef struct rxRuntimeConfig_s {
uint8_t channelCount; // number of rc channels as reported by current input driver
} rxRuntimeConfig_t;
#define PITCH_LOOKUP_LENGTH 7 #define PITCH_LOOKUP_LENGTH 7
#define THROTTLE_LOOKUP_LENGTH 12 #define THROTTLE_LOOKUP_LENGTH 12
extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL extern int16_t lookupPitchRollRC[PITCH_LOOKUP_LENGTH]; // lookup table for expo & RC rate PITCH+ROLL
extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE extern int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
typedef uint16_t (* rcReadRawDataPtr)(rxConfig_t *rxConfig, uint8_t chan); // used by receiver driver to return channel data extern rxRuntimeConfig_t rxRuntimeConfig;
uint16_t pwmReadRawRC(rxConfig_t *rxConfig, uint8_t chan); typedef uint16_t (* rcReadRawDataPtr)(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
void computeRC(rxConfig_t *rxConfig);
void rxInit(rxConfig_t *rxConfig);
void serialRxInit(rxConfig_t *rxConfig);
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
void generatePitchCurve(controlRateConfig_t *controlRateConfig); void generatePitchCurve(controlRateConfig_t *controlRateConfig);
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, uint16_t minThrottle, uint16_t maxThrottle); void generateThrottleCurve(controlRateConfig_t *controlRateConfig, uint16_t minThrottle, uint16_t maxThrottle);

33
src/rx_pwm.c Normal file
View file

@ -0,0 +1,33 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "rx_common.h"
#include "config.h"
#include "drivers/pwm_common.h"
#include "rx_pwm.h"
static uint16_t pwmReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
uint16_t data;
data = pwmRead(rxConfig->rcmap[chan]);
if (data < 750 || data > 2250)
data = rxConfig->midrc;
return data;
}
void pwmRxInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
*callback = pwmReadRawRC;
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT;
}

3
src/rx_pwm.h Normal file
View file

@ -0,0 +1,3 @@
#pragma once
void pwmRxInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);

View file

@ -23,13 +23,13 @@
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, uint8_t chan); static uint16_t sbusReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL]; static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
//rxConfig_t *rxConfig; //rxConfig_t *rxConfig;
void sbusInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback) void sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
int b; int b;
@ -40,7 +40,7 @@ void sbusInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback)
core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS)); core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS));
if (callback) if (callback)
*callback = sbusReadRawRC; *callback = sbusReadRawRC;
core.numRCChannels = SBUS_MAX_CHANNEL; rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
} }
struct sbus_dat struct sbus_dat
@ -116,7 +116,7 @@ bool sbusFrameComplete(void)
return false; return false;
} }
static uint16_t sbusReadRawRC(rxConfig_t *rxConfig, uint8_t chan) static uint16_t sbusReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
return sbusChannelData[rxConfig->rcmap[chan]] / 2 + SBUS_OFFSET; return sbusChannelData[rxConfig->rcmap[chan]] / 2 + SBUS_OFFSET;
} }

View file

@ -1,4 +1,4 @@
#pragma once #pragma once
void sbusInit(rxConfig_t *initialRxConfig, rcReadRawDataPtr *callback); void sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
bool sbusFrameComplete(void); bool sbusFrameComplete(void);

View file

@ -17,7 +17,10 @@
// driver for spektrum satellite receiver / sbus using UART2 (freeing up more motor outputs for stuff) // driver for spektrum satellite receiver / sbus using UART2 (freeing up more motor outputs for stuff)
#define SPEK_MAX_CHANNEL 7 #define SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT 12
#define SPEKTRUM_2048_CHANNEL_COUNT 12
#define SPEKTRUM_1024_CHANNEL_COUNT 7
#define SPEK_FRAME_SIZE 16 #define SPEK_FRAME_SIZE 16
static uint8_t spek_chan_shift; static uint8_t spek_chan_shift;
@ -29,9 +32,9 @@ 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, uint8_t chan); static uint16_t spektrumReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
void spektrumInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback) void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
switch (rxConfig->serialrx_type) { switch (rxConfig->serialrx_type) {
case SERIALRX_SPEKTRUM2048: case SERIALRX_SPEKTRUM2048:
@ -39,19 +42,20 @@ void spektrumInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback)
spek_chan_shift = 3; spek_chan_shift = 3;
spek_chan_mask = 0x07; spek_chan_mask = 0x07;
spekHiRes = true; spekHiRes = true;
rxRuntimeConfig->channelCount = SPEKTRUM_2048_CHANNEL_COUNT;
break; break;
case SERIALRX_SPEKTRUM1024: case SERIALRX_SPEKTRUM1024:
// 10 bit frames // 10 bit frames
spek_chan_shift = 2; spek_chan_shift = 2;
spek_chan_mask = 0x03; spek_chan_mask = 0x03;
spekHiRes = false; spekHiRes = false;
rxRuntimeConfig->channelCount = SPEKTRUM_1024_CHANNEL_COUNT;
break; break;
} }
core.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX); core.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX);
if (callback) if (callback)
*callback = spektrumReadRawRC; *callback = spektrumReadRawRC;
core.numRCChannels = SPEK_MAX_CHANNEL;
} }
// Receive ISR callback // Receive ISR callback
@ -81,22 +85,22 @@ bool spektrumFrameComplete(void)
return rcFrameComplete; return rcFrameComplete;
} }
static uint16_t spektrumReadRawRC(rxConfig_t*rxConfig, uint8_t chan) static uint16_t spektrumReadRawRC(rxConfig_t*rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
uint16_t data; uint16_t data;
static uint32_t spekChannelData[SPEK_MAX_CHANNEL]; static uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
uint8_t b; uint8_t b;
if (rcFrameComplete) { if (rcFrameComplete) {
for (b = 3; b < SPEK_FRAME_SIZE; b += 2) { for (b = 3; b < SPEK_FRAME_SIZE; b += 2) {
uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift); uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift);
if (spekChannel < SPEK_MAX_CHANNEL) if (spekChannel < rxRuntimeConfig->channelCount && spekChannel < SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT)
spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b]; spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b];
} }
rcFrameComplete = false; rcFrameComplete = false;
} }
if (chan >= SPEK_MAX_CHANNEL || !spekDataIncoming) { if (chan >= rxRuntimeConfig->channelCount || !spekDataIncoming) {
data = rxConfig->midrc; data = rxConfig->midrc;
} else { } else {
if (spekHiRes) if (spekHiRes)

View file

@ -1,4 +1,4 @@
#pragma once #pragma once
void spektrumInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback); void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
bool spektrumFrameComplete(void); bool spektrumFrameComplete(void);

View file

@ -22,15 +22,17 @@
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, uint8_t chan); static uint16_t sumdReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint32_t sumdChannelData[SUMD_MAX_CHANNEL]; static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
void sumdInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback) void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{ {
core.rcvrport = uartOpen(USART2, sumdDataReceive, 115200, MODE_RX); core.rcvrport = uartOpen(USART2, sumdDataReceive, 115200, MODE_RX);
if (callback) if (callback)
*callback = sumdReadRawRC; *callback = sumdReadRawRC;
rxRuntimeConfig->channelCount = SUMD_MAX_CHANNEL;
} }
static uint8_t sumd[SUMD_BUFFSIZE] = { 0, }; static uint8_t sumd[SUMD_BUFFSIZE] = { 0, };
@ -83,7 +85,7 @@ bool sumdFrameComplete(void)
return false; return false;
} }
static uint16_t sumdReadRawRC(rxConfig_t *rxConfig, uint8_t chan) static uint16_t sumdReadRawRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{ {
return sumdChannelData[rxConfig->rcmap[chan]] / 8; return sumdChannelData[rxConfig->rcmap[chan]] / 8;
} }

View file

@ -1,4 +1,4 @@
#pragma once #pragma once
void sumdInit(rxConfig_t *rxConfig, rcReadRawDataPtr *callback); void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
bool sumdFrameComplete(void); bool sumdFrameComplete(void);