mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 03:20:00 +03:00
reorganization of uart-based receiver drivers
FEATURE_SPEKTRUM has been removed and replaced with FEATURE_SERIALRX. cli option serialrx_type now configures what type of receiver it is 0 = spektrum1024, 1 = spektrum2048, 2 = sbus sbus will need hardware inverter to use. also cleaned up receiver drivers to assign readrawRC callback instead of assigning in code in main() none of this has been tested. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@418 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
04ab548d2e
commit
2272e1a5a6
10 changed files with 191 additions and 31 deletions
1
Makefile
1
Makefile
|
@ -52,6 +52,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
|
|||
mw.c \
|
||||
sensors.c \
|
||||
serial.c \
|
||||
sbus.c \
|
||||
spektrum.c \
|
||||
telemetry.c \
|
||||
drv_gpio.c \
|
||||
|
|
|
@ -467,6 +467,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\utils.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>sbus.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\sbus.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -1308,6 +1313,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\utils.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>sbus.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\sbus.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -2093,6 +2103,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\utils.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>sbus.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\sbus.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
|
|
@ -62,7 +62,7 @@ typedef enum {
|
|||
FEATURE_PPM = 1 << 0,
|
||||
FEATURE_VBAT = 1 << 1,
|
||||
FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
|
||||
FEATURE_SPEKTRUM = 1 << 3,
|
||||
FEATURE_SERIALRX = 1 << 3,
|
||||
FEATURE_MOTOR_STOP = 1 << 4,
|
||||
FEATURE_SERVO_TILT = 1 << 5,
|
||||
FEATURE_GYRO_SMOOTHING = 1 << 6,
|
||||
|
@ -76,6 +76,12 @@ typedef enum {
|
|||
FEATURE_3D = 1 << 14,
|
||||
} AvailableFeatures;
|
||||
|
||||
typedef enum {
|
||||
SERIALRX_SPEKTRUM1024 = 0,
|
||||
SERIALRX_SPEKTRUM2048 = 1,
|
||||
SERIALRX_SBUS = 2,
|
||||
} SerialRXType;
|
||||
|
||||
typedef enum {
|
||||
GPS_NMEA = 0,
|
||||
GPS_UBLOX,
|
||||
|
|
|
@ -42,7 +42,7 @@ static const char * const mixerNames[] = {
|
|||
|
||||
// sync this with AvailableFeatures enum from board.h
|
||||
static const char * const featureNames[] = {
|
||||
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SPEKTRUM", "MOTOR_STOP",
|
||||
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP",
|
||||
"SERVO_TILT", "GYRO_SMOOTHING", "LED_RING", "GPS",
|
||||
"FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D",
|
||||
NULL
|
||||
|
@ -116,7 +116,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "retarded_arm", VAR_UINT8, &mcfg.retarded_arm, 0, 1 },
|
||||
{ "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 },
|
||||
{ "gps_baudrate", VAR_UINT32, &mcfg.gps_baudrate, 1200, 115200 },
|
||||
{ "spektrum_hires", VAR_UINT8, &mcfg.spektrum_hires, 0, 1 },
|
||||
{ "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 2 },
|
||||
{ "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 },
|
||||
{ "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 },
|
||||
{ "vbatmincellvoltage", VAR_UINT8, &mcfg.vbatmincellvoltage, 10, 50 },
|
||||
|
|
|
@ -188,7 +188,7 @@ static void resetConf(void)
|
|||
mcfg.vbatmaxcellvoltage = 43;
|
||||
mcfg.vbatmincellvoltage = 33;
|
||||
mcfg.power_adc_channel = 0;
|
||||
mcfg.spektrum_hires = 0;
|
||||
mcfg.serialrx_type = 0;
|
||||
mcfg.midrc = 1500;
|
||||
mcfg.mincheck = 1100;
|
||||
mcfg.maxcheck = 1900;
|
||||
|
|
23
src/main.c
23
src/main.c
|
@ -5,9 +5,8 @@ core_t core;
|
|||
|
||||
extern rcReadRawDataPtr rcReadRawFunc;
|
||||
|
||||
// two receiver read functions
|
||||
// receiver read function
|
||||
extern uint16_t pwmReadRawRC(uint8_t chan);
|
||||
extern uint16_t spektrumReadRawRC(uint8_t chan);
|
||||
|
||||
#ifdef USE_LAME_PRINTF
|
||||
// gcc/GNU version
|
||||
|
@ -59,9 +58,9 @@ int main(void)
|
|||
pwm_params.airplane = true;
|
||||
else
|
||||
pwm_params.airplane = false;
|
||||
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SPEKTRUM); // spektrum support uses UART too
|
||||
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SERIALRX); // spektrum/sbus support uses UART too
|
||||
pwm_params.usePPM = feature(FEATURE_PPM);
|
||||
pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum
|
||||
pwm_params.enableInput = !feature(FEATURE_SERIALRX); // disable inputs if using spektrum
|
||||
pwm_params.useServos = core.useServo;
|
||||
pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX;
|
||||
pwm_params.motorPwmRate = mcfg.motor_pwm_rate;
|
||||
|
@ -81,12 +80,20 @@ int main(void)
|
|||
|
||||
pwmInit(&pwm_params);
|
||||
|
||||
// configure PWM/CPPM read function. spektrum below will override that
|
||||
// configure PWM/CPPM read function. spektrum or sbus below will override that
|
||||
rcReadRawFunc = pwmReadRawRC;
|
||||
|
||||
if (feature(FEATURE_SPEKTRUM)) {
|
||||
spektrumInit();
|
||||
rcReadRawFunc = spektrumReadRawRC;
|
||||
if (feature(FEATURE_SERIALRX)) {
|
||||
switch (mcfg.serialrx_type) {
|
||||
case SERIALRX_SPEKTRUM1024:
|
||||
case SERIALRX_SPEKTRUM2048:
|
||||
spektrumInit(&rcReadRawFunc);
|
||||
break;
|
||||
|
||||
case SERIALRX_SBUS:
|
||||
sbusInit(&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.
|
||||
|
|
20
src/mw.c
20
src/mw.c
|
@ -436,14 +436,26 @@ void loop(void)
|
|||
static uint8_t GPSNavReset = 1;
|
||||
bool isThrottleLow = false;
|
||||
|
||||
// this will return false if spektrum is disabled. shrug.
|
||||
if (spektrumFrameComplete())
|
||||
computeRC();
|
||||
// calculate rc stuff from serial-based receivers (spek/sbus)
|
||||
if (feature(FEATURE_SERIALRX)) {
|
||||
bool ready = false;
|
||||
switch (mcfg.serialrx_type) {
|
||||
case SERIALRX_SPEKTRUM1024:
|
||||
case SERIALRX_SPEKTRUM2048:
|
||||
ready = spektrumFrameComplete();
|
||||
break;
|
||||
case SERIALRX_SBUS:
|
||||
ready = sbusFrameComplete();
|
||||
break;
|
||||
}
|
||||
if (ready)
|
||||
computeRC();
|
||||
}
|
||||
|
||||
if ((int32_t)(currentTime - rcTime) >= 0) { // 50Hz
|
||||
rcTime = currentTime + 20000;
|
||||
// TODO clean this up. computeRC should handle this check
|
||||
if (!feature(FEATURE_SPEKTRUM))
|
||||
if (!feature(FEATURE_SERIALRX))
|
||||
computeRC();
|
||||
|
||||
// in 3D mode, we need to be able to disarm by switch at any time
|
||||
|
|
8
src/mw.h
8
src/mw.h
|
@ -273,7 +273,7 @@ typedef struct master_t {
|
|||
|
||||
// Radio/ESC-related configuration
|
||||
uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order
|
||||
uint8_t spektrum_hires; // spektrum high-resolution y/n (1024/2048bit)
|
||||
uint8_t serialrx_type; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_SERIALRX first.
|
||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||
uint16_t mincheck; // minimum rc end
|
||||
uint16_t maxcheck; // maximum rc end
|
||||
|
@ -448,9 +448,13 @@ void featureClearAll(void);
|
|||
uint32_t featureMask(void);
|
||||
|
||||
// spektrum
|
||||
void spektrumInit(void);
|
||||
void spektrumInit(rcReadRawDataPtr *callback);
|
||||
bool spektrumFrameComplete(void);
|
||||
|
||||
// sbus
|
||||
void sbusInit(rcReadRawDataPtr *callback);
|
||||
bool sbusFrameComplete(void);
|
||||
|
||||
// buzzer
|
||||
void buzzer(uint8_t warn_vbat);
|
||||
|
||||
|
|
108
src/sbus.c
Normal file
108
src/sbus.c
Normal file
|
@ -0,0 +1,108 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
// driver for SBUS receiver using UART2
|
||||
|
||||
#define SBUS_MAX_CHANNEL 8
|
||||
#define SBUS_FRAME_SIZE 25
|
||||
#define SBUS_SYNCBYTE 0x0F
|
||||
#define SBUS_ENDBYTE 0x00
|
||||
#define SBUS_OFFSET 988
|
||||
|
||||
static bool sbusFrameDone = false;
|
||||
static void sbusDataReceive(uint16_t c);
|
||||
static uint16_t sbusReadRawRC(uint8_t chan);
|
||||
|
||||
// external vars (ugh)
|
||||
extern int16_t failsafeCnt;
|
||||
|
||||
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
|
||||
|
||||
void sbusInit(rcReadRawDataPtr *callback)
|
||||
{
|
||||
int b;
|
||||
for (b = 0; b < SBUS_MAX_CHANNEL; b ++)
|
||||
sbusChannelData[b] = 2 * (mcfg.midrc - SBUS_OFFSET);
|
||||
core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, MODE_RX);
|
||||
if (callback)
|
||||
*callback = sbusReadRawRC;
|
||||
}
|
||||
|
||||
struct sbus_dat
|
||||
{
|
||||
unsigned int chan0 : 11;
|
||||
unsigned int chan1 : 11;
|
||||
unsigned int chan2 : 11;
|
||||
unsigned int chan3 : 11;
|
||||
unsigned int chan4 : 11;
|
||||
unsigned int chan5 : 11;
|
||||
unsigned int chan6 : 11;
|
||||
unsigned int chan7 : 11;
|
||||
unsigned int chan8 : 11;
|
||||
unsigned int chan9 : 11;
|
||||
unsigned int chan10 : 11;
|
||||
unsigned int chan11 : 11;
|
||||
} __attribute__ ((__packed__));
|
||||
|
||||
typedef union
|
||||
{
|
||||
uint8_t in[SBUS_FRAME_SIZE];
|
||||
struct sbus_dat msg;
|
||||
} sbus_msg;
|
||||
|
||||
static sbus_msg sbus;
|
||||
|
||||
// Receive ISR callback
|
||||
static void sbusDataReceive(uint16_t c)
|
||||
{
|
||||
uint32_t sbusTime;
|
||||
static uint32_t sbusTimeLast;
|
||||
static uint8_t sbusFramePosition;
|
||||
|
||||
sbusTime = micros();
|
||||
if ((sbusTime - sbusTimeLast) > 4000)
|
||||
sbusFramePosition = 0;
|
||||
sbusTimeLast = sbusTime;
|
||||
|
||||
if (sbusFramePosition == 0 && c != SBUS_SYNCBYTE)
|
||||
return;
|
||||
|
||||
sbusFrameDone = false; // lazy main loop didnt fetch the stuff
|
||||
if (sbusFramePosition != 0)
|
||||
sbus.in[sbusFramePosition - 1] = (uint8_t)c;
|
||||
|
||||
if (sbusFramePosition == SBUS_FRAME_SIZE - 1) {
|
||||
if (sbus.in[sbusFramePosition - 1] == SBUS_ENDBYTE)
|
||||
sbusFrameDone = true;
|
||||
sbusFramePosition = 0;
|
||||
} else {
|
||||
sbusFramePosition++;
|
||||
}
|
||||
}
|
||||
|
||||
bool sbusFrameComplete(void)
|
||||
{
|
||||
if (sbusFrameDone) {
|
||||
if (!((sbus.in[22] >> 3) & 0x0001)) { // failsave flag
|
||||
failsafeCnt = 0; // clear FailSafe counter
|
||||
sbusChannelData[0] = sbus.msg.chan0;
|
||||
sbusChannelData[1] = sbus.msg.chan1;
|
||||
sbusChannelData[2] = sbus.msg.chan2;
|
||||
sbusChannelData[3] = sbus.msg.chan3;
|
||||
sbusChannelData[4] = sbus.msg.chan4;
|
||||
sbusChannelData[5] = sbus.msg.chan5;
|
||||
sbusChannelData[6] = sbus.msg.chan6;
|
||||
sbusChannelData[7] = sbus.msg.chan7;
|
||||
// need more channels? No problem. Add them.
|
||||
sbusFrameDone = false;
|
||||
return true;
|
||||
}
|
||||
sbusFrameDone = false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static uint16_t sbusReadRawRC(uint8_t chan)
|
||||
{
|
||||
return sbusChannelData[mcfg.rcmap[chan]] / 2 + SBUS_OFFSET;
|
||||
}
|
|
@ -8,26 +8,35 @@
|
|||
static uint8_t spek_chan_shift;
|
||||
static uint8_t spek_chan_mask;
|
||||
static bool rcFrameComplete = false;
|
||||
static bool spekHiRes = false;
|
||||
static bool spekDataIncoming = false;
|
||||
volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
|
||||
static void spektrumDataReceive(uint16_t c);
|
||||
static uint16_t spektrumReadRawRC(uint8_t chan);
|
||||
|
||||
// external vars (ugh)
|
||||
extern int16_t failsafeCnt;
|
||||
|
||||
void spektrumInit(void)
|
||||
void spektrumInit(rcReadRawDataPtr *callback)
|
||||
{
|
||||
if (mcfg.spektrum_hires) {
|
||||
// 11 bit frames
|
||||
spek_chan_shift = 3;
|
||||
spek_chan_mask = 0x07;
|
||||
} else {
|
||||
// 10 bit frames
|
||||
spek_chan_shift = 2;
|
||||
spek_chan_mask = 0x03;
|
||||
switch (mcfg.serialrx_type) {
|
||||
case SERIALRX_SPEKTRUM2048:
|
||||
// 11 bit frames
|
||||
spek_chan_shift = 3;
|
||||
spek_chan_mask = 0x07;
|
||||
spekHiRes = true;
|
||||
break;
|
||||
case SERIALRX_SPEKTRUM1024:
|
||||
// 10 bit frames
|
||||
spek_chan_shift = 2;
|
||||
spek_chan_mask = 0x03;
|
||||
spekHiRes = false;
|
||||
break;
|
||||
}
|
||||
|
||||
core.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX);
|
||||
if (callback)
|
||||
*callback = spektrumReadRawRC;
|
||||
}
|
||||
|
||||
// Receive ISR callback
|
||||
|
@ -57,9 +66,7 @@ bool spektrumFrameComplete(void)
|
|||
return rcFrameComplete;
|
||||
}
|
||||
|
||||
// static const uint8_t spekRcChannelMap[SPEK_MAX_CHANNEL] = {1, 2, 3, 0, 4, 5, 6};
|
||||
|
||||
uint16_t spektrumReadRawRC(uint8_t chan)
|
||||
static uint16_t spektrumReadRawRC(uint8_t chan)
|
||||
{
|
||||
uint16_t data;
|
||||
static uint32_t spekChannelData[SPEK_MAX_CHANNEL];
|
||||
|
@ -77,7 +84,7 @@ uint16_t spektrumReadRawRC(uint8_t chan)
|
|||
if (chan >= SPEK_MAX_CHANNEL || !spekDataIncoming) {
|
||||
data = mcfg.midrc;
|
||||
} else {
|
||||
if (mcfg.spektrum_hires)
|
||||
if (spekHiRes)
|
||||
data = 988 + (spekChannelData[mcfg.rcmap[chan]] >> 1); // 2048 mode
|
||||
else
|
||||
data = 988 + spekChannelData[mcfg.rcmap[chan]]; // 1024 mode
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue