rewritten drv_uart to suck slightly less
tested w/o GPS git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@382 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
1ff0036dec
commit
cbb580f753
101
src/cli.c
101
src/cli.c
|
@ -216,6 +216,8 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
static void cliSetVar(const clivalue_t *var, const int32_t value);
|
static void cliSetVar(const clivalue_t *var, const int32_t value);
|
||||||
static void cliPrintVar(const clivalue_t *var, uint32_t full);
|
static void cliPrintVar(const clivalue_t *var, uint32_t full);
|
||||||
|
static void cliPrint(const char *str);
|
||||||
|
static void cliWrite(uint8_t ch);
|
||||||
|
|
||||||
#ifndef HAVE_ITOA_FUNCTION
|
#ifndef HAVE_ITOA_FUNCTION
|
||||||
|
|
||||||
|
@ -396,7 +398,7 @@ static char *ftoa(float x, char *floatString)
|
||||||
|
|
||||||
static void cliPrompt(void)
|
static void cliPrompt(void)
|
||||||
{
|
{
|
||||||
uartPrint("\r\n# ");
|
cliPrint("\r\n# ");
|
||||||
}
|
}
|
||||||
|
|
||||||
static int cliCompare(const void *a, const void *b)
|
static int cliCompare(const void *a, const void *b)
|
||||||
|
@ -441,7 +443,7 @@ static void cliCMix(char *cmdline)
|
||||||
len = strlen(cmdline);
|
len = strlen(cmdline);
|
||||||
|
|
||||||
if (len == 0) {
|
if (len == 0) {
|
||||||
uartPrint("Custom mixer: \r\nMotor\tThr\tRoll\tPitch\tYaw\r\n");
|
cliPrint("Custom mixer: \r\nMotor\tThr\tRoll\tPitch\tYaw\r\n");
|
||||||
for (i = 0; i < MAX_MOTORS; i++) {
|
for (i = 0; i < MAX_MOTORS; i++) {
|
||||||
if (mcfg.customMixer[i].throttle == 0.0f)
|
if (mcfg.customMixer[i].throttle == 0.0f)
|
||||||
break;
|
break;
|
||||||
|
@ -458,10 +460,10 @@ static void cliCMix(char *cmdline)
|
||||||
mixsum[1] += mcfg.customMixer[i].pitch;
|
mixsum[1] += mcfg.customMixer[i].pitch;
|
||||||
mixsum[2] += mcfg.customMixer[i].yaw;
|
mixsum[2] += mcfg.customMixer[i].yaw;
|
||||||
}
|
}
|
||||||
uartPrint("Sanity check:\t");
|
cliPrint("Sanity check:\t");
|
||||||
for (i = 0; i < 3; i++)
|
for (i = 0; i < 3; i++)
|
||||||
uartPrint(fabs(mixsum[i]) > 0.01f ? "NG\t" : "OK\t");
|
cliPrint(fabs(mixsum[i]) > 0.01f ? "NG\t" : "OK\t");
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
return;
|
return;
|
||||||
} else if (strncasecmp(cmdline, "reset", 5) == 0) {
|
} else if (strncasecmp(cmdline, "reset", 5) == 0) {
|
||||||
// erase custom mixer
|
// erase custom mixer
|
||||||
|
@ -473,7 +475,7 @@ static void cliCMix(char *cmdline)
|
||||||
len = strlen(++ptr);
|
len = strlen(++ptr);
|
||||||
for (i = 0; ; i++) {
|
for (i = 0; ; i++) {
|
||||||
if (mixerNames[i] == NULL) {
|
if (mixerNames[i] == NULL) {
|
||||||
uartPrint("Invalid mixer type...\r\n");
|
cliPrint("Invalid mixer type...\r\n");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (strncasecmp(ptr, mixerNames[i], len) == 0) {
|
if (strncasecmp(ptr, mixerNames[i], len) == 0) {
|
||||||
|
@ -509,7 +511,7 @@ static void cliCMix(char *cmdline)
|
||||||
check++;
|
check++;
|
||||||
}
|
}
|
||||||
if (check != 4) {
|
if (check != 4) {
|
||||||
uartPrint("Wrong number of arguments, needs idx thr roll pitch yaw\r\n");
|
cliPrint("Wrong number of arguments, needs idx thr roll pitch yaw\r\n");
|
||||||
} else {
|
} else {
|
||||||
cliCMix("");
|
cliCMix("");
|
||||||
}
|
}
|
||||||
|
@ -521,9 +523,9 @@ static void cliCMix(char *cmdline)
|
||||||
|
|
||||||
static void cliDefaults(char *cmdline)
|
static void cliDefaults(char *cmdline)
|
||||||
{
|
{
|
||||||
uartPrint("Resetting to defaults...\r\n");
|
cliPrint("Resetting to defaults...\r\n");
|
||||||
checkFirstTime(true);
|
checkFirstTime(true);
|
||||||
uartPrint("Rebooting...");
|
cliPrint("Rebooting...");
|
||||||
delay(10);
|
delay(10);
|
||||||
systemReset(false);
|
systemReset(false);
|
||||||
}
|
}
|
||||||
|
@ -596,13 +598,13 @@ static void cliDump(char *cmdline)
|
||||||
setval = &valueTable[i];
|
setval = &valueTable[i];
|
||||||
printf("set %s = ", valueTable[i].name);
|
printf("set %s = ", valueTable[i].name);
|
||||||
cliPrintVar(setval, 0);
|
cliPrintVar(setval, 0);
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliExit(char *cmdline)
|
static void cliExit(char *cmdline)
|
||||||
{
|
{
|
||||||
uartPrint("\r\nLeaving CLI mode...\r\n");
|
cliPrint("\r\nLeaving CLI mode...\r\n");
|
||||||
*cliBuffer = '\0';
|
*cliBuffer = '\0';
|
||||||
bufferIndex = 0;
|
bufferIndex = 0;
|
||||||
cliMode = 0;
|
cliMode = 0;
|
||||||
|
@ -620,22 +622,22 @@ static void cliFeature(char *cmdline)
|
||||||
mask = featureMask();
|
mask = featureMask();
|
||||||
|
|
||||||
if (len == 0) {
|
if (len == 0) {
|
||||||
uartPrint("Enabled features: ");
|
cliPrint("Enabled features: ");
|
||||||
for (i = 0; ; i++) {
|
for (i = 0; ; i++) {
|
||||||
if (featureNames[i] == NULL)
|
if (featureNames[i] == NULL)
|
||||||
break;
|
break;
|
||||||
if (mask & (1 << i))
|
if (mask & (1 << i))
|
||||||
printf("%s ", featureNames[i]);
|
printf("%s ", featureNames[i]);
|
||||||
}
|
}
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
} else if (strncasecmp(cmdline, "list", len) == 0) {
|
} else if (strncasecmp(cmdline, "list", len) == 0) {
|
||||||
uartPrint("Available features: ");
|
cliPrint("Available features: ");
|
||||||
for (i = 0; ; i++) {
|
for (i = 0; ; i++) {
|
||||||
if (featureNames[i] == NULL)
|
if (featureNames[i] == NULL)
|
||||||
break;
|
break;
|
||||||
printf("%s ", featureNames[i]);
|
printf("%s ", featureNames[i]);
|
||||||
}
|
}
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
return;
|
return;
|
||||||
} else {
|
} else {
|
||||||
bool remove = false;
|
bool remove = false;
|
||||||
|
@ -648,16 +650,16 @@ static void cliFeature(char *cmdline)
|
||||||
|
|
||||||
for (i = 0; ; i++) {
|
for (i = 0; ; i++) {
|
||||||
if (featureNames[i] == NULL) {
|
if (featureNames[i] == NULL) {
|
||||||
uartPrint("Invalid feature name...\r\n");
|
cliPrint("Invalid feature name...\r\n");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (strncasecmp(cmdline, featureNames[i], len) == 0) {
|
if (strncasecmp(cmdline, featureNames[i], len) == 0) {
|
||||||
if (remove) {
|
if (remove) {
|
||||||
featureClear(1 << i);
|
featureClear(1 << i);
|
||||||
uartPrint("Disabled ");
|
cliPrint("Disabled ");
|
||||||
} else {
|
} else {
|
||||||
featureSet(1 << i);
|
featureSet(1 << i);
|
||||||
uartPrint("Enabled ");
|
cliPrint("Enabled ");
|
||||||
}
|
}
|
||||||
printf("%s\r\n", featureNames[i]);
|
printf("%s\r\n", featureNames[i]);
|
||||||
break;
|
break;
|
||||||
|
@ -670,7 +672,7 @@ static void cliHelp(char *cmdline)
|
||||||
{
|
{
|
||||||
uint32_t i = 0;
|
uint32_t i = 0;
|
||||||
|
|
||||||
uartPrint("Available commands:\r\n");
|
cliPrint("Available commands:\r\n");
|
||||||
for (i = 0; i < CMD_COUNT; i++)
|
for (i = 0; i < CMD_COUNT; i++)
|
||||||
printf("%s\t%s\r\n", cmdTable[i].name, cmdTable[i].param);
|
printf("%s\t%s\r\n", cmdTable[i].name, cmdTable[i].param);
|
||||||
}
|
}
|
||||||
|
@ -690,12 +692,12 @@ static void cliMap(char *cmdline)
|
||||||
for (i = 0; i < 8; i++) {
|
for (i = 0; i < 8; i++) {
|
||||||
if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
|
if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
|
||||||
continue;
|
continue;
|
||||||
uartPrint("Must be any order of AETR1234\r\n");
|
cliPrint("Must be any order of AETR1234\r\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
parseRcChannels(cmdline);
|
parseRcChannels(cmdline);
|
||||||
}
|
}
|
||||||
uartPrint("Current assignment: ");
|
cliPrint("Current assignment: ");
|
||||||
for (i = 0; i < 8; i++)
|
for (i = 0; i < 8; i++)
|
||||||
out[mcfg.rcmap[i]] = rcChannelLetters[i];
|
out[mcfg.rcmap[i]] = rcChannelLetters[i];
|
||||||
out[i] = '\0';
|
out[i] = '\0';
|
||||||
|
@ -713,19 +715,19 @@ static void cliMixer(char *cmdline)
|
||||||
printf("Current mixer: %s\r\n", mixerNames[mcfg.mixerConfiguration - 1]);
|
printf("Current mixer: %s\r\n", mixerNames[mcfg.mixerConfiguration - 1]);
|
||||||
return;
|
return;
|
||||||
} else if (strncasecmp(cmdline, "list", len) == 0) {
|
} else if (strncasecmp(cmdline, "list", len) == 0) {
|
||||||
uartPrint("Available mixers: ");
|
cliPrint("Available mixers: ");
|
||||||
for (i = 0; ; i++) {
|
for (i = 0; ; i++) {
|
||||||
if (mixerNames[i] == NULL)
|
if (mixerNames[i] == NULL)
|
||||||
break;
|
break;
|
||||||
printf("%s ", mixerNames[i]);
|
printf("%s ", mixerNames[i]);
|
||||||
}
|
}
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (i = 0; ; i++) {
|
for (i = 0; ; i++) {
|
||||||
if (mixerNames[i] == NULL) {
|
if (mixerNames[i] == NULL) {
|
||||||
uartPrint("Invalid mixer type...\r\n");
|
cliPrint("Invalid mixer type...\r\n");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
|
if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
|
||||||
|
@ -757,13 +759,24 @@ static void cliProfile(char *cmdline)
|
||||||
|
|
||||||
static void cliSave(char *cmdline)
|
static void cliSave(char *cmdline)
|
||||||
{
|
{
|
||||||
uartPrint("Saving...");
|
cliPrint("Saving...");
|
||||||
writeEEPROM(0, true);
|
writeEEPROM(0, true);
|
||||||
uartPrint("\r\nRebooting...");
|
cliPrint("\r\nRebooting...");
|
||||||
delay(10);
|
delay(10);
|
||||||
systemReset(false);
|
systemReset(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void cliPrint(const char *str)
|
||||||
|
{
|
||||||
|
while (*str)
|
||||||
|
uartWrite(core.mainport, *(str++));
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cliWrite(uint8_t ch)
|
||||||
|
{
|
||||||
|
uartWrite(core.mainport, ch);
|
||||||
|
}
|
||||||
|
|
||||||
static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
||||||
{
|
{
|
||||||
int32_t value = 0;
|
int32_t value = 0;
|
||||||
|
@ -838,12 +851,12 @@ static void cliSet(char *cmdline)
|
||||||
len = strlen(cmdline);
|
len = strlen(cmdline);
|
||||||
|
|
||||||
if (len == 0 || (len == 1 && cmdline[0] == '*')) {
|
if (len == 0 || (len == 1 && cmdline[0] == '*')) {
|
||||||
uartPrint("Current settings: \r\n");
|
cliPrint("Current settings: \r\n");
|
||||||
for (i = 0; i < VALUE_COUNT; i++) {
|
for (i = 0; i < VALUE_COUNT; i++) {
|
||||||
val = &valueTable[i];
|
val = &valueTable[i];
|
||||||
printf("%s = ", valueTable[i].name);
|
printf("%s = ", valueTable[i].name);
|
||||||
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
|
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
}
|
}
|
||||||
} else if ((eqptr = strstr(cmdline, "="))) {
|
} else if ((eqptr = strstr(cmdline, "="))) {
|
||||||
// has equal, set var
|
// has equal, set var
|
||||||
|
@ -859,12 +872,12 @@ static void cliSet(char *cmdline)
|
||||||
printf("%s set to ", valueTable[i].name);
|
printf("%s set to ", valueTable[i].name);
|
||||||
cliPrintVar(val, 0);
|
cliPrintVar(val, 0);
|
||||||
} else {
|
} else {
|
||||||
uartPrint("ERR: Value assignment out of range\r\n");
|
cliPrint("ERR: Value assignment out of range\r\n");
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
uartPrint("ERR: Unknown variable name\r\n");
|
cliPrint("ERR: Unknown variable name\r\n");
|
||||||
} else {
|
} else {
|
||||||
// no equals, check for matching variables.
|
// no equals, check for matching variables.
|
||||||
for (i = 0; i < VALUE_COUNT; i++) {
|
for (i = 0; i < VALUE_COUNT; i++) {
|
||||||
|
@ -899,26 +912,26 @@ static void cliStatus(char *cmdline)
|
||||||
if (accHardware == ACC_MPU6050)
|
if (accHardware == ACC_MPU6050)
|
||||||
printf(".%c", mcfg.mpu6050_scale ? 'o' : 'n');
|
printf(".%c", mcfg.mpu6050_scale ? 'o' : 'n');
|
||||||
}
|
}
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
|
|
||||||
printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cGetErrorCounter(), sizeof(master_t));
|
printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cGetErrorCounter(), sizeof(master_t));
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliVersion(char *cmdline)
|
static void cliVersion(char *cmdline)
|
||||||
{
|
{
|
||||||
uartPrint("Afro32 CLI version 2.1 " __DATE__ " / " __TIME__);
|
cliPrint("Afro32 CLI version 2.2 " __DATE__ " / " __TIME__);
|
||||||
}
|
}
|
||||||
|
|
||||||
void cliProcess(void)
|
void cliProcess(void)
|
||||||
{
|
{
|
||||||
if (!cliMode) {
|
if (!cliMode) {
|
||||||
cliMode = 1;
|
cliMode = 1;
|
||||||
uartPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
|
cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
|
||||||
cliPrompt();
|
cliPrompt();
|
||||||
}
|
}
|
||||||
|
|
||||||
while (isUartAvailable()) {
|
while (isUartAvailable(core.mainport)) {
|
||||||
uint8_t c = uartRead();
|
uint8_t c = uartRead(core.mainport);
|
||||||
if (c == '\t' || c == '?') {
|
if (c == '\t' || c == '?') {
|
||||||
// do tab completion
|
// do tab completion
|
||||||
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
|
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
|
||||||
|
@ -945,28 +958,28 @@ void cliProcess(void)
|
||||||
}
|
}
|
||||||
if (!bufferIndex || pstart != pend) {
|
if (!bufferIndex || pstart != pend) {
|
||||||
/* Print list of ambiguous matches */
|
/* Print list of ambiguous matches */
|
||||||
uartPrint("\r\033[K");
|
cliPrint("\r\033[K");
|
||||||
for (cmd = pstart; cmd <= pend; cmd++) {
|
for (cmd = pstart; cmd <= pend; cmd++) {
|
||||||
uartPrint(cmd->name);
|
cliPrint(cmd->name);
|
||||||
uartWrite('\t');
|
cliWrite('\t');
|
||||||
}
|
}
|
||||||
cliPrompt();
|
cliPrompt();
|
||||||
i = 0; /* Redraw prompt */
|
i = 0; /* Redraw prompt */
|
||||||
}
|
}
|
||||||
for (; i < bufferIndex; i++)
|
for (; i < bufferIndex; i++)
|
||||||
uartWrite(cliBuffer[i]);
|
cliWrite(cliBuffer[i]);
|
||||||
} else if (!bufferIndex && c == 4) {
|
} else if (!bufferIndex && c == 4) {
|
||||||
cliExit(cliBuffer);
|
cliExit(cliBuffer);
|
||||||
return;
|
return;
|
||||||
} else if (c == 12) {
|
} else if (c == 12) {
|
||||||
// clear screen
|
// clear screen
|
||||||
uartPrint("\033[2J\033[1;1H");
|
cliPrint("\033[2J\033[1;1H");
|
||||||
cliPrompt();
|
cliPrompt();
|
||||||
} else if (bufferIndex && (c == '\n' || c == '\r')) {
|
} else if (bufferIndex && (c == '\n' || c == '\r')) {
|
||||||
// enter pressed
|
// enter pressed
|
||||||
clicmd_t *cmd = NULL;
|
clicmd_t *cmd = NULL;
|
||||||
clicmd_t target;
|
clicmd_t target;
|
||||||
uartPrint("\r\n");
|
cliPrint("\r\n");
|
||||||
cliBuffer[bufferIndex] = 0; // null terminate
|
cliBuffer[bufferIndex] = 0; // null terminate
|
||||||
|
|
||||||
target.name = cliBuffer;
|
target.name = cliBuffer;
|
||||||
|
@ -976,7 +989,7 @@ void cliProcess(void)
|
||||||
if (cmd)
|
if (cmd)
|
||||||
cmd->func(cliBuffer + strlen(cmd->name) + 1);
|
cmd->func(cliBuffer + strlen(cmd->name) + 1);
|
||||||
else
|
else
|
||||||
uartPrint("ERR: Unknown command, try 'help'");
|
cliPrint("ERR: Unknown command, try 'help'");
|
||||||
|
|
||||||
memset(cliBuffer, 0, sizeof(cliBuffer));
|
memset(cliBuffer, 0, sizeof(cliBuffer));
|
||||||
bufferIndex = 0;
|
bufferIndex = 0;
|
||||||
|
@ -989,13 +1002,13 @@ void cliProcess(void)
|
||||||
// backspace
|
// backspace
|
||||||
if (bufferIndex) {
|
if (bufferIndex) {
|
||||||
cliBuffer[--bufferIndex] = 0;
|
cliBuffer[--bufferIndex] = 0;
|
||||||
uartPrint("\010 \010");
|
cliPrint("\010 \010");
|
||||||
}
|
}
|
||||||
} else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
|
} else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
|
||||||
if (!bufferIndex && c == 32)
|
if (!bufferIndex && c == 32)
|
||||||
continue;
|
continue;
|
||||||
cliBuffer[bufferIndex++] = c;
|
cliBuffer[bufferIndex++] = c;
|
||||||
uartWrite(c);
|
cliWrite(c);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
429
src/drv_uart.c
429
src/drv_uart.c
|
@ -1,59 +1,40 @@
|
||||||
#include "board.h"
|
#include "board.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
DMA UART routines idea lifted from AutoQuad
|
DMA UART routines idea lifted from AutoQuad
|
||||||
Copyright © 2011 Bill Nesbitt
|
Copyright © 2011 Bill Nesbitt
|
||||||
*/
|
*/
|
||||||
#define UART_BUFFER_SIZE 256
|
|
||||||
|
|
||||||
// Receive buffer, circular DMA
|
static serialPort_t serialPort1;
|
||||||
volatile uint8_t rxBuffer[UART_BUFFER_SIZE];
|
static serialPort_t serialPort2;
|
||||||
volatile uint32_t rxDMAPos = 0;
|
|
||||||
volatile uint8_t txBuffer[UART_BUFFER_SIZE];
|
|
||||||
volatile uint32_t txBufferTail = 0;
|
|
||||||
volatile uint32_t txBufferHead = 0;
|
|
||||||
volatile bool txDMAEmpty = false;
|
|
||||||
|
|
||||||
static void uartTxDMA(void)
|
// USART1 - Telemetry (RX/TX by DMA)
|
||||||
{
|
serialPort_t *serialUSART1(uint32_t baudRate, portmode_t mode)
|
||||||
DMA1_Channel4->CMAR = (uint32_t)&txBuffer[txBufferTail];
|
|
||||||
if (txBufferHead > txBufferTail) {
|
|
||||||
DMA1_Channel4->CNDTR = txBufferHead - txBufferTail;
|
|
||||||
txBufferTail = txBufferHead;
|
|
||||||
} else {
|
|
||||||
DMA1_Channel4->CNDTR = UART_BUFFER_SIZE - txBufferTail;
|
|
||||||
txBufferTail = 0;
|
|
||||||
}
|
|
||||||
txDMAEmpty = false;
|
|
||||||
DMA_Cmd(DMA1_Channel4, ENABLE);
|
|
||||||
}
|
|
||||||
|
|
||||||
void DMA1_Channel4_IRQHandler(void)
|
|
||||||
{
|
|
||||||
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
|
||||||
DMA_Cmd(DMA1_Channel4, DISABLE);
|
|
||||||
|
|
||||||
if (txBufferHead != txBufferTail)
|
|
||||||
uartTxDMA();
|
|
||||||
else
|
|
||||||
txDMAEmpty = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void uartInit(uint32_t speed)
|
|
||||||
{
|
{
|
||||||
|
serialPort_t *s;
|
||||||
|
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
||||||
|
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
||||||
gpio_config_t gpio;
|
gpio_config_t gpio;
|
||||||
USART_InitTypeDef USART_InitStructure;
|
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
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->rxDMAChannel = DMA1_Channel5;
|
||||||
|
s->txDMAChannel = DMA1_Channel4;
|
||||||
|
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||||
// USART1_TX PA9
|
// USART1_TX PA9
|
||||||
// USART1_RX PA10
|
// USART1_RX PA10
|
||||||
gpio.pin = Pin_9;
|
|
||||||
gpio.speed = Speed_2MHz;
|
gpio.speed = Speed_2MHz;
|
||||||
|
gpio.pin = Pin_9;
|
||||||
gpio.mode = Mode_AF_PP;
|
gpio.mode = Mode_AF_PP;
|
||||||
|
if (mode & MODE_TX)
|
||||||
gpioInit(GPIOA, &gpio);
|
gpioInit(GPIOA, &gpio);
|
||||||
gpio.pin = Pin_10;
|
gpio.pin = Pin_10;
|
||||||
gpio.mode = Mode_IPU;
|
gpio.mode = Mode_IPU;
|
||||||
|
if (mode & MODE_RX)
|
||||||
gpioInit(GPIOA, &gpio);
|
gpioInit(GPIOA, &gpio);
|
||||||
|
|
||||||
// DMA TX Interrupt
|
// DMA TX Interrupt
|
||||||
|
@ -63,191 +44,255 @@ void uartInit(uint32_t speed)
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
|
||||||
USART_InitStructure.USART_BaudRate = speed;
|
return s;
|
||||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
|
||||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
|
||||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
|
||||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
|
||||||
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
|
|
||||||
USART_Init(USART1, &USART_InitStructure);
|
|
||||||
|
|
||||||
// Receive DMA into a circular buffer
|
|
||||||
DMA_DeInit(DMA1_Channel5);
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USART1->DR;
|
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)rxBuffer;
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_BufferSize = UART_BUFFER_SIZE;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
|
||||||
DMA_Init(DMA1_Channel5, &DMA_InitStructure);
|
|
||||||
|
|
||||||
DMA_Cmd(DMA1_Channel5, ENABLE);
|
|
||||||
USART_DMACmd(USART1, USART_DMAReq_Rx, ENABLE);
|
|
||||||
rxDMAPos = DMA_GetCurrDataCounter(DMA1_Channel5);
|
|
||||||
|
|
||||||
// Transmit DMA
|
|
||||||
DMA_DeInit(DMA1_Channel4);
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USART1->DR;
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
|
||||||
DMA_Init(DMA1_Channel4, &DMA_InitStructure);
|
|
||||||
DMA_ITConfig(DMA1_Channel4, DMA_IT_TC, ENABLE);
|
|
||||||
DMA1_Channel4->CNDTR = 0;
|
|
||||||
USART_DMACmd(USART1, USART_DMAReq_Tx, ENABLE);
|
|
||||||
|
|
||||||
USART_Cmd(USART1, ENABLE);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isUartAvailable(void)
|
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
||||||
|
serialPort_t *serialUSART2(uint32_t baudRate, portmode_t mode)
|
||||||
{
|
{
|
||||||
return (DMA_GetCurrDataCounter(DMA1_Channel5) != rxDMAPos) ? true : false;
|
serialPort_t *s;
|
||||||
}
|
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
||||||
|
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
||||||
bool isUartTransmitDMAEmpty(void)
|
|
||||||
{
|
|
||||||
return txDMAEmpty;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool isUartTransmitEmpty(void)
|
|
||||||
{
|
|
||||||
return (txBufferTail == txBufferHead);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t uartRead(void)
|
|
||||||
{
|
|
||||||
uint8_t ch;
|
|
||||||
|
|
||||||
ch = rxBuffer[UART_BUFFER_SIZE - rxDMAPos];
|
|
||||||
// go back around the buffer
|
|
||||||
if (--rxDMAPos == 0)
|
|
||||||
rxDMAPos = UART_BUFFER_SIZE;
|
|
||||||
|
|
||||||
return ch;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t uartReadPoll(void)
|
|
||||||
{
|
|
||||||
while (!isUartAvailable()); // wait for some bytes
|
|
||||||
return uartRead();
|
|
||||||
}
|
|
||||||
|
|
||||||
void uartWrite(uint8_t ch)
|
|
||||||
{
|
|
||||||
txBuffer[txBufferHead] = ch;
|
|
||||||
txBufferHead = (txBufferHead + 1) % UART_BUFFER_SIZE;
|
|
||||||
|
|
||||||
// if DMA wasn't enabled, fire it up
|
|
||||||
if (!(DMA1_Channel4->CCR & 1))
|
|
||||||
uartTxDMA();
|
|
||||||
}
|
|
||||||
|
|
||||||
void uartPrint(char *str)
|
|
||||||
{
|
|
||||||
while (*str)
|
|
||||||
uartWrite(*(str++));
|
|
||||||
}
|
|
||||||
|
|
||||||
/* -------------------------- UART2 (Spektrum, GPS) ----------------------------- */
|
|
||||||
uartReceiveCallbackPtr uart2Callback = NULL;
|
|
||||||
#define UART2_BUFFER_SIZE 128
|
|
||||||
|
|
||||||
volatile uint8_t tx2Buffer[UART2_BUFFER_SIZE];
|
|
||||||
uint32_t tx2BufferTail = 0;
|
|
||||||
uint32_t tx2BufferHead = 0;
|
|
||||||
bool uart2RxOnly = false;
|
|
||||||
|
|
||||||
static void uart2Open(uint32_t speed)
|
|
||||||
{
|
|
||||||
USART_InitTypeDef USART_InitStructure;
|
|
||||||
|
|
||||||
USART_StructInit(&USART_InitStructure);
|
|
||||||
USART_InitStructure.USART_BaudRate = speed;
|
|
||||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
|
||||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
|
||||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
|
||||||
USART_InitStructure.USART_Mode = USART_Mode_Rx | (uart2RxOnly ? 0 : USART_Mode_Tx);
|
|
||||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
|
||||||
USART_Init(USART2, &USART_InitStructure);
|
|
||||||
USART_Cmd(USART2, ENABLE);
|
|
||||||
}
|
|
||||||
|
|
||||||
void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly)
|
|
||||||
{
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
gpio_config_t gpio;
|
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->USARTx = USART2;
|
||||||
|
|
||||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||||
|
// USART2_TX PA2
|
||||||
|
// USART2_RX PA3
|
||||||
|
gpio.speed = Speed_2MHz;
|
||||||
|
gpio.pin = GPIO_Pin_2;
|
||||||
|
gpio.mode = Mode_AF_PP;
|
||||||
|
if (mode & MODE_TX)
|
||||||
|
gpioInit(GPIOA, &gpio);
|
||||||
|
gpio.pin = Pin_3;
|
||||||
|
gpio.mode = Mode_IPU;
|
||||||
|
if (mode & MODE_RX)
|
||||||
|
gpioInit(GPIOA, &gpio);
|
||||||
|
|
||||||
uart2RxOnly = rxOnly;
|
// RX/TX Interrupt
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
|
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
|
||||||
// USART2_TX PA2
|
return s;
|
||||||
// USART2_RX PA3
|
|
||||||
gpio.pin = GPIO_Pin_2;
|
|
||||||
gpio.speed = Speed_2MHz;
|
|
||||||
gpio.mode = Mode_AF_PP;
|
|
||||||
if (!rxOnly)
|
|
||||||
gpioInit(GPIOA, &gpio);
|
|
||||||
gpio.pin = Pin_3;
|
|
||||||
gpio.mode = Mode_IPU;
|
|
||||||
gpioInit(GPIOA, &gpio);
|
|
||||||
|
|
||||||
uart2Open(speed);
|
|
||||||
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
|
|
||||||
if (!rxOnly)
|
|
||||||
USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
|
|
||||||
uart2Callback = func;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void uart2ChangeBaud(uint32_t speed)
|
serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, uint32_t baudRate, portmode_t mode)
|
||||||
{
|
{
|
||||||
uart2Open(speed);
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
USART_InitTypeDef USART_InitStructure;
|
||||||
|
serialPort_t *s = NULL;
|
||||||
|
|
||||||
|
if (USARTx == USART1)
|
||||||
|
s = serialUSART1(baudRate, mode);
|
||||||
|
if (USARTx == USART2)
|
||||||
|
s = serialUSART2(baudRate, mode);
|
||||||
|
|
||||||
|
s->USARTx = USARTx;
|
||||||
|
s->rxBufferHead = s->rxBufferTail = 0;
|
||||||
|
s->txBufferHead = s->txBufferTail = 0;
|
||||||
|
// callback for IRQ-based RX ONLY
|
||||||
|
s->callback = callback;
|
||||||
|
s->mode = mode;
|
||||||
|
|
||||||
|
USART_InitStructure.USART_BaudRate = baudRate;
|
||||||
|
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||||
|
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||||
|
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||||
|
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||||
|
USART_InitStructure.USART_Mode = 0;
|
||||||
|
if (mode & MODE_RX)
|
||||||
|
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
||||||
|
if (mode & MODE_TX)
|
||||||
|
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
||||||
|
USART_Init(USARTx, &USART_InitStructure);
|
||||||
|
USART_Cmd(USARTx, ENABLE);
|
||||||
|
|
||||||
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USARTx->DR;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||||
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
|
|
||||||
|
// Receive DMA or IRQ
|
||||||
|
if (mode & MODE_RX) {
|
||||||
|
if (s->rxDMAChannel) {
|
||||||
|
DMA_InitStructure.DMA_BufferSize = s->rxBufferSize;
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||||
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->rxBuffer;
|
||||||
|
DMA_DeInit(s->rxDMAChannel);
|
||||||
|
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
|
||||||
|
DMA_Cmd(s->rxDMAChannel, ENABLE);
|
||||||
|
USART_DMACmd(USARTx, USART_DMAReq_Rx, ENABLE);
|
||||||
|
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
|
||||||
|
} else {
|
||||||
|
USART_ITConfig(USARTx, USART_IT_RXNE, ENABLE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void uart2Write(uint8_t ch)
|
// Transmit DMA or IRQ
|
||||||
|
if (mode & MODE_TX) {
|
||||||
|
if (s->txDMAChannel) {
|
||||||
|
DMA_InitStructure.DMA_BufferSize = s->txBufferSize;
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
|
DMA_DeInit(s->txDMAChannel);
|
||||||
|
DMA_Init(s->txDMAChannel, &DMA_InitStructure);
|
||||||
|
DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE);
|
||||||
|
DMA_SetCurrDataCounter(s->txDMAChannel, 0);
|
||||||
|
s->txDMAChannel->CNDTR = 0;
|
||||||
|
USART_DMACmd(USARTx, USART_DMAReq_Tx, ENABLE);
|
||||||
|
} else {
|
||||||
|
USART_ITConfig(USARTx, USART_IT_TXE, ENABLE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return s;
|
||||||
|
}
|
||||||
|
|
||||||
|
void uartChangeBaud(serialPort_t *s, uint32_t baudRate)
|
||||||
{
|
{
|
||||||
if (uart2RxOnly)
|
USART_InitTypeDef USART_InitStructure;
|
||||||
return;
|
|
||||||
|
|
||||||
tx2Buffer[tx2BufferHead] = ch;
|
USART_InitStructure.USART_BaudRate = baudRate;
|
||||||
tx2BufferHead = (tx2BufferHead + 1) % UART2_BUFFER_SIZE;
|
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||||
|
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||||
USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
|
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||||
|
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||||
|
USART_InitStructure.USART_Mode = 0;
|
||||||
|
if (s->mode & MODE_RX)
|
||||||
|
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
||||||
|
if (s->mode & MODE_TX)
|
||||||
|
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
||||||
|
USART_Init(s->USARTx, &USART_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isUart2TransmitEmpty(void)
|
static void uartStartTxDMA(serialPort_t *s)
|
||||||
{
|
{
|
||||||
return tx2BufferTail == tx2BufferHead;
|
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;
|
||||||
|
} else {
|
||||||
|
s->txDMAChannel->CNDTR = s->txBufferSize - s->txBufferTail;
|
||||||
|
s->txBufferTail = 0;
|
||||||
|
}
|
||||||
|
s->txDMAEmpty = false;
|
||||||
|
DMA_Cmd(s->txDMAChannel, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isUartAvailable(serialPort_t *s)
|
||||||
|
{
|
||||||
|
if (s->rxDMAChannel)
|
||||||
|
return s->rxDMAChannel->CNDTR != s->rxDMAPos;
|
||||||
|
else
|
||||||
|
return s->rxBufferTail != s->rxBufferHead;
|
||||||
|
}
|
||||||
|
|
||||||
|
// BUGBUG TODO TODO FIXME
|
||||||
|
bool isUartTransmitEmpty(serialPort_t *s)
|
||||||
|
{
|
||||||
|
if (s->txDMAChannel)
|
||||||
|
return s->txDMAEmpty;
|
||||||
|
else
|
||||||
|
return s->txBufferTail == s->txBufferHead;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t uartRead(serialPort_t *s)
|
||||||
|
{
|
||||||
|
uint8_t ch;
|
||||||
|
|
||||||
|
if (s->rxDMAChannel) {
|
||||||
|
ch = s->rxBuffer[s->rxBufferSize - s->rxDMAPos];
|
||||||
|
if (--s->rxDMAPos == 0)
|
||||||
|
s->rxDMAPos = s->rxBufferSize;
|
||||||
|
} else {
|
||||||
|
ch = s->rxBuffer[s->rxBufferTail];
|
||||||
|
s->rxBufferTail = (s->rxBufferTail + 1) % s->rxBufferSize;
|
||||||
|
}
|
||||||
|
|
||||||
|
return ch;
|
||||||
|
}
|
||||||
|
|
||||||
|
void uartWrite(serialPort_t *s, uint8_t ch)
|
||||||
|
{
|
||||||
|
s->txBuffer[s->txBufferHead] = ch;
|
||||||
|
s->txBufferHead = (s->txBufferHead + 1) % s->txBufferSize;
|
||||||
|
|
||||||
|
if (s->txDMAChannel) {
|
||||||
|
if (!(s->txDMAChannel->CCR & 1))
|
||||||
|
uartStartTxDMA(s);
|
||||||
|
} else {
|
||||||
|
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Handlers
|
||||||
|
|
||||||
|
// USART1 Tx DMA Handler
|
||||||
|
void DMA1_Channel4_IRQHandler(void)
|
||||||
|
{
|
||||||
|
serialPort_t *s = &serialPort1;
|
||||||
|
DMA_ClearITPendingBit(DMA1_IT_TC4);
|
||||||
|
DMA_Cmd(s->txDMAChannel, DISABLE);
|
||||||
|
|
||||||
|
if (s->txBufferHead != s->txBufferTail)
|
||||||
|
uartStartTxDMA(s);
|
||||||
|
else
|
||||||
|
s->txDMAEmpty = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// USART1 Tx IRQ Handler
|
||||||
|
void USART1_IRQHandler(void)
|
||||||
|
{
|
||||||
|
serialPort_t *s = &serialPort1;
|
||||||
|
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;
|
||||||
|
} else {
|
||||||
|
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// USART2 Rx/Tx IRQ Handler
|
||||||
void USART2_IRQHandler(void)
|
void USART2_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uint16_t SR = USART2->SR;
|
serialPort_t *s = &serialPort2;
|
||||||
|
uint16_t SR = s->USARTx->SR;
|
||||||
|
|
||||||
if (SR & USART_IT_RXNE) {
|
if (SR & USART_FLAG_RXNE) {
|
||||||
if (uart2Callback)
|
// If we registered a callback, pass crap there
|
||||||
uart2Callback(USART_ReceiveData(USART2));
|
if (s->callback) {
|
||||||
|
s->callback(s->USARTx->DR);
|
||||||
|
} else {
|
||||||
|
s->rxBuffer[s->rxBufferHead] = s->USARTx->DR;
|
||||||
|
s->rxBufferHead = (s->rxBufferHead + 1) % s->rxBufferSize;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (SR & USART_FLAG_TXE) {
|
if (SR & USART_FLAG_TXE) {
|
||||||
if (tx2BufferTail != tx2BufferHead) {
|
if (s->txBufferTail != s->txBufferHead) {
|
||||||
USART2->DR = tx2Buffer[tx2BufferTail];
|
s->USARTx->DR = s->txBuffer[s->txBufferTail];
|
||||||
tx2BufferTail = (tx2BufferTail + 1) % UART2_BUFFER_SIZE;
|
s->txBufferTail = (s->txBufferTail + 1) % s->txBufferSize;
|
||||||
} else {
|
} else {
|
||||||
USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
|
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,17 +1,50 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// USART1
|
#define UART_BUFFER_SIZE 64
|
||||||
void uartInit(uint32_t speed);
|
|
||||||
bool isUartAvailable(void);
|
|
||||||
bool isUartTransmitEmpty(void);
|
|
||||||
bool isUartTransmitDMAEmpty(void);
|
|
||||||
uint8_t uartRead(void);
|
|
||||||
uint8_t uartReadPoll(void);
|
|
||||||
void uartWrite(uint8_t ch);
|
|
||||||
void uartPrint(char *str);
|
|
||||||
|
|
||||||
// USART2 (GPS, Spektrum)
|
#define UART1_RX_BUFFER_SIZE 256
|
||||||
void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly);
|
#define UART1_TX_BUFFER_SIZE 256
|
||||||
void uart2ChangeBaud(uint32_t speed);
|
#define UART2_RX_BUFFER_SIZE 128
|
||||||
bool isUart2TransmitEmpty(void);
|
#define UART2_TX_BUFFER_SIZE 64
|
||||||
void uart2Write(uint8_t ch);
|
#define MAX_SERIAL_PORTS 2
|
||||||
|
|
||||||
|
// This is a bitmask
|
||||||
|
typedef enum portmode_t {
|
||||||
|
MODE_RX = 1,
|
||||||
|
MODE_TX = 2,
|
||||||
|
MODE_RXTX = 3
|
||||||
|
} portmode_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint32_t baudRate;
|
||||||
|
uint32_t rxBufferSize;
|
||||||
|
uint32_t txBufferSize;
|
||||||
|
volatile uint8_t *rxBuffer;
|
||||||
|
volatile uint8_t *txBuffer;
|
||||||
|
uint32_t rxDMAPos;
|
||||||
|
uint32_t rxBufferHead;
|
||||||
|
uint32_t rxBufferTail;
|
||||||
|
uint32_t txBufferHead;
|
||||||
|
uint32_t txBufferTail;
|
||||||
|
|
||||||
|
DMA_Channel_TypeDef *rxDMAChannel;
|
||||||
|
DMA_Channel_TypeDef *txDMAChannel;
|
||||||
|
uint32_t rxDMAIrq;
|
||||||
|
uint32_t txDMAIrq;
|
||||||
|
bool txDMAEmpty;
|
||||||
|
USART_TypeDef *USARTx;
|
||||||
|
|
||||||
|
uartReceiveCallbackPtr callback;
|
||||||
|
portmode_t mode;
|
||||||
|
} serialPort_t;
|
||||||
|
|
||||||
|
extern serialPort_t serialPort1;
|
||||||
|
extern serialPort_t serialPort2;
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
12
src/gps.c
12
src/gps.c
|
@ -43,7 +43,7 @@ void gpsInit(uint32_t baudrate)
|
||||||
int offset = 0;
|
int offset = 0;
|
||||||
|
|
||||||
GPS_set_pids();
|
GPS_set_pids();
|
||||||
uart2Init(baudrate, GPS_NewData, false);
|
core.gpsport = uartOpen(USART2, GPS_NewData, baudrate, MODE_RXTX);
|
||||||
|
|
||||||
if (mcfg.gps_type == GPS_UBLOX)
|
if (mcfg.gps_type == GPS_UBLOX)
|
||||||
offset = 0;
|
offset = 0;
|
||||||
|
@ -52,7 +52,7 @@ void gpsInit(uint32_t baudrate)
|
||||||
|
|
||||||
if (mcfg.gps_type != GPS_NMEA) {
|
if (mcfg.gps_type != GPS_NMEA) {
|
||||||
for (i = 0; i < 5; i++) {
|
for (i = 0; i < 5; i++) {
|
||||||
uart2ChangeBaud(init_speed[i]);
|
uartChangeBaud(core.gpsport, init_speed[i]);
|
||||||
switch (baudrate) {
|
switch (baudrate) {
|
||||||
case 19200:
|
case 19200:
|
||||||
gpsPrint(gpsInitStrings[offset]);
|
gpsPrint(gpsInitStrings[offset]);
|
||||||
|
@ -71,10 +71,10 @@ void gpsInit(uint32_t baudrate)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uart2ChangeBaud(baudrate);
|
uartChangeBaud(core.gpsport, baudrate);
|
||||||
if (mcfg.gps_type == GPS_UBLOX) {
|
if (mcfg.gps_type == GPS_UBLOX) {
|
||||||
for (i = 0; i < sizeof(ubloxInit); i++) {
|
for (i = 0; i < sizeof(ubloxInit); i++) {
|
||||||
uart2Write(ubloxInit[i]); // send ubx init binary
|
uartWrite(core.gpsport, ubloxInit[i]); // send ubx init binary
|
||||||
delay(4);
|
delay(4);
|
||||||
}
|
}
|
||||||
} else if (mcfg.gps_type == GPS_MTK) {
|
} else if (mcfg.gps_type == GPS_MTK) {
|
||||||
|
@ -91,13 +91,13 @@ void gpsInit(uint32_t baudrate)
|
||||||
static void gpsPrint(const char *str)
|
static void gpsPrint(const char *str)
|
||||||
{
|
{
|
||||||
while (*str) {
|
while (*str) {
|
||||||
uart2Write(*str);
|
uartWrite(core.gpsport, *str);
|
||||||
if (mcfg.gps_type == GPS_UBLOX)
|
if (mcfg.gps_type == GPS_UBLOX)
|
||||||
delay(4);
|
delay(4);
|
||||||
str++;
|
str++;
|
||||||
}
|
}
|
||||||
// wait to send all
|
// wait to send all
|
||||||
while (!isUart2TransmitEmpty());
|
while (!isUartTransmitEmpty(core.gpsport));
|
||||||
delay(30);
|
delay(30);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
32
src/main.c
32
src/main.c
|
@ -1,7 +1,8 @@
|
||||||
#include "board.h"
|
#include "board.h"
|
||||||
#include "mw.h"
|
#include "mw.h"
|
||||||
|
|
||||||
extern uint8_t useServo;
|
core_t core;
|
||||||
|
|
||||||
extern rcReadRawDataPtr rcReadRawFunc;
|
extern rcReadRawDataPtr rcReadRawFunc;
|
||||||
|
|
||||||
// two receiver read functions
|
// two receiver read functions
|
||||||
|
@ -19,8 +20,8 @@ static void _putc(void *p, char c)
|
||||||
int fputc(int c, FILE *f)
|
int fputc(int c, FILE *f)
|
||||||
{
|
{
|
||||||
// let DMA catch up a bit when using set or dump, we're too fast.
|
// let DMA catch up a bit when using set or dump, we're too fast.
|
||||||
while (!isUartTransmitDMAEmpty());
|
while (!isUartTransmitEmpty(core.mainport));
|
||||||
uartWrite(c);
|
uartWrite(core.mainport, c);
|
||||||
return c;
|
return c;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -31,27 +32,6 @@ int main(void)
|
||||||
drv_pwm_config_t pwm_params;
|
drv_pwm_config_t pwm_params;
|
||||||
drv_adc_config_t adc_params;
|
drv_adc_config_t adc_params;
|
||||||
|
|
||||||
#if 0
|
|
||||||
// PC12, PA15
|
|
||||||
// using this to write asm for bootloader :)
|
|
||||||
RCC->APB2ENR |= RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO; // GPIOA/C+AFIO only
|
|
||||||
AFIO->MAPR &= 0xF0FFFFFF;
|
|
||||||
AFIO->MAPR = 0x02000000;
|
|
||||||
GPIOA->CRH = 0x34444444; // PIN 15 Output 50MHz
|
|
||||||
GPIOA->BRR = 0x8000; // set low 15
|
|
||||||
GPIOC->CRH = 0x44434444; // PIN 12 Output 50MHz
|
|
||||||
GPIOC->BRR = 0x1000; // set low 12
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
// using this to write asm for bootloader :)
|
|
||||||
RCC->APB2ENR |= RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO; // GPIOB + AFIO
|
|
||||||
AFIO->MAPR &= 0xF0FFFFFF;
|
|
||||||
AFIO->MAPR = 0x02000000;
|
|
||||||
GPIOB->BRR = 0x18; // set low 4 & 3
|
|
||||||
GPIOB->CRL = 0x44433444; // PIN 4 & 3 Output 50MHz
|
|
||||||
#endif
|
|
||||||
|
|
||||||
systemInit();
|
systemInit();
|
||||||
#ifdef USE_LAME_PRINTF
|
#ifdef USE_LAME_PRINTF
|
||||||
init_printf(NULL, _putc);
|
init_printf(NULL, _putc);
|
||||||
|
@ -73,7 +53,7 @@ int main(void)
|
||||||
// We have these sensors; SENSORS_SET defined in board.h depending on hardware platform
|
// We have these sensors; SENSORS_SET defined in board.h depending on hardware platform
|
||||||
sensorsSet(SENSORS_SET);
|
sensorsSet(SENSORS_SET);
|
||||||
|
|
||||||
mixerInit(); // this will set useServo var depending on mixer type
|
mixerInit(); // this will set core.useServo var depending on mixer type
|
||||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||||
if (mcfg.mixerConfiguration == MULTITYPE_AIRPLANE || mcfg.mixerConfiguration == MULTITYPE_FLYING_WING)
|
if (mcfg.mixerConfiguration == MULTITYPE_AIRPLANE || mcfg.mixerConfiguration == MULTITYPE_FLYING_WING)
|
||||||
pwm_params.airplane = true;
|
pwm_params.airplane = true;
|
||||||
|
@ -82,7 +62,7 @@ int main(void)
|
||||||
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SPEKTRUM); // spektrum support uses UART too
|
pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SPEKTRUM); // spektrum support uses UART too
|
||||||
pwm_params.usePPM = feature(FEATURE_PPM);
|
pwm_params.usePPM = feature(FEATURE_PPM);
|
||||||
pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum
|
pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum
|
||||||
pwm_params.useServos = useServo;
|
pwm_params.useServos = core.useServo;
|
||||||
pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX;
|
pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX;
|
||||||
pwm_params.motorPwmRate = mcfg.motor_pwm_rate;
|
pwm_params.motorPwmRate = mcfg.motor_pwm_rate;
|
||||||
pwm_params.servoPwmRate = mcfg.servo_pwm_rate;
|
pwm_params.servoPwmRate = mcfg.servo_pwm_rate;
|
||||||
|
|
|
@ -2,7 +2,6 @@
|
||||||
#include "mw.h"
|
#include "mw.h"
|
||||||
|
|
||||||
static uint8_t numberMotor = 0;
|
static uint8_t numberMotor = 0;
|
||||||
uint8_t useServo = 0;
|
|
||||||
int16_t motor[MAX_MOTORS];
|
int16_t motor[MAX_MOTORS];
|
||||||
int16_t servo[8] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
|
int16_t servo[8] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
|
||||||
|
|
||||||
|
@ -144,10 +143,10 @@ void mixerInit(void)
|
||||||
int i;
|
int i;
|
||||||
|
|
||||||
// enable servos for mixes that require them. note, this shifts motor counts.
|
// enable servos for mixes that require them. note, this shifts motor counts.
|
||||||
useServo = mixers[mcfg.mixerConfiguration].useServo;
|
core.useServo = mixers[mcfg.mixerConfiguration].useServo;
|
||||||
// if we want camstab/trig, that also enables servos, even if mixer doesn't
|
// if we want camstab/trig, that also enables servos, even if mixer doesn't
|
||||||
if (feature(FEATURE_SERVO_TILT))
|
if (feature(FEATURE_SERVO_TILT))
|
||||||
useServo = 1;
|
core.useServo = 1;
|
||||||
|
|
||||||
if (mcfg.mixerConfiguration == MULTITYPE_CUSTOM) {
|
if (mcfg.mixerConfiguration == MULTITYPE_CUSTOM) {
|
||||||
// load custom mixer into currentMixer
|
// load custom mixer into currentMixer
|
||||||
|
@ -198,7 +197,7 @@ void mixerLoadMix(int index)
|
||||||
|
|
||||||
void writeServos(void)
|
void writeServos(void)
|
||||||
{
|
{
|
||||||
if (!useServo)
|
if (!core.useServo)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
switch (mcfg.mixerConfiguration) {
|
switch (mcfg.mixerConfiguration) {
|
||||||
|
|
11
src/mw.h
11
src/mw.h
|
@ -286,6 +286,16 @@ typedef struct master_t {
|
||||||
uint8_t chk; // XOR checksum
|
uint8_t chk; // XOR checksum
|
||||||
} master_t;
|
} master_t;
|
||||||
|
|
||||||
|
// Core runtime settings
|
||||||
|
typedef struct core_t {
|
||||||
|
serialPort_t *mainport;
|
||||||
|
serialPort_t *gpsport;
|
||||||
|
serialPort_t *telemport;
|
||||||
|
serialPort_t *rcvrport;
|
||||||
|
bool useServo;
|
||||||
|
|
||||||
|
} core_t;
|
||||||
|
|
||||||
typedef struct flags_t {
|
typedef struct flags_t {
|
||||||
uint8_t OK_TO_ARM;
|
uint8_t OK_TO_ARM;
|
||||||
uint8_t ARMED;
|
uint8_t ARMED;
|
||||||
|
@ -369,6 +379,7 @@ extern uint8_t GPS_svinfo_svid[16]; // Satellite ID
|
||||||
extern uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
extern uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
||||||
extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
||||||
|
|
||||||
|
extern core_t core;
|
||||||
extern master_t mcfg;
|
extern master_t mcfg;
|
||||||
extern config_t cfg;
|
extern config_t cfg;
|
||||||
extern flags_t f;
|
extern flags_t f;
|
||||||
|
|
24
src/serial.c
24
src/serial.c
|
@ -157,16 +157,16 @@ void serialize32(uint32_t a)
|
||||||
{
|
{
|
||||||
static uint8_t t;
|
static uint8_t t;
|
||||||
t = a;
|
t = a;
|
||||||
uartWrite(t);
|
uartWrite(core.mainport, t);
|
||||||
checksum ^= t;
|
checksum ^= t;
|
||||||
t = a >> 8;
|
t = a >> 8;
|
||||||
uartWrite(t);
|
uartWrite(core.mainport, t);
|
||||||
checksum ^= t;
|
checksum ^= t;
|
||||||
t = a >> 16;
|
t = a >> 16;
|
||||||
uartWrite(t);
|
uartWrite(core.mainport, t);
|
||||||
checksum ^= t;
|
checksum ^= t;
|
||||||
t = a >> 24;
|
t = a >> 24;
|
||||||
uartWrite(t);
|
uartWrite(core.mainport, t);
|
||||||
checksum ^= t;
|
checksum ^= t;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -174,16 +174,16 @@ void serialize16(int16_t a)
|
||||||
{
|
{
|
||||||
static uint8_t t;
|
static uint8_t t;
|
||||||
t = a;
|
t = a;
|
||||||
uartWrite(t);
|
uartWrite(core.mainport, t);
|
||||||
checksum ^= t;
|
checksum ^= t;
|
||||||
t = a >> 8 & 0xff;
|
t = a >> 8 & 0xff;
|
||||||
uartWrite(t);
|
uartWrite(core.mainport, t);
|
||||||
checksum ^= t;
|
checksum ^= t;
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialize8(uint8_t a)
|
void serialize8(uint8_t a)
|
||||||
{
|
{
|
||||||
uartWrite(a);
|
uartWrite(core.mainport, a);
|
||||||
checksum ^= a;
|
checksum ^= a;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -261,7 +261,9 @@ void serialInit(uint32_t baudrate)
|
||||||
{
|
{
|
||||||
int idx;
|
int idx;
|
||||||
|
|
||||||
uartInit(baudrate);
|
core.mainport = uartOpen(USART1, NULL, baudrate, MODE_RXTX);
|
||||||
|
// TODO fix/hax
|
||||||
|
core.telemport = core.mainport;
|
||||||
// calculate used boxes based on features and fill availableBoxes[] array
|
// calculate used boxes based on features and fill availableBoxes[] array
|
||||||
memset(availableBoxes, 0xFF, sizeof(availableBoxes));
|
memset(availableBoxes, 0xFF, sizeof(availableBoxes));
|
||||||
|
|
||||||
|
@ -670,8 +672,8 @@ void serialCom(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
while (isUartAvailable()) {
|
while (isUartAvailable(core.mainport)) {
|
||||||
c = uartRead();
|
c = uartRead(core.mainport);
|
||||||
|
|
||||||
if (c_state == IDLE) {
|
if (c_state == IDLE) {
|
||||||
c_state = (c == '$') ? HEADER_START : IDLE;
|
c_state = (c == '$') ? HEADER_START : IDLE;
|
||||||
|
@ -707,7 +709,7 @@ void serialCom(void)
|
||||||
c_state = IDLE;
|
c_state = IDLE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (!cliMode && !isUartAvailable() && feature(FEATURE_TELEMETRY) && f.ARMED) { // The first 2 conditions should never evaluate to true but I'm putting it here anyway - silpstream
|
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
|
||||||
sendTelemetry();
|
sendTelemetry();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -27,10 +27,10 @@ void spektrumInit(void)
|
||||||
spek_chan_mask = 0x03;
|
spek_chan_mask = 0x03;
|
||||||
}
|
}
|
||||||
|
|
||||||
uart2Init(115200, spektrumDataReceive, true);
|
core.rcvrport = uartOpen(USART2, spektrumDataReceive, 115200, MODE_RX);
|
||||||
}
|
}
|
||||||
|
|
||||||
// UART2 Receive ISR callback
|
// Receive ISR callback
|
||||||
static void spektrumDataReceive(uint16_t c)
|
static void spektrumDataReceive(uint16_t c)
|
||||||
{
|
{
|
||||||
uint32_t spekTime;
|
uint32_t spekTime;
|
||||||
|
|
|
@ -48,29 +48,28 @@
|
||||||
// from sensors.c
|
// from sensors.c
|
||||||
extern uint8_t batteryCellCount;
|
extern uint8_t batteryCellCount;
|
||||||
|
|
||||||
|
|
||||||
static void sendDataHead(uint8_t id)
|
static void sendDataHead(uint8_t id)
|
||||||
{
|
{
|
||||||
uartWrite(PROTOCOL_HEADER);
|
uartWrite(core.telemport, PROTOCOL_HEADER);
|
||||||
uartWrite(id);
|
uartWrite(core.telemport, id);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void sendTelemetryTail(void)
|
static void sendTelemetryTail(void)
|
||||||
{
|
{
|
||||||
uartWrite(PROTOCOL_TAIL);
|
uartWrite(core.telemport, PROTOCOL_TAIL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serializeFrsky(uint8_t data)
|
static void serializeFrsky(uint8_t data)
|
||||||
{
|
{
|
||||||
// take care of byte stuffing
|
// take care of byte stuffing
|
||||||
if (data == 0x5e) {
|
if (data == 0x5e) {
|
||||||
uartWrite(0x5d);
|
uartWrite(core.telemport, 0x5d);
|
||||||
uartWrite(0x3e);
|
uartWrite(core.telemport, 0x3e);
|
||||||
} else if (data == 0x5d) {
|
} else if (data == 0x5d) {
|
||||||
uartWrite(0x5d);
|
uartWrite(core.telemport, 0x5d);
|
||||||
uartWrite(0x3d);
|
uartWrite(core.telemport, 0x3d);
|
||||||
} else
|
} else
|
||||||
uartWrite(data);
|
uartWrite(core.telemport, data);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serialize16(int16_t a)
|
static void serialize16(int16_t a)
|
||||||
|
@ -183,7 +182,7 @@ static void sendVoltage(void)
|
||||||
/*
|
/*
|
||||||
* Send voltage with ID_VOLTAGE_AMP
|
* Send voltage with ID_VOLTAGE_AMP
|
||||||
*/
|
*/
|
||||||
static void sendVoltageAmp()
|
static void sendVoltageAmp(void)
|
||||||
{
|
{
|
||||||
uint16_t voltage = (vbat * 110) / 21;
|
uint16_t voltage = (vbat * 110) / 21;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue