Merge pull request #6382 from mikeller/fix_smartport_delay

Removed delay from SmartPort frame processing.
This commit is contained in:
Michael Keller 2018-07-17 18:42:12 +12:00 committed by GitHub
commit f487cea809
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
1 changed files with 3 additions and 12 deletions

View File

@ -203,8 +203,6 @@ typedef struct smartPortFrame_s {
static smartPortWriteFrameFn *smartPortWriteFrame; static smartPortWriteFrameFn *smartPortWriteFrame;
static timeUs_t lastTelemetryFrameReceivedUs;
#if defined(USE_MSP_OVER_TELEMETRY) #if defined(USE_MSP_OVER_TELEMETRY)
static bool smartPortMspReplyPending = false; static bool smartPortMspReplyPending = false;
#endif #endif
@ -234,7 +232,6 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
if ((c == FSSP_SENSOR_ID1) && checkQueueEmpty()) { if ((c == FSSP_SENSOR_ID1) && checkQueueEmpty()) {
// our slot is starting, no need to decode more // our slot is starting, no need to decode more
*clearToSend = true; *clearToSend = true;
lastTelemetryFrameReceivedUs = micros();
skipUntilStart = true; skipUntilStart = true;
} else if (c == FSSP_SENSOR_ID2) { } else if (c == FSSP_SENSOR_ID2) {
checksum = 0; checksum = 0;
@ -256,7 +253,6 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
checksum += c; checksum += c;
if (!useChecksum && (smartPortRxBytes == sizeof(smartPortPayload_t))) { if (!useChecksum && (smartPortRxBytes == sizeof(smartPortPayload_t))) {
lastTelemetryFrameReceivedUs = micros();
skipUntilStart = true; skipUntilStart = true;
return (smartPortPayload_t *)&rxBuffer; return (smartPortPayload_t *)&rxBuffer;
@ -267,7 +263,6 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
checksum += c; checksum += c;
checksum = (checksum & 0xFF) + (checksum >> 8); checksum = (checksum & 0xFF) + (checksum >> 8);
if (checksum == 0xFF) { if (checksum == 0xFF) {
lastTelemetryFrameReceivedUs = micros();
return (smartPortPayload_t *)&rxBuffer; return (smartPortPayload_t *)&rxBuffer;
} }
@ -816,21 +811,17 @@ static bool serialCheckQueueEmpty(void)
void handleSmartPortTelemetry(void) void handleSmartPortTelemetry(void)
{ {
static bool clearToSend = false;
static smartPortPayload_t *payload = NULL;
const uint32_t requestTimeout = millis() + SMARTPORT_SERVICE_TIMEOUT_MS; const uint32_t requestTimeout = millis() + SMARTPORT_SERVICE_TIMEOUT_MS;
if (telemetryState == TELEMETRY_STATE_INITIALIZED_SERIAL && smartPortSerialPort) { if (telemetryState == TELEMETRY_STATE_INITIALIZED_SERIAL && smartPortSerialPort) {
smartPortPayload_t *payload = NULL;
bool clearToSend = false;
while (serialRxBytesWaiting(smartPortSerialPort) > 0 && !payload) { while (serialRxBytesWaiting(smartPortSerialPort) > 0 && !payload) {
uint8_t c = serialRead(smartPortSerialPort); uint8_t c = serialRead(smartPortSerialPort);
payload = smartPortDataReceive(c, &clearToSend, serialCheckQueueEmpty, true); payload = smartPortDataReceive(c, &clearToSend, serialCheckQueueEmpty, true);
} }
if (cmpTimeUs(micros(), lastTelemetryFrameReceivedUs) >= SMARTPORT_MIN_TELEMETRY_RESPONSE_DELAY_US) { processSmartPortTelemetry(payload, &clearToSend, &requestTimeout);
processSmartPortTelemetry(payload, &clearToSend, &requestTimeout);
payload = NULL;
}
} }
} }
#endif #endif