From 0e460c18b02a6ccbf7b8c95cfb448e5c645c1672 Mon Sep 17 00:00:00 2001 From: Michael Hope Date: Tue, 21 Jul 2015 21:26:39 +0200 Subject: [PATCH] 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 --- src/main/io/serial_msp.c | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 98c1b1671..16e466800 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -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;