1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

Clarified the name of the 'clear to send' function in SmartPort. (#9011)

Clarified the name of the 'clear to send' function in SmartPort.
This commit is contained in:
Michael Keller 2019-10-18 08:26:06 +13:00 committed by GitHub
commit 1c8d41b952
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
3 changed files with 10 additions and 9 deletions

View file

@ -254,7 +254,7 @@ static void buildTelemetryFrame(uint8_t *packet)
frame[14]=lcrc;
}
static bool frSkyXCheckQueueEmpty(void)
static bool frSkyXReadyToSend(void)
{
return true;
}
@ -553,7 +553,7 @@ rx_spi_received_e frSkyXProcessFrame(uint8_t * const packet)
}
while (remoteToProcessIndex < telemetryRxBuffer[remoteToProcessId].data.dataLength && !payload) {
payload = smartPortDataReceive(telemetryRxBuffer[remoteToProcessId].data.data[remoteToProcessIndex], &clearToSend, frSkyXCheckQueueEmpty, false);
payload = smartPortDataReceive(telemetryRxBuffer[remoteToProcessId].data.data[remoteToProcessIndex], &clearToSend, frSkyXReadyToSend, false);
remoteToProcessIndex = remoteToProcessIndex + 1;
}
}

View file

@ -207,7 +207,7 @@ static smartPortWriteFrameFn *smartPortWriteFrame;
static bool smartPortMspReplyPending = false;
#endif
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool useChecksum)
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortReadyToSendFn *readyToSend, bool useChecksum)
{
static uint8_t rxBuffer[sizeof(smartPortPayload_t)];
static uint8_t smartPortRxBytes = 0;
@ -229,9 +229,10 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
if (awaitingSensorId) {
awaitingSensorId = false;
if ((c == FSSP_SENSOR_ID1) && checkQueueEmpty()) {
// our slot is starting, no need to decode more
if ((c == FSSP_SENSOR_ID1) && readyToSend()) {
// our slot is starting, start sending
*clearToSend = true;
// no need to decode more
skipUntilStart = true;
} else if (c == FSSP_SENSOR_ID2) {
checksum = 0;
@ -865,7 +866,7 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
}
}
static bool serialCheckQueueEmpty(void)
static bool serialReadyToSend(void)
{
return (serialRxBytesWaiting(smartPortSerialPort) == 0);
}
@ -879,7 +880,7 @@ void handleSmartPortTelemetry(void)
bool clearToSend = false;
while (serialRxBytesWaiting(smartPortSerialPort) > 0 && !payload) {
uint8_t c = serialRead(smartPortSerialPort);
payload = smartPortDataReceive(c, &clearToSend, serialCheckQueueEmpty, true);
payload = smartPortDataReceive(c, &clearToSend, serialReadyToSend, true);
}
processSmartPortTelemetry(payload, &clearToSend, &requestTimeout);

View file

@ -61,7 +61,7 @@ typedef struct smartPortPayload_s {
} __attribute__((packed)) smartPortPayload_t;
typedef void smartPortWriteFrameFn(const smartPortPayload_t *payload);
typedef bool smartPortCheckQueueEmptyFn(void);
typedef bool smartPortReadyToSendFn(void);
bool initSmartPortTelemetry(void);
void checkSmartPortTelemetryState(void);
@ -70,7 +70,7 @@ bool initSmartPortTelemetryExternal(smartPortWriteFrameFn *smartPortWriteFrameEx
void handleSmartPortTelemetry(void);
void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *hasRequest, const uint32_t *requestTimeout);
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool withChecksum);
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortReadyToSendFn *checkQueueEmpty, bool withChecksum);
struct serialPort_s;
void smartPortWriteFrameSerial(const smartPortPayload_t *payload, struct serialPort_s *port, uint16_t checksum);