mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
msp: add buffering around the writes.
This bulks up the writes and lets the USB VCP driver send one 20 byte frame instead of 20 one byte frames. This speeds up the blackbox download and makes VCP much more reliable when running under a virtual machine. Signed-off-by: Michael Hope <mlhx@google.com>
This commit is contained in:
parent
96306ff9ab
commit
0e460c18b0
1 changed files with 15 additions and 2 deletions
|
@ -43,6 +43,7 @@
|
|||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
|
@ -413,10 +414,11 @@ typedef struct mspPort_s {
|
|||
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
|
||||
|
||||
static mspPort_t *currentPort;
|
||||
static bufWriter_t *writer;
|
||||
|
||||
static void serialize8(uint8_t a)
|
||||
{
|
||||
serialWrite(mspSerialPort, a);
|
||||
bufWriterAppend(writer, a);
|
||||
currentPort->checksum ^= a;
|
||||
}
|
||||
|
||||
|
@ -1903,7 +1905,7 @@ static bool mspProcessReceivedData(uint8_t c)
|
|||
return true;
|
||||
}
|
||||
|
||||
void setCurrentPort(mspPort_t *port)
|
||||
static void setCurrentPort(mspPort_t *port)
|
||||
{
|
||||
currentPort = port;
|
||||
mspSerialPort = currentPort->port;
|
||||
|
@ -1921,6 +1923,10 @@ void mspProcess(void)
|
|||
}
|
||||
|
||||
setCurrentPort(candidatePort);
|
||||
// Big enough to fit a MSP_STATUS in one write.
|
||||
uint8_t buf[sizeof(bufWriter_t) + 20];
|
||||
writer = bufWriterInit(buf, sizeof(buf),
|
||||
serialWriteBufShim, currentPort->port);
|
||||
|
||||
while (serialRxBytesWaiting(mspSerialPort)) {
|
||||
|
||||
|
@ -1937,6 +1943,8 @@ void mspProcess(void)
|
|||
}
|
||||
}
|
||||
|
||||
bufWriterFlush(writer);
|
||||
|
||||
if (isRebootScheduled) {
|
||||
waitForSerialPortToFinishTransmitting(candidatePort->port);
|
||||
stopMotors();
|
||||
|
@ -2005,10 +2013,15 @@ void sendMspTelemetry(void)
|
|||
}
|
||||
|
||||
setCurrentPort(mspTelemetryPort);
|
||||
uint8_t buf[sizeof(bufWriter_t) + 16];
|
||||
writer = bufWriterInit(buf, sizeof(buf),
|
||||
serialWriteBufShim, currentPort->port);
|
||||
|
||||
processOutCommand(mspTelemetryCommandSequence[sequenceIndex]);
|
||||
tailSerialReply();
|
||||
|
||||
bufWriterFlush(writer);
|
||||
|
||||
sequenceIndex++;
|
||||
if (sequenceIndex >= TELEMETRY_MSP_COMMAND_SEQUENCE_ENTRY_COUNT) {
|
||||
sequenceIndex = 0;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue