Skip to content

Commit

Permalink
Eliminated inefficient serial function calls at runtime.
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeller committed May 9, 2018
1 parent 3af1610 commit 032f3b5
Show file tree
Hide file tree
Showing 5 changed files with 14 additions and 23 deletions.
2 changes: 1 addition & 1 deletion src/main/io/rcdevice_cam.c
Expand Up @@ -72,7 +72,7 @@ static bool rcdeviceIsCameraControlEnabled(void)

bool rcdeviceIsEnabled(void)
{
return findSerialPortConfig(FUNCTION_RCDEVICE) != NULL;
return camDevice->serialPort != NULL;
}

static bool rcdeviceIs5KeyEnabled(void)
Expand Down
17 changes: 2 additions & 15 deletions src/main/io/serial.c
Expand Up @@ -221,10 +221,6 @@ serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
return NULL;
}

typedef struct findSharedSerialPortState_s {
uint8_t lastIndex;
} findSharedSerialPortState_t;

portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
{
if (!portConfig || (portConfig->functionMask & function) == 0) {
Expand All @@ -238,19 +234,10 @@ bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionM
return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
}

static findSharedSerialPortState_t findSharedSerialPortState;

serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
{
memset(&findSharedSerialPortState, 0, sizeof(findSharedSerialPortState));

return findNextSharedSerialPort(functionMask, sharedWithFunction);
}

serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction)
{
while (findSharedSerialPortState.lastIndex < SERIAL_PORT_COUNT) {
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[findSharedSerialPortState.lastIndex++];
for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) {
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];

if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
const serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(candidate->identifier);
Expand Down
1 change: 0 additions & 1 deletion src/main/io/serial.h
Expand Up @@ -107,7 +107,6 @@ typedef struct serialPortUsage_s {
} serialPortUsage_t;

serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);

//
// configuration
Expand Down
16 changes: 10 additions & 6 deletions src/main/msp/msp_serial.c
Expand Up @@ -41,11 +41,12 @@

static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];

static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort)
static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, bool sharedWithTelemetry)
{
memset(mspPortToReset, 0, sizeof(mspPort_t));

mspPortToReset->port = serialPort;
mspPortToReset->sharedWithTelemetry = sharedWithTelemetry;
}

void mspSerialAllocatePorts(void)
Expand All @@ -61,7 +62,8 @@ void mspSerialAllocatePorts(void)

serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
if (serialPort) {
resetMspPort(mspPort, serialPort);
bool sharedWithTelemetry = isSerialPortShared(portConfig, FUNCTION_MSP, TELEMETRY_PORT_FUNCTIONS_MASK);
resetMspPort(mspPort, serialPort, sharedWithTelemetry);
portIndex++;
}

Expand All @@ -82,10 +84,12 @@ void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)

#if defined(USE_TELEMETRY)
void mspSerialReleaseSharedTelemetryPorts(void) {
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_PORT_FUNCTIONS_MASK, FUNCTION_MSP);
while (sharedPort) {
mspSerialReleasePortIfAllocated(sharedPort);
sharedPort = findNextSharedSerialPort(TELEMETRY_PORT_FUNCTIONS_MASK, FUNCTION_MSP);
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t *candidateMspPort = &mspPorts[portIndex];
if (candidateMspPort->sharedWithTelemetry) {
closeSerialPort(candidateMspPort->port);
memset(candidateMspPort, 0, sizeof(mspPort_t));
}
}
}
#endif
Expand Down
1 change: 1 addition & 0 deletions src/main/msp/msp_serial.h
Expand Up @@ -96,6 +96,7 @@ typedef struct __attribute__((packed)) {
struct serialPort_s;
typedef struct mspPort_s {
struct serialPort_s *port; // null when port unused.
bool sharedWithTelemetry;
timeMs_t lastActivityMs;
mspPendingSystemRequest_e pendingRequest;
mspState_e c_state;
Expand Down

0 comments on commit 032f3b5

Please sign in to comment.