Update serial port code so that it's possible to open more than one port

per function.

Note: a future commit will enable MSP to work on additional ports in
order to support simultaneous combinations of Serial/Bluetooth
configuration, OSD, RX_MSP on otherwise unused ports.
This commit is contained in:
Dominic Clifton 2014-05-22 12:41:07 +01:00
parent 4f88ff1054
commit 51d28e19aa
5 changed files with 107 additions and 4957 deletions

File diff suppressed because it is too large Load Diff

View File

@ -1,5 +1,6 @@
#pragma once
#define UNUSED(x) (void)(x)
#define BUILD_BUG_ON(condition) ((void)sizeof(char[1 - 2*!!(condition)]))
//#define SOFT_I2C // enable to test software i2c

View File

@ -73,8 +73,21 @@ typedef struct serialPortSearchResult_s {
serialPortFunction_t *portFunction;
const serialPortConstraint_t *portConstraint;
const functionConstraint_t *functionConstraint;
// private
uint8_t startSerialPortFunctionIndex; // used by findNextSerialPort
} serialPortSearchResult_t;
static serialPortFunctionList_t serialPortFunctionList = {
4,
serialPortFunctions
};
serialPortFunctionList_t *getSerialPortFunctionList(void)
{
return &serialPortFunctionList;
}
uint8_t lookupScenarioIndex(serialPortFunctionScenario_e scenario) {
uint8_t index;
for (index = 0; index < SERIAL_PORT_SCENARIO_COUNT; index++) {
@ -140,20 +153,11 @@ static void sortSerialPortFunctions(serialPortFunction_t *serialPortFunctions, u
qsort(serialPortFunctions, elements, sizeof(serialPortFunction_t), serialPortFunctionMostSpecificFirstComparator);
}
/*
* since this method, and other methods that use it, use a single instance of
* searchPortSearchResult be sure to copy the data out of it before it gets overwritten by another caller.
* If this becomes a problem perhaps change the implementation to use a destination argument.
*/
static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint)
serialPortSearchResult_t *findNextSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint, serialPortSearchResult_t *resultBuffer)
{
static serialPortSearchResult_t serialPortSearchResult;
sortSerialPortFunctions(serialPortFunctions, SERIAL_PORT_COUNT);
uint8_t serialPortFunctionIndex;
serialPortFunction_t *serialPortFunction;
for (serialPortFunctionIndex = 0; serialPortFunctionIndex < SERIAL_PORT_COUNT; serialPortFunctionIndex++) {
for (serialPortFunctionIndex = resultBuffer->startSerialPortFunctionIndex; serialPortFunctionIndex < SERIAL_PORT_COUNT; serialPortFunctionIndex++) {
serialPortFunction = &serialPortFunctions[serialPortFunctionIndex];
if (!(serialPortFunction->scenario & function)) {
@ -180,16 +184,38 @@ static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function, c
continue;
}
serialPortSearchResult.portIndex = serialPortIndex;
serialPortSearchResult.portConstraint = serialPortConstraint;
serialPortSearchResult.portFunction = serialPortFunction;
serialPortSearchResult.functionConstraint = functionConstraint;
return &serialPortSearchResult;
resultBuffer->portIndex = serialPortIndex;
resultBuffer->portConstraint = serialPortConstraint;
resultBuffer->portFunction = serialPortFunction;
resultBuffer->functionConstraint = functionConstraint;
uint8_t nextStartIndex = serialPortFunctionIndex + 1;
resultBuffer->startSerialPortFunctionIndex = nextStartIndex;
return resultBuffer;
}
return NULL;
}
/*
* since this method, and other methods that use it, use a single instance of
* searchPortSearchResult be sure to copy the data out of it before it gets overwritten by another caller.
* If this becomes a problem perhaps change the implementation to use a destination argument.
*/
static serialPortSearchResult_t *findSerialPort(serialPortFunction_e function, const functionConstraint_t *functionConstraint)
{
static serialPortSearchResult_t serialPortSearchResult;
memset(&serialPortSearchResult, 0, sizeof(serialPortSearchResult));
// FIXME this only needs to be done once, after the config has been loaded.
sortSerialPortFunctions(serialPortFunctions, SERIAL_PORT_COUNT);
return findNextSerialPort(function, functionConstraint, &serialPortSearchResult);
}
static serialPortFunction_t *findSerialPortFunction(uint16_t functionMask)
{
serialPortIndex_e portIndex;
@ -271,8 +297,7 @@ functionConstraint_t *getConfiguredFunctionConstraint(serialPortFunction_e funct
switch(function) {
case FUNCTION_MSP:
configuredFunctionConstraint.minBaudRate = serialConfig->msp_baudrate;
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
configuredFunctionConstraint.maxBaudRate = serialConfig->msp_baudrate;
break;
case FUNCTION_CLI:
@ -388,13 +413,27 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
{
serialPort_t *serialPort = NULL;
functionConstraint_t *functionConstraint = getConfiguredFunctionConstraint(function);
functionConstraint_t *initialFunctionConstraint = getConfiguredFunctionConstraint(function);
functionConstraint_t updatedFunctionConstraint;
memcpy(&updatedFunctionConstraint, initialFunctionConstraint, sizeof(updatedFunctionConstraint));
if (initialFunctionConstraint->autoBaud == NO_AUTOBAUD) {
updatedFunctionConstraint.minBaudRate = baudRate;
updatedFunctionConstraint.maxBaudRate = baudRate;
}
functionConstraint_t *functionConstraint = &updatedFunctionConstraint;
serialPortSearchResult_t *searchResult = findSerialPort(function, functionConstraint);
while(searchResult && searchResult->portFunction->port) {
// port is already open, find the next one
searchResult = findNextSerialPort(function, functionConstraint, searchResult);
}
if (!searchResult) {
return NULL;
}
serialPortIndex_e portIndex = searchResult->portIndex;
const serialPortConstraint_t *serialPortConstraint = searchResult->portConstraint;

View File

@ -78,6 +78,11 @@ typedef struct serialPortFunction_s {
serialPortFunction_e currentFunction;
} serialPortFunction_t;
typedef struct serialPortFunctionList_s {
uint8_t serialPortCount;
serialPortFunction_t *functions;
} serialPortFunctionList_t;
typedef struct serialConfig_s {
uint8_t serial_port_1_scenario;
uint8_t serial_port_2_scenario;
@ -109,5 +114,7 @@ bool isSerialConfigValid(serialConfig_t *serialConfig);
bool doesConfigurationUsePort(serialConfig_t *serialConfig, serialPortIdentifier_e portIdentifier);
bool isSerialPortFunctionShared(serialPortFunction_e functionToUse, uint16_t functionMask);
serialPortFunctionList_t *getSerialPortFunctionList(void);
void evaluateOtherData(uint8_t sr);
void handleSerial(void);

View File

@ -2,6 +2,8 @@
#include <stdint.h>
#include <string.h>
#include "build_config.h"
#include "platform.h"
#include "common/axis.h"
@ -277,6 +279,44 @@ reset:
}
}
// This rate is chosen since softserial supports it.
#define MSP_FALLBACK_BAUDRATE 19200
static void openAllMSPSerialPorts(serialConfig_t *serialConfig)
{
serialPort_t *port;
mspPort = NULL; // XXX delete this when adding support for MSP on more than one port.
do {
uint32_t baudRate = serialConfig->msp_baudrate;
bool triedFallbackRate = false;
do {
port = openSerialPort(FUNCTION_MSP, NULL, baudRate, MODE_RXTX, SERIAL_NOT_INVERTED);
if (!port) {
if (triedFallbackRate) {
break;
}
baudRate = MSP_FALLBACK_BAUDRATE;
triedFallbackRate = true;
}
} while (!port);
// XXX delete this when adding support for MSP on more than one port.
if (port) {
mspPort = port; // just use the last one opened for now, the least specific serial port scenario will in for now
}
} while (port);
// XXX this function might help with adding support for MSP on more than one port, if not delete it.
serialPortFunctionList_t *serialPortFunctionList = getSerialPortFunctionList();
UNUSED(serialPortFunctionList);
}
void mspInit(serialConfig_t *serialConfig)
{
int idx;
@ -316,10 +356,7 @@ void mspInit(serialConfig_t *serialConfig)
availableBoxes[idx++] = BOXTELEMETRY;
numberBoxItems = idx;
mspPort = findOpenSerialPort(FUNCTION_MSP);
if (!mspPort) {
mspPort = openSerialPort(FUNCTION_MSP, NULL, serialConfig->msp_baudrate, MODE_RXTX, SERIAL_NOT_INVERTED);
}
openAllMSPSerialPorts(serialConfig);
}
static void evaluateCommand(void)