Totally rework software serial to provide tx at the same time as rx using only one timer.
First cut at polymorphic serial port implementation. Split serialPort_t into uartPort_t and serialPort_t. Calls to uartWrite() can now be replaced with calls to serialWrite(). Replacing calls to serialWriteByte(softSerial_t*, char) with calls to serialWrite(serialPort_t*, char). This completes the proof of concept for polymorphic serial port implementations (uartPort and softSerialPort). Renaming isSerialAvailable to uartTotalBytesWaiting. Renaming serialAvailable to softSerialTotalBytesWaiting. Adding serialTotalBytesWaiting to serial API and updating calls to the former methods to use the serial API. Renaming serialRead to softSerialRead. Adding serialRead to serial API and updating calls to uartRead and softSerialRead to use the serial API. Renamed uartPrint to serialPrint which now works on any serialPort implementation. Replacing calls to isUartTransmitEmpty with isSoftSerialTransmitBufferEmpty. Replacing remaing calls to uartWrite with serialWrite. Adding isSoftSerialTransmitBufferEmpty to the serial API. Adding serialSet/GetBaudRate to the serial API. Since softSerial does not implement serialSetBaudRate some GPS serial initialisation code has been updated. At this point it is probably possible to switch around all the ports and use a software serial implementation if desired. By Dominic Clifton / https://github.com/hydra/baseflight/ git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@423 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
7c595e4110
commit
28d5927836
1
Makefile
1
Makefile
|
@ -59,6 +59,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
|
|||
drv_i2c.c \
|
||||
drv_i2c_soft.c \
|
||||
drv_system.c \
|
||||
drv_serial.c \
|
||||
drv_uart.c \
|
||||
printf.c \
|
||||
utils.c \
|
||||
|
|
|
@ -672,6 +672,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_bma280.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_serial.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_serial.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -1518,6 +1523,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_bma280.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_serial.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_serial.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -2548,6 +2558,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_bma280.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_serial.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_serial.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
|
|
@ -126,7 +126,7 @@ typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init proto
|
|||
typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
||||
typedef void (* baroOpFuncPtr)(void); // baro start operation
|
||||
typedef void (* baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
|
||||
typedef void (* uartReceiveCallbackPtr)(uint16_t data); // used by uart2 driver to return frames to app
|
||||
typedef void (* serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
|
||||
typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data
|
||||
typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype
|
||||
|
||||
|
@ -244,6 +244,7 @@ typedef struct baro_t
|
|||
#include "drv_l3g4200d.h"
|
||||
#include "drv_pwm.h"
|
||||
#include "drv_timer.h"
|
||||
#include "drv_serial.h"
|
||||
#include "drv_uart.h"
|
||||
#include "drv_softserial.h"
|
||||
#else
|
||||
|
@ -264,6 +265,7 @@ typedef struct baro_t
|
|||
#include "drv_l3g4200d.h"
|
||||
#include "drv_pwm.h"
|
||||
#include "drv_timer.h"
|
||||
#include "drv_serial.h"
|
||||
#include "drv_uart.h"
|
||||
#include "drv_softserial.h"
|
||||
#include "drv_hcsr04.h"
|
||||
|
|
|
@ -931,8 +931,8 @@ void cliProcess(void)
|
|||
cliPrompt();
|
||||
}
|
||||
|
||||
while (isUartAvailable(core.mainport)) {
|
||||
uint8_t c = uartRead(core.mainport);
|
||||
while (serialTotalBytesWaiting(core.mainport)) {
|
||||
uint8_t c = serialRead(core.mainport);
|
||||
if (c == '\t' || c == '?') {
|
||||
// do tab completion
|
||||
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
|
||||
|
|
|
@ -325,7 +325,7 @@ bool pwmInit(drv_pwm_config_t *init)
|
|||
|
||||
#ifdef SOFTSERIAL_19200_LOOPBACK
|
||||
// skip softSerial ports
|
||||
if ((port == PWM5 || port == PWM6))
|
||||
if ((port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8))
|
||||
continue;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -0,0 +1,40 @@
|
|||
#include "board.h"
|
||||
|
||||
void serialPrint(serialPort_t *instance, const char *str)
|
||||
{
|
||||
uint8_t ch;
|
||||
while ((ch = *(str++))) {
|
||||
serialWrite(instance, ch);
|
||||
}
|
||||
}
|
||||
|
||||
inline uint32_t serialGetBaudRate(serialPort_t *instance)
|
||||
{
|
||||
return instance->baudRate;
|
||||
}
|
||||
|
||||
inline void serialWrite(serialPort_t *instance, uint8_t ch)
|
||||
{
|
||||
instance->vTable->serialWrite(instance, ch);
|
||||
}
|
||||
|
||||
inline uint8_t serialTotalBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->serialTotalBytesWaiting(instance);
|
||||
}
|
||||
|
||||
inline uint8_t serialRead(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->serialRead(instance);
|
||||
}
|
||||
|
||||
inline void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||
{
|
||||
instance->vTable->serialSetBaudRate(instance, baudRate);
|
||||
}
|
||||
|
||||
inline bool isSerialTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->isSerialTransmitBufferEmpty(instance);
|
||||
}
|
||||
|
|
@ -0,0 +1,48 @@
|
|||
#pragma once
|
||||
|
||||
typedef enum portMode_t {
|
||||
MODE_RX = 1,
|
||||
MODE_TX = 2,
|
||||
MODE_RXTX = MODE_RX | MODE_TX
|
||||
} portMode_t;
|
||||
|
||||
typedef struct serialPort {
|
||||
|
||||
const struct serialPortVTable *vTable;
|
||||
|
||||
portMode_t mode;
|
||||
uint32_t baudRate;
|
||||
|
||||
uint32_t rxBufferSize;
|
||||
uint32_t txBufferSize;
|
||||
volatile uint8_t *rxBuffer;
|
||||
volatile uint8_t *txBuffer;
|
||||
uint32_t rxBufferHead;
|
||||
uint32_t rxBufferTail;
|
||||
uint32_t txBufferHead;
|
||||
uint32_t txBufferTail;
|
||||
|
||||
// FIXME rename member to rxCallback
|
||||
serialReceiveCallbackPtr callback;
|
||||
} serialPort_t;
|
||||
|
||||
struct serialPortVTable {
|
||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||
|
||||
uint8_t (*serialTotalBytesWaiting)(serialPort_t *instance);
|
||||
|
||||
uint8_t (*serialRead)(serialPort_t *instance);
|
||||
|
||||
// Specified baud rate may not be allowed by an implementation, use serialGetBaudRate to determine actual baud rate in use.
|
||||
void (*serialSetBaudRate)(serialPort_t *instance, uint32_t baudRate);
|
||||
|
||||
bool (*isSerialTransmitBufferEmpty)(serialPort_t *instance);
|
||||
};
|
||||
|
||||
inline void serialWrite(serialPort_t *instance, uint8_t ch);
|
||||
inline uint8_t serialTotalBytesWaiting(serialPort_t *instance);
|
||||
inline uint8_t serialRead(serialPort_t *instance);
|
||||
inline void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
|
||||
inline bool isSerialTransmitBufferEmpty(serialPort_t *instance);
|
||||
void serialPrint(serialPort_t *instance, const char *str);
|
||||
uint32_t serialGetBaudRate(serialPort_t *instance);
|
|
@ -1,12 +1,34 @@
|
|||
#include "board.h"
|
||||
|
||||
enum serialBitStatus {
|
||||
WAITING_FOR_START_BIT = -1, BIT_0, BIT_1, BIT_2, BIT_3, BIT_4, BIT_5, BIT_6, BIT_7, WAITING_FOR_STOP_BIT
|
||||
};
|
||||
// There needs to be a table of timerMhz per baud rate so the system can set the timer correctly.
|
||||
// See http://www.wormfood.net/avrbaudcalc.php?postbitrate=19200&postclock=72
|
||||
// Currently defaulting to 3Mhz to support 19200.
|
||||
#define SOFT_SERIAL_TIMER_MHZ 3
|
||||
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 4
|
||||
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 5
|
||||
|
||||
#define RX_TOTAL_BITS 8
|
||||
#define TX_TOTAL_BITS 10
|
||||
|
||||
#define MAX_SOFTSERIAL_PORTS 2
|
||||
softSerial_t softSerialPorts[MAX_SOFTSERIAL_PORTS];
|
||||
|
||||
void onSerialTimer(uint8_t portIndex, uint16_t capture);
|
||||
|
||||
uint8_t readRxSignal(softSerial_t *softSerial)
|
||||
{
|
||||
return GPIO_ReadInputDataBit(softSerial->rxTimerHardware->gpio, softSerial->rxTimerHardware->pin);
|
||||
}
|
||||
|
||||
void setTxSignal(softSerial_t *softSerial, uint8_t state)
|
||||
{
|
||||
if (state) {
|
||||
digitalHi(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin);
|
||||
} else {
|
||||
digitalLo(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin);
|
||||
}
|
||||
}
|
||||
|
||||
softSerial_t* lookupSoftSerial(uint8_t reference)
|
||||
{
|
||||
assert_param(reference >= 0 && reference <= MAX_SOFTSERIAL_PORTS);
|
||||
|
@ -14,50 +36,87 @@ softSerial_t* lookupSoftSerial(uint8_t reference)
|
|||
return &(softSerialPorts[reference]);
|
||||
}
|
||||
|
||||
void resetSerialTimer(softSerial_t *softSerial)
|
||||
{
|
||||
//uint16_t counter = TIM_GetCounter(softSerial->rxTimerHardware->tim);
|
||||
TIM_SetCounter(softSerial->rxTimerHardware->tim, 0);
|
||||
//counter = TIM_GetCounter(softSerial->rxTimerHardware->tim);
|
||||
}
|
||||
|
||||
void stopSerialTimer(softSerial_t *softSerial)
|
||||
{
|
||||
TIM_Cmd(softSerial->timerHardware->tim, DISABLE);
|
||||
TIM_SetCounter(softSerial->timerHardware->tim, 0);
|
||||
TIM_Cmd(softSerial->rxTimerHardware->tim, DISABLE);
|
||||
}
|
||||
|
||||
void startSerialTimer(softSerial_t *softSerial)
|
||||
{
|
||||
TIM_SetCounter(softSerial->timerHardware->tim, 0);
|
||||
TIM_Cmd(softSerial->timerHardware->tim, ENABLE);
|
||||
TIM_Cmd(softSerial->rxTimerHardware->tim, ENABLE);
|
||||
}
|
||||
|
||||
static void waitForFirstBit(softSerial_t *softSerial)
|
||||
static void softSerialGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
|
||||
{
|
||||
softSerial->state = BIT_0;
|
||||
startSerialTimer(softSerial);
|
||||
gpio_config_t cfg;
|
||||
|
||||
cfg.pin = pin;
|
||||
cfg.mode = mode;
|
||||
cfg.speed = Speed_2MHz;
|
||||
gpioInit(gpio, &cfg);
|
||||
}
|
||||
|
||||
static void onSerialPinChange(uint8_t reference, uint16_t capture)
|
||||
void serialInputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||
{
|
||||
softSerial_t *softSerial = lookupSoftSerial(reference);
|
||||
if (softSerial->state == WAITING_FOR_START_BIT) {
|
||||
waitForFirstBit(softSerial);
|
||||
}
|
||||
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPU);
|
||||
}
|
||||
|
||||
uint8_t readSerialSignal(softSerial_t *softSerial)
|
||||
#define TICKS_PER_BIT 3
|
||||
|
||||
void serialTimerConfig(const timerHardware_t *timerHardwarePtr, uint32_t baud, uint8_t reference, timerCCCallbackPtr callback)
|
||||
{
|
||||
return GPIO_ReadInputDataBit(softSerial->timerHardware->gpio, softSerial->timerHardware->pin);
|
||||
uint16_t timerPeriod = (SOFT_SERIAL_TIMER_MHZ * 1000000) / (baud * TICKS_PER_BIT);
|
||||
timerInConfig(timerHardwarePtr, timerPeriod, SOFT_SERIAL_TIMER_MHZ);
|
||||
configureTimerCaptureCompareInterrupt(timerHardwarePtr, reference, callback);
|
||||
}
|
||||
|
||||
void mergeSignalWithCurrentByte(softSerial_t *softSerial, uint8_t serialSignal)
|
||||
void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||
{
|
||||
softSerial->rxBuffer[softSerial->port.rxBufferTail] |= (serialSignal << softSerial->state);
|
||||
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_Out_PP);
|
||||
}
|
||||
|
||||
inline void initialiseCurrentByteWithFirstSignal(softSerial_t *softSerial, uint8_t serialSignal)
|
||||
void setupSoftSerial1(uint32_t baud)
|
||||
{
|
||||
softSerial->rxBuffer[softSerial->port.rxBufferTail] = serialSignal;
|
||||
}
|
||||
int portIndex = 0;
|
||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||
|
||||
inline void prepareForNextSignal(softSerial_t *softSerial) {
|
||||
softSerial->state++;
|
||||
softSerial->port.vTable = softSerialVTable;
|
||||
softSerial->port.mode = MODE_RXTX;
|
||||
softSerial->port.baudRate = baud;
|
||||
|
||||
softSerial->rxTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_RX_HARDWARE]);
|
||||
softSerial->txTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_TX_HARDWARE]);
|
||||
|
||||
softSerial->port.rxBufferSize = SOFT_SERIAL_BUFFER_SIZE;
|
||||
softSerial->port.rxBuffer = softSerial->rxBuffer;
|
||||
softSerial->port.rxBufferTail = 0;
|
||||
softSerial->port.rxBufferHead = 0;
|
||||
|
||||
softSerial->port.txBuffer = softSerial->txBuffer;
|
||||
softSerial->port.txBufferSize = SOFT_SERIAL_BUFFER_SIZE,
|
||||
softSerial->port.txBufferTail = 0;
|
||||
softSerial->port.txBufferHead = 0;
|
||||
|
||||
softSerial->isTransmittingData = false;
|
||||
softSerial->isSearchingForStartBit = true;
|
||||
softSerial->isSearchingForStopBit = false;
|
||||
|
||||
softSerial->timerRxCounter = 1;
|
||||
|
||||
serialInputPortConfig(softSerial->rxTimerHardware);
|
||||
serialOutputPortConfig(softSerial->txTimerHardware);
|
||||
|
||||
setTxSignal(softSerial, 1);
|
||||
delay(50);
|
||||
|
||||
serialTimerConfig(softSerial->rxTimerHardware, baud, portIndex, onSerialTimer);
|
||||
}
|
||||
|
||||
void updateBufferIndex(softSerial_t *softSerial)
|
||||
|
@ -70,104 +129,135 @@ void updateBufferIndex(softSerial_t *softSerial)
|
|||
}
|
||||
}
|
||||
|
||||
void prepareForNextByte(softSerial_t *softSerial)
|
||||
/*********************************************/
|
||||
|
||||
void searchForStartBit(softSerial_t *softSerial)
|
||||
{
|
||||
stopSerialTimer(softSerial);
|
||||
softSerial->state = WAITING_FOR_START_BIT;
|
||||
char rxSignal = readRxSignal(softSerial);
|
||||
if (rxSignal == 1) {
|
||||
// start bit not found
|
||||
softSerial->timerRxCounter = 1; // process on next timer event
|
||||
return;
|
||||
}
|
||||
|
||||
// timer is aligned to falling signal of start bit.
|
||||
// three ticks per bit.
|
||||
|
||||
softSerial->isSearchingForStartBit = false;
|
||||
softSerial->internalRxBuffer = 0;
|
||||
softSerial->timerRxCounter = TICKS_PER_BIT + 1; // align to middle of next bit
|
||||
softSerial->bitsLeftToReceive = RX_TOTAL_BITS;
|
||||
softSerial->rxBitSelectionMask = 1;
|
||||
}
|
||||
|
||||
void searchForStopBit(softSerial_t *softSerial)
|
||||
{
|
||||
softSerial->timerRxCounter = 1;
|
||||
|
||||
char rxSignal = readRxSignal(softSerial);
|
||||
if (rxSignal != 1) {
|
||||
// not found
|
||||
return;
|
||||
}
|
||||
|
||||
softSerial->isSearchingForStopBit = false;
|
||||
softSerial->isSearchingForStartBit = true;
|
||||
softSerial->internalRxBuffer &= 0xFF;
|
||||
|
||||
softSerial->port.rxBuffer[softSerial->port.rxBufferTail] = softSerial->internalRxBuffer;
|
||||
updateBufferIndex(softSerial);
|
||||
}
|
||||
|
||||
void readDataBit(softSerial_t *softSerial)
|
||||
{
|
||||
softSerial->timerRxCounter = TICKS_PER_BIT; // keep aligned to middle of bit
|
||||
|
||||
char rxSignal = readRxSignal(softSerial);
|
||||
if (rxSignal) {
|
||||
softSerial->internalRxBuffer |= softSerial->rxBitSelectionMask;
|
||||
}
|
||||
softSerial->rxBitSelectionMask <<= 1;
|
||||
if (--softSerial->bitsLeftToReceive <= 0) {
|
||||
softSerial->isSearchingForStopBit = true;
|
||||
softSerial->timerRxCounter = 2;
|
||||
}
|
||||
}
|
||||
|
||||
void processRxState(softSerial_t *softSerial)
|
||||
{
|
||||
//digitalToggle(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin);
|
||||
|
||||
if (--softSerial->timerRxCounter > 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (softSerial->isSearchingForStartBit) {
|
||||
searchForStartBit(softSerial);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
if (softSerial->isSearchingForStopBit) {
|
||||
searchForStopBit(softSerial);
|
||||
return;
|
||||
}
|
||||
|
||||
readDataBit(softSerial);
|
||||
}
|
||||
|
||||
|
||||
void processTxState(softSerial_t *softSerial)
|
||||
{
|
||||
char mask;
|
||||
|
||||
if (!softSerial->isTransmittingData) {
|
||||
|
||||
if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// data to send
|
||||
|
||||
char byteToSend = softSerial->port.txBuffer[softSerial->port.txBufferTail++];
|
||||
if (softSerial->port.txBufferTail >= softSerial->port.txBufferSize) {
|
||||
softSerial->port.txBufferTail = 0;
|
||||
}
|
||||
|
||||
// build internal buffer, start bit(1) + data bits + stop bit(0)
|
||||
softSerial->internalTxBuffer = (1 << (TX_TOTAL_BITS - 1)) | (byteToSend << 1);
|
||||
softSerial->bitsLeftToTransmit = TX_TOTAL_BITS;
|
||||
|
||||
// start immediately
|
||||
softSerial->timerTxCounter = 1;
|
||||
softSerial->isTransmittingData = true;
|
||||
return;
|
||||
}
|
||||
|
||||
if (--softSerial->timerTxCounter <= 0) {
|
||||
mask = softSerial->internalTxBuffer & 1;
|
||||
softSerial->internalTxBuffer >>= 1;
|
||||
|
||||
setTxSignal(softSerial, mask);
|
||||
|
||||
softSerial->timerTxCounter = TICKS_PER_BIT;
|
||||
if (--softSerial->bitsLeftToTransmit <= 0) {
|
||||
softSerial->isTransmittingData = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void onSerialTimer(uint8_t portIndex, uint16_t capture)
|
||||
{
|
||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||
|
||||
uint8_t serialSignal = readSerialSignal(softSerial);
|
||||
|
||||
switch (softSerial->state) {
|
||||
case BIT_0:
|
||||
initialiseCurrentByteWithFirstSignal(softSerial, serialSignal);
|
||||
prepareForNextSignal(softSerial);
|
||||
break;
|
||||
|
||||
case BIT_1:
|
||||
case BIT_2:
|
||||
case BIT_3:
|
||||
case BIT_4:
|
||||
case BIT_5:
|
||||
case BIT_6:
|
||||
case BIT_7:
|
||||
mergeSignalWithCurrentByte(softSerial, serialSignal);
|
||||
|
||||
prepareForNextSignal(softSerial);
|
||||
break;
|
||||
|
||||
case WAITING_FOR_STOP_BIT:
|
||||
prepareForNextByte(softSerial);
|
||||
break;
|
||||
}
|
||||
processTxState(softSerial);
|
||||
processRxState(softSerial);
|
||||
}
|
||||
|
||||
#define SOFT_SERIAL_TIMER_MHZ 1
|
||||
#define SOFT_SERIAL_1_TIMER_HARDWARE 4
|
||||
|
||||
static void softSerialGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
|
||||
{
|
||||
gpio_config_t cfg;
|
||||
|
||||
cfg.pin = pin;
|
||||
cfg.mode = mode;
|
||||
cfg.speed = Speed_2MHz;
|
||||
gpioInit(gpio, &cfg);
|
||||
}
|
||||
|
||||
void serialInputPortConfig(const timerHardware_t *timerHardwarePtr, uint16_t baud, uint8_t reference, timerCCCallbackPtr callback)
|
||||
{
|
||||
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPU);
|
||||
|
||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
||||
|
||||
int oneBitPeriod = (SOFT_SERIAL_TIMER_MHZ * 1000000) / baud;
|
||||
|
||||
timerInConfig(timerHardwarePtr, oneBitPeriod, SOFT_SERIAL_TIMER_MHZ);
|
||||
configureTimerCaptureCompareInterrupt(timerHardwarePtr, reference, callback);
|
||||
}
|
||||
|
||||
void setupSoftSerial1(uint32_t baud)
|
||||
{
|
||||
int portIndex = 0;
|
||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||
|
||||
softSerial->timerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_HARDWARE]);
|
||||
softSerial->timerIndex = SOFT_SERIAL_1_TIMER_HARDWARE;
|
||||
softSerial->state = WAITING_FOR_START_BIT;
|
||||
|
||||
softSerial->port.rxBufferSize = SOFT_SERIAL_BUFFER_SIZE;
|
||||
softSerial->port.rxBuffer = softSerial->rxBuffer;
|
||||
softSerial->port.rxBufferTail = 0;
|
||||
softSerial->port.rxBufferHead = 0;
|
||||
|
||||
softSerial->port.txBuffer = 0;
|
||||
softSerial->port.txBufferSize = 0;
|
||||
softSerial->port.txBufferTail = 0;
|
||||
softSerial->port.txBufferHead = 0;
|
||||
|
||||
softSerial->port.baudRate = baud;
|
||||
softSerial->port.mode = MODE_RX;
|
||||
|
||||
// FIXME this uart specific initialisation doesn't belong really here
|
||||
softSerial->port.txDMAChannel = 0;
|
||||
softSerial->port.txDMAChannel = 0;
|
||||
|
||||
configureTimerChannelCallback(softSerial->timerHardware->tim, TIM_Channel_2, portIndex, onSerialTimer);
|
||||
|
||||
TIM_ITConfig(TIM3, TIM_IT_CC2, ENABLE);
|
||||
stopSerialTimer(softSerial);
|
||||
|
||||
serialInputPortConfig(softSerial->timerHardware, baud, portIndex, onSerialPinChange);
|
||||
}
|
||||
|
||||
bool serialAvailable(softSerial_t *softSerial)
|
||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
softSerial_t *softSerial = (softSerial_t *)instance;
|
||||
if (softSerial->port.rxBufferTail == softSerial->port.rxBufferHead) {
|
||||
return 0;
|
||||
}
|
||||
|
@ -190,14 +280,43 @@ static void moveHeadToNextByte(softSerial_t *softSerial)
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t serialReadByte(softSerial_t *softSerial)
|
||||
uint8_t softSerialReadByte(serialPort_t *instance)
|
||||
{
|
||||
if (serialAvailable(softSerial) == 0) {
|
||||
if (softSerialTotalBytesWaiting(instance) == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
char b = softSerial->port.rxBuffer[softSerial->port.rxBufferHead];
|
||||
char b = instance->rxBuffer[instance->rxBufferHead];
|
||||
|
||||
moveHeadToNextByte(softSerial);
|
||||
moveHeadToNextByte((softSerial_t *)instance);
|
||||
return b;
|
||||
}
|
||||
|
||||
void softSerialWriteByte(serialPort_t *s, uint8_t ch)
|
||||
{
|
||||
s->txBuffer[s->txBufferHead] = ch;
|
||||
s->txBufferHead = (s->txBufferHead + 1) % s->txBufferSize;
|
||||
|
||||
}
|
||||
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate)
|
||||
{
|
||||
// not implemented.
|
||||
}
|
||||
|
||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
return instance->txBufferHead == instance->txBufferTail;
|
||||
}
|
||||
|
||||
|
||||
const struct serialPortVTable softSerialVTable[] = {
|
||||
{
|
||||
softSerialWriteByte,
|
||||
softSerialTotalBytesWaiting,
|
||||
softSerialReadByte,
|
||||
softSerialSetBaudRate,
|
||||
isSoftSerialTransmitBufferEmpty
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -10,16 +10,38 @@
|
|||
#define SOFT_SERIAL_BUFFER_SIZE 256
|
||||
|
||||
typedef struct softSerial_s {
|
||||
const timerHardware_t *timerHardware;
|
||||
uint8_t timerIndex;
|
||||
serialPort_t port;
|
||||
volatile int state;
|
||||
volatile uint8_t rxBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
||||
} softSerial_t;
|
||||
void setupSoftSerial1(uint32_t baud);
|
||||
|
||||
uint8_t serialReadByte(softSerial_t *softSerial);
|
||||
bool serialAvailable(softSerial_t *softSerial);
|
||||
const timerHardware_t *rxTimerHardware;
|
||||
volatile uint8_t rxBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
||||
|
||||
const timerHardware_t *txTimerHardware;
|
||||
volatile uint8_t txBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
||||
|
||||
uint8_t isSearchingForStopBit;
|
||||
uint8_t rxBitSelectionMask;
|
||||
uint8_t isSearchingForStartBit;
|
||||
uint8_t isTransmittingData;
|
||||
uint8_t timerRxCounter;
|
||||
uint8_t timerTxCounter;
|
||||
uint8_t bitsLeftToReceive;
|
||||
uint8_t bitsLeftToTransmit;
|
||||
uint16_t internalRxBuffer; // excluding start/stop bits
|
||||
uint16_t internalTxBuffer; // includes start and stop bits
|
||||
|
||||
} softSerial_t;
|
||||
|
||||
extern timerHardware_t* serialTimerHardware;
|
||||
extern softSerial_t softSerialPorts[];
|
||||
|
||||
extern const struct serialPortVTable softSerialVTable[];
|
||||
|
||||
void setupSoftSerial1(uint32_t baud);
|
||||
|
||||
// serialPort API
|
||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);
|
||||
|
||||
|
|
163
src/drv_uart.c
163
src/drv_uart.c
|
@ -4,23 +4,28 @@
|
|||
Copyright © 2011 Bill Nesbitt
|
||||
*/
|
||||
|
||||
static serialPort_t serialPort1;
|
||||
static serialPort_t serialPort2;
|
||||
static uartPort_t uartPort1;
|
||||
static uartPort_t uartPort2;
|
||||
|
||||
// USART1 - Telemetry (RX/TX by DMA)
|
||||
serialPort_t *serialUSART1(uint32_t baudRate, portmode_t mode)
|
||||
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
|
||||
{
|
||||
serialPort_t *s;
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &serialPort1;
|
||||
s->rxBufferSize = UART1_RX_BUFFER_SIZE;
|
||||
s->txBufferSize = UART1_TX_BUFFER_SIZE;
|
||||
s->rxBuffer = rx1Buffer;
|
||||
s->txBuffer = tx1Buffer;
|
||||
s = &uartPort1;
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
s->port.rxBuffer = rx1Buffer;
|
||||
s->port.txBuffer = tx1Buffer;
|
||||
s->port.rxBufferSize = UART1_RX_BUFFER_SIZE;
|
||||
s->port.txBufferSize = UART1_TX_BUFFER_SIZE;
|
||||
|
||||
s->rxDMAChannel = DMA1_Channel5;
|
||||
s->txDMAChannel = DMA1_Channel4;
|
||||
|
||||
|
@ -48,20 +53,24 @@ serialPort_t *serialUSART1(uint32_t baudRate, portmode_t mode)
|
|||
}
|
||||
|
||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||
serialPort_t *serialUSART2(uint32_t baudRate, portmode_t mode)
|
||||
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
|
||||
{
|
||||
serialPort_t *s;
|
||||
uartPort_t *s;
|
||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &serialPort2;
|
||||
s->baudRate = baudRate;
|
||||
s->rxBufferSize = UART2_RX_BUFFER_SIZE;
|
||||
s->txBufferSize = UART2_TX_BUFFER_SIZE;
|
||||
s->rxBuffer = rx2Buffer;
|
||||
s->txBuffer = tx2Buffer;
|
||||
s = &uartPort2;
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
s->port.rxBufferSize = UART2_RX_BUFFER_SIZE;
|
||||
s->port.txBufferSize = UART2_TX_BUFFER_SIZE;
|
||||
s->port.rxBuffer = rx2Buffer;
|
||||
s->port.txBuffer = tx2Buffer;
|
||||
|
||||
s->USARTx = USART2;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
|
@ -87,11 +96,12 @@ serialPort_t *serialUSART2(uint32_t baudRate, portmode_t mode)
|
|||
return s;
|
||||
}
|
||||
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, uint32_t baudRate, portmode_t mode)
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode)
|
||||
{
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
serialPort_t *s = NULL;
|
||||
|
||||
uartPort_t *s = NULL;
|
||||
|
||||
if (USARTx == USART1)
|
||||
s = serialUSART1(baudRate, mode);
|
||||
|
@ -99,11 +109,14 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, u
|
|||
s = serialUSART2(baudRate, mode);
|
||||
|
||||
s->USARTx = USARTx;
|
||||
s->rxBufferHead = s->rxBufferTail = 0;
|
||||
s->txBufferHead = s->txBufferTail = 0;
|
||||
|
||||
// common serial initialisation code should move to serialPort::init()
|
||||
s->port.rxBufferHead = s->port.rxBufferTail = 0;
|
||||
s->port.txBufferHead = s->port.txBufferTail = 0;
|
||||
// callback for IRQ-based RX ONLY
|
||||
s->callback = callback;
|
||||
s->mode = mode;
|
||||
s->port.callback = callback;
|
||||
s->port.mode = mode;
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
USART_InitStructure.USART_BaudRate = baudRate;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
|
@ -130,10 +143,10 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, u
|
|||
// Receive DMA or IRQ
|
||||
if (mode & MODE_RX) {
|
||||
if (s->rxDMAChannel) {
|
||||
DMA_InitStructure.DMA_BufferSize = s->rxBufferSize;
|
||||
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->rxBuffer;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
|
||||
DMA_DeInit(s->rxDMAChannel);
|
||||
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
|
||||
DMA_Cmd(s->rxDMAChannel, ENABLE);
|
||||
|
@ -147,7 +160,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, u
|
|||
// Transmit DMA or IRQ
|
||||
if (mode & MODE_TX) {
|
||||
if (s->txDMAChannel) {
|
||||
DMA_InitStructure.DMA_BufferSize = s->txBufferSize;
|
||||
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_DeInit(s->txDMAChannel);
|
||||
|
@ -161,12 +174,13 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, u
|
|||
}
|
||||
}
|
||||
|
||||
return s;
|
||||
return (serialPort_t *)s;
|
||||
}
|
||||
|
||||
void uartChangeBaud(serialPort_t *s, uint32_t baudRate)
|
||||
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||
{
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
|
||||
USART_InitStructure.USART_BaudRate = baudRate;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
|
@ -174,64 +188,71 @@ void uartChangeBaud(serialPort_t *s, uint32_t baudRate)
|
|||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
USART_InitStructure.USART_Mode = 0;
|
||||
if (s->mode & MODE_RX)
|
||||
if (s->port.mode & MODE_RX)
|
||||
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
||||
if (s->mode & MODE_TX)
|
||||
if (s->port.mode & MODE_TX)
|
||||
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
||||
USART_Init(s->USARTx, &USART_InitStructure);
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
}
|
||||
|
||||
static void uartStartTxDMA(serialPort_t *s)
|
||||
static void uartStartTxDMA(uartPort_t *s)
|
||||
{
|
||||
s->txDMAChannel->CMAR = (uint32_t)&s->txBuffer[s->txBufferTail];
|
||||
if (s->txBufferHead > s->txBufferTail) {
|
||||
s->txDMAChannel->CNDTR = s->txBufferHead - s->txBufferTail;
|
||||
s->txBufferTail = s->txBufferHead;
|
||||
s->txDMAChannel->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
|
||||
if (s->port.txBufferHead > s->port.txBufferTail) {
|
||||
s->txDMAChannel->CNDTR = s->port.txBufferHead - s->port.txBufferTail;
|
||||
s->port.txBufferTail = s->port.txBufferHead;
|
||||
} else {
|
||||
s->txDMAChannel->CNDTR = s->txBufferSize - s->txBufferTail;
|
||||
s->txBufferTail = 0;
|
||||
s->txDMAChannel->CNDTR = s->port.txBufferSize - s->port.txBufferTail;
|
||||
s->port.txBufferTail = 0;
|
||||
}
|
||||
s->txDMAEmpty = false;
|
||||
DMA_Cmd(s->txDMAChannel, ENABLE);
|
||||
}
|
||||
|
||||
bool isUartAvailable(serialPort_t *s)
|
||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)instance;
|
||||
// FIXME always returns 1 or 0, not the amount of bytes waiting
|
||||
if (s->rxDMAChannel)
|
||||
return s->rxDMAChannel->CNDTR != s->rxDMAPos;
|
||||
else
|
||||
return s->rxBufferTail != s->rxBufferHead;
|
||||
return s->port.rxBufferTail != s->port.rxBufferHead;
|
||||
}
|
||||
|
||||
// BUGBUG TODO TODO FIXME
|
||||
bool isUartTransmitEmpty(serialPort_t *s)
|
||||
// BUGBUG TODO TODO FIXME - What is the bug?
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
if (s->txDMAChannel)
|
||||
return s->txDMAEmpty;
|
||||
else
|
||||
return s->txBufferTail == s->txBufferHead;
|
||||
return s->port.txBufferTail == s->port.txBufferHead;
|
||||
}
|
||||
|
||||
uint8_t uartRead(serialPort_t *s)
|
||||
uint8_t uartRead(serialPort_t *instance)
|
||||
{
|
||||
uint8_t ch;
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
|
||||
if (s->rxDMAChannel) {
|
||||
ch = s->rxBuffer[s->rxBufferSize - s->rxDMAPos];
|
||||
ch = s->port.rxBuffer[s->port.rxBufferSize - s->rxDMAPos];
|
||||
if (--s->rxDMAPos == 0)
|
||||
s->rxDMAPos = s->rxBufferSize;
|
||||
s->rxDMAPos = s->port.rxBufferSize;
|
||||
} else {
|
||||
ch = s->rxBuffer[s->rxBufferTail];
|
||||
s->rxBufferTail = (s->rxBufferTail + 1) % s->rxBufferSize;
|
||||
ch = s->port.rxBuffer[s->port.rxBufferTail];
|
||||
s->port.rxBufferTail = (s->port.rxBufferTail + 1) % s->port.rxBufferSize;
|
||||
}
|
||||
|
||||
return ch;
|
||||
}
|
||||
|
||||
void uartWrite(serialPort_t *s, uint8_t ch)
|
||||
void uartWrite(serialPort_t *instance, uint8_t ch)
|
||||
{
|
||||
s->txBuffer[s->txBufferHead] = ch;
|
||||
s->txBufferHead = (s->txBufferHead + 1) % s->txBufferSize;
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
s->port.txBuffer[s->port.txBufferHead] = ch;
|
||||
s->port.txBufferHead = (s->port.txBufferHead + 1) % s->port.txBufferSize;
|
||||
|
||||
if (s->txDMAChannel) {
|
||||
if (!(s->txDMAChannel->CCR & 1))
|
||||
|
@ -241,24 +262,26 @@ void uartWrite(serialPort_t *s, uint8_t ch)
|
|||
}
|
||||
}
|
||||
|
||||
void uartPrint(serialPort_t *s, const char *str)
|
||||
{
|
||||
uint8_t ch;
|
||||
while ((ch = *(str++))) {
|
||||
uartWrite(s, ch);
|
||||
const struct serialPortVTable uartVTable[] = {
|
||||
{
|
||||
uartWrite,
|
||||
uartTotalBytesWaiting,
|
||||
uartRead,
|
||||
uartSetBaudRate,
|
||||
isUartTransmitBufferEmpty
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
// Handlers
|
||||
|
||||
// USART1 Tx DMA Handler
|
||||
void DMA1_Channel4_IRQHandler(void)
|
||||
{
|
||||
serialPort_t *s = &serialPort1;
|
||||
uartPort_t *s = &uartPort1;
|
||||
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
||||
DMA_Cmd(s->txDMAChannel, DISABLE);
|
||||
|
||||
if (s->txBufferHead != s->txBufferTail)
|
||||
if (s->port.txBufferHead != s->port.txBufferTail)
|
||||
uartStartTxDMA(s);
|
||||
else
|
||||
s->txDMAEmpty = true;
|
||||
|
@ -267,13 +290,13 @@ void DMA1_Channel4_IRQHandler(void)
|
|||
// USART1 Tx IRQ Handler
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
serialPort_t *s = &serialPort1;
|
||||
uartPort_t *s = &uartPort1;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->txBufferTail != s->txBufferHead) {
|
||||
s->USARTx->DR = s->txBuffer[s->txBufferTail];
|
||||
s->txBufferTail = (s->txBufferTail + 1) % s->txBufferSize;
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
|
@ -283,22 +306,22 @@ void USART1_IRQHandler(void)
|
|||
// USART2 Rx/Tx IRQ Handler
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
serialPort_t *s = &serialPort2;
|
||||
uartPort_t *s = &uartPort2;
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
||||
if (SR & USART_FLAG_RXNE) {
|
||||
// If we registered a callback, pass crap there
|
||||
if (s->callback) {
|
||||
s->callback(s->USARTx->DR);
|
||||
if (s->port.callback) {
|
||||
s->port.callback(s->USARTx->DR);
|
||||
} else {
|
||||
s->rxBuffer[s->rxBufferHead] = s->USARTx->DR;
|
||||
s->rxBufferHead = (s->rxBufferHead + 1) % s->rxBufferSize;
|
||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
||||
}
|
||||
}
|
||||
if (SR & USART_FLAG_TXE) {
|
||||
if (s->txBufferTail != s->txBufferHead) {
|
||||
s->USARTx->DR = s->txBuffer[s->txBufferTail];
|
||||
s->txBufferTail = (s->txBufferTail + 1) % s->txBufferSize;
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail];
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
|
|
|
@ -8,30 +8,11 @@
|
|||
#define UART2_TX_BUFFER_SIZE 64
|
||||
#define MAX_SERIAL_PORTS 2
|
||||
|
||||
// This is a bitmask
|
||||
typedef enum portmode_t {
|
||||
MODE_RX = 1,
|
||||
MODE_TX = 2,
|
||||
MODE_RXTX = 3
|
||||
} portmode_t;
|
||||
|
||||
// FIXME this is a uart_t really. Move the generic properties into a separate structure (serialPort_t) and update the code to use it
|
||||
typedef struct {
|
||||
portmode_t mode;
|
||||
uint32_t baudRate;
|
||||
|
||||
uint32_t rxBufferSize;
|
||||
uint32_t txBufferSize;
|
||||
volatile uint8_t *rxBuffer;
|
||||
volatile uint8_t *txBuffer;
|
||||
uint32_t rxBufferHead;
|
||||
uint32_t rxBufferTail;
|
||||
uint32_t txBufferHead;
|
||||
uint32_t txBufferTail;
|
||||
|
||||
// FIXME rename callback type so something more generic
|
||||
uartReceiveCallbackPtr callback;
|
||||
|
||||
serialPort_t port;
|
||||
|
||||
// FIXME these are uart specific and do not belong in here
|
||||
DMA_Channel_TypeDef *rxDMAChannel;
|
||||
DMA_Channel_TypeDef *txDMAChannel;
|
||||
|
@ -43,12 +24,15 @@ typedef struct {
|
|||
bool txDMAEmpty;
|
||||
|
||||
USART_TypeDef *USARTx;
|
||||
} serialPort_t;
|
||||
} uartPort_t;
|
||||
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, uint32_t baudRate, portmode_t mode);
|
||||
void uartChangeBaud(serialPort_t *s, uint32_t baudRate);
|
||||
bool isUartAvailable(serialPort_t *s);
|
||||
bool isUartTransmitEmpty(serialPort_t *s);
|
||||
uint8_t uartRead(serialPort_t *s);
|
||||
void uartWrite(serialPort_t *s, uint8_t ch);
|
||||
void uartPrint(serialPort_t *s, const char *str);
|
||||
extern const struct serialPortVTable uartVTable[];
|
||||
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode);
|
||||
|
||||
// serialPort API
|
||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance);
|
||||
uint8_t uartRead(serialPort_t *instance);
|
||||
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
bool isUartTransmitBufferEmpty(serialPort_t *s);
|
||||
|
|
19
src/gps.c
19
src/gps.c
|
@ -10,6 +10,9 @@ const uint32_t init_speed[5] = { 9600, 19200, 38400, 57600, 115200 };
|
|||
static void GPS_NewData(uint16_t c);
|
||||
static void gpsPrint(const char *str);
|
||||
|
||||
#define UBX_INIT_STRING_INDEX 0
|
||||
#define MTK_INIT_STRING_INDEX 4
|
||||
|
||||
static const char * const gpsInitStrings[] = {
|
||||
"$PUBX,41,1,0003,0001,19200,0*23\r\n", // UBX0..3
|
||||
"$PUBX,41,1,0003,0001,38400,0*26\r\n",
|
||||
|
@ -45,13 +48,15 @@ void gpsInit(uint32_t baudrate)
|
|||
core.gpsport = uartOpen(USART2, GPS_NewData, baudrate, MODE_RXTX);
|
||||
|
||||
if (mcfg.gps_type == GPS_UBLOX)
|
||||
offset = 0;
|
||||
offset = UBX_INIT_STRING_INDEX;
|
||||
else if (mcfg.gps_type == GPS_MTK)
|
||||
offset = 4;
|
||||
offset = MTK_INIT_STRING_INDEX;
|
||||
|
||||
if (mcfg.gps_type != GPS_NMEA) {
|
||||
for (i = 0; i < 5; i++) {
|
||||
uartChangeBaud(core.gpsport, init_speed[i]);
|
||||
serialSetBaudRate(core.gpsport, init_speed[i]);
|
||||
// verify the requested change took effect.
|
||||
baudrate = serialGetBaudRate(core.gpsport);
|
||||
switch (baudrate) {
|
||||
case 19200:
|
||||
gpsPrint(gpsInitStrings[offset]);
|
||||
|
@ -70,10 +75,10 @@ void gpsInit(uint32_t baudrate)
|
|||
}
|
||||
}
|
||||
|
||||
uartChangeBaud(core.gpsport, baudrate);
|
||||
serialSetBaudRate(core.gpsport, baudrate);
|
||||
if (mcfg.gps_type == GPS_UBLOX) {
|
||||
for (i = 0; i < sizeof(ubloxInit); i++) {
|
||||
uartWrite(core.gpsport, ubloxInit[i]); // send ubx init binary
|
||||
serialWrite(core.gpsport, ubloxInit[i]); // send ubx init binary
|
||||
delay(4);
|
||||
}
|
||||
} else if (mcfg.gps_type == GPS_MTK) {
|
||||
|
@ -90,13 +95,13 @@ void gpsInit(uint32_t baudrate)
|
|||
static void gpsPrint(const char *str)
|
||||
{
|
||||
while (*str) {
|
||||
uartWrite(core.gpsport, *str);
|
||||
serialWrite(core.gpsport, *str);
|
||||
if (mcfg.gps_type == GPS_UBLOX)
|
||||
delay(4);
|
||||
str++;
|
||||
}
|
||||
// wait to send all
|
||||
while (!isUartTransmitEmpty(core.gpsport));
|
||||
while (!isSerialTransmitBufferEmpty(core.gpsport));
|
||||
delay(30);
|
||||
}
|
||||
|
||||
|
|
23
src/main.c
23
src/main.c
|
@ -12,15 +12,15 @@ extern uint16_t pwmReadRawRC(uint8_t chan);
|
|||
// gcc/GNU version
|
||||
static void _putc(void *p, char c)
|
||||
{
|
||||
uartWrite(core.mainport, c);
|
||||
serialWrite(core.mainport, c);
|
||||
}
|
||||
#else
|
||||
// keil/armcc version
|
||||
int fputc(int c, FILE *f)
|
||||
{
|
||||
// let DMA catch up a bit when using set or dump, we're too fast.
|
||||
while (!isUartTransmitEmpty(core.mainport));
|
||||
uartWrite(core.mainport, c);
|
||||
while (!isSerialTransmitBufferEmpty(core.mainport));
|
||||
serialWrite(core.mainport, c);
|
||||
return c;
|
||||
}
|
||||
#endif
|
||||
|
@ -129,13 +129,11 @@ int main(void)
|
|||
if (feature(FEATURE_VBAT))
|
||||
batteryInit();
|
||||
|
||||
#ifdef SOFTSERIAL_19200_LOOPBACK
|
||||
|
||||
serialInit(19200);
|
||||
setupSoftSerial1(19200);
|
||||
uartPrint(core.mainport, "LOOPBACK 19200 ENABLED");
|
||||
#else
|
||||
serialInit(mcfg.serial_baudrate);
|
||||
#ifdef SOFTSERIAL_19200_LOOPBACK
|
||||
setupSoftSerial1(19200);
|
||||
serialPort_t* loopbackPort = (serialPort_t*)&(softSerialPorts[0]);
|
||||
serialPrint(loopbackPort, "LOOPBACK 19200 ENABLED\r\n");
|
||||
#endif
|
||||
|
||||
previousTime = micros();
|
||||
|
@ -149,10 +147,11 @@ int main(void)
|
|||
while (1) {
|
||||
loop();
|
||||
#ifdef SOFTSERIAL_19200_LOOPBACK
|
||||
while (serialAvailable(&softSerialPorts[0])) {
|
||||
while (serialTotalBytesWaiting(loopbackPort)) {
|
||||
|
||||
uint8_t b = serialReadByte(&softSerialPorts[0]);
|
||||
uartWrite(core.mainport, b);
|
||||
uint8_t b = serialRead(loopbackPort);
|
||||
serialWrite(loopbackPort, b);
|
||||
//serialWrite(core.mainport, b);
|
||||
};
|
||||
#endif
|
||||
}
|
||||
|
|
2
src/mw.h
2
src/mw.h
|
@ -284,7 +284,7 @@ typedef struct master_t {
|
|||
// gps-related stuff
|
||||
uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2+ ??
|
||||
uint32_t gps_baudrate; // GPS baudrate
|
||||
// serial(uart1) baudrate
|
||||
|
||||
uint32_t serial_baudrate;
|
||||
|
||||
config_t profile[3]; // 3 separate profiles
|
||||
|
|
|
@ -228,7 +228,7 @@ void tfp_printf(char *fmt, ...)
|
|||
va_start(va, fmt);
|
||||
tfp_format(stdout_putp, stdout_putf, fmt, va);
|
||||
va_end(va);
|
||||
while (!isUartTransmitEmpty(core.mainport));
|
||||
while (!isSerialTransmitBufferEmpty(core.mainport));
|
||||
}
|
||||
|
||||
static void putcp(void *p, char c)
|
||||
|
|
22
src/serial.c
22
src/serial.c
|
@ -157,16 +157,16 @@ void serialize32(uint32_t a)
|
|||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 8;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 16;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 24;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
}
|
||||
|
||||
|
@ -174,16 +174,16 @@ void serialize16(int16_t a)
|
|||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
t = a >> 8 & 0xff;
|
||||
uartWrite(core.mainport, t);
|
||||
serialWrite(core.mainport, t);
|
||||
checksum ^= t;
|
||||
}
|
||||
|
||||
void serialize8(uint8_t a)
|
||||
{
|
||||
uartWrite(core.mainport, a);
|
||||
serialWrite(core.mainport, a);
|
||||
checksum ^= a;
|
||||
}
|
||||
|
||||
|
@ -682,14 +682,14 @@ void serialCom(void)
|
|||
HEADER_CMD,
|
||||
} c_state = IDLE;
|
||||
|
||||
// in cli mode, all uart stuff goes to here. enter cli mode by sending #
|
||||
// in cli mode, all serial stuff goes to here. enter cli mode by sending #
|
||||
if (cliMode) {
|
||||
cliProcess();
|
||||
return;
|
||||
}
|
||||
|
||||
while (isUartAvailable(core.mainport)) {
|
||||
c = uartRead(core.mainport);
|
||||
while (serialTotalBytesWaiting(core.mainport)) {
|
||||
c = serialRead(core.mainport);
|
||||
|
||||
if (c_state == IDLE) {
|
||||
c_state = (c == '$') ? HEADER_START : IDLE;
|
||||
|
@ -725,7 +725,7 @@ void serialCom(void)
|
|||
c_state = IDLE;
|
||||
}
|
||||
}
|
||||
if (!cliMode && !isUartAvailable(core.telemport) && feature(FEATURE_TELEMETRY) && f.ARMED) { // The first 2 conditions should never evaluate to true but I'm putting it here anyway - silpstream
|
||||
if (!cliMode && !serialTotalBytesWaiting(core.telemport) && feature(FEATURE_TELEMETRY) && f.ARMED) { // The first 2 conditions should never evaluate to true but I'm putting it here anyway - silpstream
|
||||
sendTelemetry();
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -50,26 +50,26 @@ extern uint8_t batteryCellCount;
|
|||
|
||||
static void sendDataHead(uint8_t id)
|
||||
{
|
||||
uartWrite(core.telemport, PROTOCOL_HEADER);
|
||||
uartWrite(core.telemport, id);
|
||||
serialWrite(core.telemport, PROTOCOL_HEADER);
|
||||
serialWrite(core.telemport, id);
|
||||
}
|
||||
|
||||
static void sendTelemetryTail(void)
|
||||
{
|
||||
uartWrite(core.telemport, PROTOCOL_TAIL);
|
||||
serialWrite(core.telemport, PROTOCOL_TAIL);
|
||||
}
|
||||
|
||||
static void serializeFrsky(uint8_t data)
|
||||
{
|
||||
// take care of byte stuffing
|
||||
if (data == 0x5e) {
|
||||
uartWrite(core.telemport, 0x5d);
|
||||
uartWrite(core.telemport, 0x3e);
|
||||
serialWrite(core.telemport, 0x5d);
|
||||
serialWrite(core.telemport, 0x3e);
|
||||
} else if (data == 0x5d) {
|
||||
uartWrite(core.telemport, 0x5d);
|
||||
uartWrite(core.telemport, 0x3d);
|
||||
serialWrite(core.telemport, 0x5d);
|
||||
serialWrite(core.telemport, 0x3d);
|
||||
} else
|
||||
uartWrite(core.telemport, data);
|
||||
serialWrite(core.telemport, data);
|
||||
}
|
||||
|
||||
static void serialize16(int16_t a)
|
||||
|
|
Loading…
Reference in New Issue