mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Make more bulk writes asynchronous where possible, begin MSP impl.
This commit is contained in:
parent
3888427558
commit
3c74ac2c91
3 changed files with 185 additions and 51 deletions
|
@ -112,33 +112,43 @@ static uint32_t flashfsTransmitBufferUsed()
|
||||||
return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead;
|
return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead;
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint32_t flashfsTransmitBufferRemaining()
|
|
||||||
{
|
|
||||||
return FLASHFS_WRITE_BUFFER_USABLE - flashfsTransmitBufferUsed();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Waits for the flash device to be ready to accept writes, then write the given buffers to flash sequentially.
|
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
|
||||||
|
* each write.
|
||||||
*
|
*
|
||||||
* Advances the address of the beginning of the supplied buffers and reduces the size of the buffers according to how
|
* In synchronous mode, waits for the flash to become ready before writing so that every byte requested can be written.
|
||||||
* many bytes get written.
|
*
|
||||||
|
* In asynchronous mode, if the flash is busy, then the write is aborted and the routine returns immediately.
|
||||||
|
* In this case the returned number of bytes written will be less than the total amount requested.
|
||||||
|
*
|
||||||
|
* Modifies the supplied buffer pointers and sizes to reflect how many bytes remain in each of them.
|
||||||
*
|
*
|
||||||
* bufferCount: the number of buffers provided
|
* bufferCount: the number of buffers provided
|
||||||
* buffers: an array of pointers to the beginning of buffers
|
* buffers: an array of pointers to the beginning of buffers
|
||||||
* bufferSizes: an array of the sizes of those buffers
|
* bufferSizes: an array of the sizes of those buffers
|
||||||
|
* sync: true if we should wait for the device to be idle before writes, otherwise if the device is busy the
|
||||||
|
* write will be aborted and this routine will return immediately.
|
||||||
|
*
|
||||||
|
* Returns the number of bytes written
|
||||||
*/
|
*/
|
||||||
static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount)
|
static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount, bool sync)
|
||||||
{
|
{
|
||||||
const flashGeometry_t *geometry = m25p16_getGeometry();
|
const flashGeometry_t *geometry = m25p16_getGeometry();
|
||||||
|
|
||||||
uint32_t bytesTotalRemaining = 0;
|
uint32_t bytesTotal = 0;
|
||||||
|
|
||||||
int i;
|
int i;
|
||||||
|
|
||||||
for (i = 0; i < bufferCount; i++) {
|
for (i = 0; i < bufferCount; i++) {
|
||||||
bytesTotalRemaining += bufferSizes[i];
|
bytesTotal += bufferSizes[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!sync && !m25p16_isReady()) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t bytesTotalRemaining = bytesTotal;
|
||||||
|
|
||||||
while (bytesTotalRemaining > 0) {
|
while (bytesTotalRemaining > 0) {
|
||||||
uint32_t bytesTotalThisIteration;
|
uint32_t bytesTotalThisIteration;
|
||||||
uint32_t bytesRemainThisIteration;
|
uint32_t bytesRemainThisIteration;
|
||||||
|
@ -186,7 +196,16 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes,
|
||||||
|
|
||||||
// Advance the cursor in the file system to match the bytes we wrote
|
// Advance the cursor in the file system to match the bytes we wrote
|
||||||
flashfsSetTailAddress(tailAddress + bytesTotalThisIteration);
|
flashfsSetTailAddress(tailAddress + bytesTotalThisIteration);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* We'll have to wait for that write to complete before we can issue the next one, so if
|
||||||
|
* the user requested asynchronous writes, break now.
|
||||||
|
*/
|
||||||
|
if (!sync)
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return bytesTotal - bytesTotalRemaining;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -209,6 +228,22 @@ static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t buffer
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Called after bytes have been written from the buffer to advance the position of the tail by the given amount.
|
||||||
|
*/
|
||||||
|
static void flashfsAdvanceTailInBuffer(uint32_t delta)
|
||||||
|
{
|
||||||
|
bufferTail += delta;
|
||||||
|
|
||||||
|
if (bufferTail > FLASHFS_WRITE_BUFFER_SIZE) {
|
||||||
|
bufferTail -= FLASHFS_WRITE_BUFFER_SIZE;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (bufferTail == bufferHead) {
|
||||||
|
flashfsClearBuffer();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* If the flash is ready to accept writes, flush the buffer to it, otherwise schedule
|
* If the flash is ready to accept writes, flush the buffer to it, otherwise schedule
|
||||||
* a flush for later and return immediately.
|
* a flush for later and return immediately.
|
||||||
|
@ -220,19 +255,15 @@ void flashfsFlushAsync()
|
||||||
return; // Nothing to flush
|
return; // Nothing to flush
|
||||||
}
|
}
|
||||||
|
|
||||||
if (m25p16_isReady()) {
|
|
||||||
uint8_t const * buffers[2];
|
uint8_t const * buffers[2];
|
||||||
uint32_t bufferSizes[2];
|
uint32_t bufferSizes[2];
|
||||||
|
uint32_t bytesWritten;
|
||||||
|
|
||||||
flashfsGetDirtyDataBuffers(buffers, bufferSizes);
|
flashfsGetDirtyDataBuffers(buffers, bufferSizes);
|
||||||
flashfsWriteBuffers(buffers, bufferSizes, 2);
|
bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 2, false);
|
||||||
|
flashfsAdvanceTailInBuffer(bytesWritten);
|
||||||
|
|
||||||
flashfsClearBuffer();
|
shouldFlush = bufferTail != bufferHead;
|
||||||
|
|
||||||
shouldFlush = false;
|
|
||||||
} else {
|
|
||||||
shouldFlush = true;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -248,9 +279,14 @@ void flashfsFlushSync()
|
||||||
return; // Nothing to write
|
return; // Nothing to write
|
||||||
}
|
}
|
||||||
|
|
||||||
m25p16_waitForReady(10); //TODO caller should customize timeout
|
uint8_t const * buffers[2];
|
||||||
|
uint32_t bufferSizes[2];
|
||||||
|
|
||||||
flashfsFlushAsync();
|
flashfsGetDirtyDataBuffers(buffers, bufferSizes);
|
||||||
|
flashfsWriteBuffers(buffers, bufferSizes, 2, true);
|
||||||
|
|
||||||
|
// We've written our entire buffer now:
|
||||||
|
flashfsClearBuffer();
|
||||||
}
|
}
|
||||||
|
|
||||||
void flashfsSeekAbs(uint32_t offset)
|
void flashfsSeekAbs(uint32_t offset)
|
||||||
|
@ -282,8 +318,6 @@ void flashfsWriteByte(uint8_t byte)
|
||||||
|
|
||||||
void flashfsWrite(const uint8_t *data, unsigned int len)
|
void flashfsWrite(const uint8_t *data, unsigned int len)
|
||||||
{
|
{
|
||||||
// Would writing this cause our buffer to reach the flush threshold? If so just write it now
|
|
||||||
if (shouldFlush || len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) {
|
|
||||||
uint8_t const * buffers[3];
|
uint8_t const * buffers[3];
|
||||||
uint32_t bufferSizes[3];
|
uint32_t bufferSizes[3];
|
||||||
|
|
||||||
|
@ -294,15 +328,48 @@ void flashfsWrite(const uint8_t *data, unsigned int len)
|
||||||
buffers[2] = data;
|
buffers[2] = data;
|
||||||
bufferSizes[2] = len;
|
bufferSizes[2] = len;
|
||||||
|
|
||||||
// Write all three buffers through to the flash
|
/*
|
||||||
flashfsWriteBuffers(buffers, bufferSizes, 3);
|
* Would writing this data to our buffer cause our buffer to reach the flush threshold? If so try to write through
|
||||||
|
* to the flash now
|
||||||
|
*/
|
||||||
|
if (shouldFlush || bufferSizes[0] + bufferSizes[1] + bufferSizes[2] >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) {
|
||||||
|
uint32_t bytesWritten;
|
||||||
|
|
||||||
// And now our buffer is empty
|
// Attempt to write all three buffers through to the flash asynchronously
|
||||||
|
bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 3, false);
|
||||||
|
|
||||||
|
if (bufferSizes[0] == 0 && bufferSizes[1] == 0) {
|
||||||
|
// We wrote all the data that was previously buffered
|
||||||
|
flashfsClearBuffer();
|
||||||
|
|
||||||
|
if (bufferSizes[2] == 0) {
|
||||||
|
// And we wrote all the data the user supplied! Job done!
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// We only wrote a portion of the old data, so advance the tail to remove the bytes we did write from the buffer
|
||||||
|
flashfsAdvanceTailInBuffer(bytesWritten);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] > FLASHFS_WRITE_BUFFER_USABLE) {
|
||||||
|
/*
|
||||||
|
* We don't have enough room to store the new data in the buffer without blocking waiting for the flash to
|
||||||
|
* become ready, so we're forced to write it through synchronously.
|
||||||
|
*
|
||||||
|
* TODO we can skip this code and just drop the data for this write instead if the caller wants to
|
||||||
|
* prioritize predictable response time over reliable data delivery (i.e. sync/async)
|
||||||
|
*/
|
||||||
|
flashfsWriteBuffers(buffers, bufferSizes, 3, true);
|
||||||
flashfsClearBuffer();
|
flashfsClearBuffer();
|
||||||
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Fall through and add the remainder of the incoming data to our buffer
|
||||||
|
data = buffers[2];
|
||||||
|
len = bufferSizes[2];
|
||||||
|
}
|
||||||
|
|
||||||
// Buffer up the data the user supplied instead of writing it right away
|
// Buffer up the data the user supplied instead of writing it right away
|
||||||
|
|
||||||
// First write the portion before we wrap around the end of the circular buffer
|
// First write the portion before we wrap around the end of the circular buffer
|
||||||
|
|
|
@ -114,7 +114,7 @@ static void cliMixer(char *cmdline);
|
||||||
|
|
||||||
#ifdef FLASHFS
|
#ifdef FLASHFS
|
||||||
static void cliFlashIdent(char *cmdline);
|
static void cliFlashIdent(char *cmdline);
|
||||||
static void cliFlashEraseSector(char *cmdline);
|
static void cliFlashErase(char *cmdline);
|
||||||
static void cliFlashWrite(char *cmdline);
|
static void cliFlashWrite(char *cmdline);
|
||||||
static void cliFlashRead(char *cmdline);
|
static void cliFlashRead(char *cmdline);
|
||||||
#endif
|
#endif
|
||||||
|
@ -175,7 +175,7 @@ const clicmd_t cmdTable[] = {
|
||||||
{ "exit", "", cliExit },
|
{ "exit", "", cliExit },
|
||||||
{ "feature", "list or -val or val", cliFeature },
|
{ "feature", "list or -val or val", cliFeature },
|
||||||
#ifdef FLASHFS
|
#ifdef FLASHFS
|
||||||
{ "flash_erase_sector", "erase flash sector at the given address", cliFlashEraseSector },
|
{ "flash_erase", "erase flash chip", cliFlashErase },
|
||||||
{ "flash_ident", "get flash chip details", cliFlashIdent },
|
{ "flash_ident", "get flash chip details", cliFlashIdent },
|
||||||
{ "flash_read", "read text from the given address", cliFlashRead },
|
{ "flash_read", "read text from the given address", cliFlashRead },
|
||||||
{ "flash_write", "write text to the given address", cliFlashWrite },
|
{ "flash_write", "write text to the given address", cliFlashWrite },
|
||||||
|
@ -757,12 +757,13 @@ static void cliFlashIdent(char *cmdline)
|
||||||
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize);
|
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliFlashEraseSector(char *cmdline)
|
static void cliFlashErase(char *cmdline)
|
||||||
{
|
{
|
||||||
uint32_t address = atoi(cmdline);
|
UNUSED(cmdline);
|
||||||
|
|
||||||
flashfsEraseRange(address, address + 1);
|
printf("Erasing, please wait...\r\n");
|
||||||
printf("Erased sector at %u.\r\n", address);
|
flashfsEraseCompletely();
|
||||||
|
printf("Erased flash chip.\r\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliFlashWrite(char *cmdline)
|
static void cliFlashWrite(char *cmdline)
|
||||||
|
|
|
@ -53,6 +53,7 @@
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
|
#include "io/flashfs.h"
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "sensors/boardalignment.h"
|
#include "sensors/boardalignment.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
@ -121,7 +122,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
||||||
#define MSP_PROTOCOL_VERSION 0
|
#define MSP_PROTOCOL_VERSION 0
|
||||||
|
|
||||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||||
#define API_VERSION_MINOR 4 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
#define API_VERSION_MINOR 5 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||||
|
|
||||||
#define API_VERSION_LENGTH 2
|
#define API_VERSION_LENGTH 2
|
||||||
|
|
||||||
|
@ -219,6 +220,10 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||||
// DEPRECATED - Use MSP_BUILD_INFO instead
|
// DEPRECATED - Use MSP_BUILD_INFO instead
|
||||||
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
|
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
|
||||||
|
|
||||||
|
#define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip
|
||||||
|
#define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip
|
||||||
|
#define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip
|
||||||
|
|
||||||
//
|
//
|
||||||
// Multwii original MSP commands
|
// Multwii original MSP commands
|
||||||
//
|
//
|
||||||
|
@ -421,24 +426,24 @@ uint32_t read32(void)
|
||||||
return t;
|
return t;
|
||||||
}
|
}
|
||||||
|
|
||||||
void headSerialResponse(uint8_t err, uint8_t s)
|
void headSerialResponse(uint8_t err, uint8_t responseBodySize)
|
||||||
{
|
{
|
||||||
serialize8('$');
|
serialize8('$');
|
||||||
serialize8('M');
|
serialize8('M');
|
||||||
serialize8(err ? '!' : '>');
|
serialize8(err ? '!' : '>');
|
||||||
currentPort->checksum = 0; // start calculating a new checksum
|
currentPort->checksum = 0; // start calculating a new checksum
|
||||||
serialize8(s);
|
serialize8(responseBodySize);
|
||||||
serialize8(currentPort->cmdMSP);
|
serialize8(currentPort->cmdMSP);
|
||||||
}
|
}
|
||||||
|
|
||||||
void headSerialReply(uint8_t s)
|
void headSerialReply(uint8_t responseBodySize)
|
||||||
{
|
{
|
||||||
headSerialResponse(0, s);
|
headSerialResponse(0, responseBodySize);
|
||||||
}
|
}
|
||||||
|
|
||||||
void headSerialError(uint8_t s)
|
void headSerialError(uint8_t responseBodySize)
|
||||||
{
|
{
|
||||||
headSerialResponse(1, s);
|
headSerialResponse(1, responseBodySize);
|
||||||
}
|
}
|
||||||
|
|
||||||
void tailSerialReply(void)
|
void tailSerialReply(void)
|
||||||
|
@ -518,6 +523,44 @@ reset:
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void serializeDataflashSummaryReply(void)
|
||||||
|
{
|
||||||
|
#ifdef FLASHFS
|
||||||
|
const flashGeometry_t *geometry = flashfsGetGeometry();
|
||||||
|
headSerialReply(2 * 4);
|
||||||
|
serialize32(geometry->sectors);
|
||||||
|
serialize32(geometry->totalSize);
|
||||||
|
#else
|
||||||
|
headSerialReply(2 * 4);
|
||||||
|
serialize32(0);
|
||||||
|
serialize32(0);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef FLASHFS
|
||||||
|
void serializeDataflashReadReply(uint32_t address, uint8_t size)
|
||||||
|
{
|
||||||
|
enum { DATAFLASH_READ_REPLY_CHUNK_SIZE = 128 };
|
||||||
|
|
||||||
|
uint8_t buffer[DATAFLASH_READ_REPLY_CHUNK_SIZE];
|
||||||
|
|
||||||
|
if (size > DATAFLASH_READ_REPLY_CHUNK_SIZE) {
|
||||||
|
size = DATAFLASH_READ_REPLY_CHUNK_SIZE;
|
||||||
|
}
|
||||||
|
|
||||||
|
headSerialReply(4 + size);
|
||||||
|
|
||||||
|
serialize32(address);
|
||||||
|
|
||||||
|
flashfsSeekAbs(address);
|
||||||
|
flashfsRead(buffer, size);
|
||||||
|
|
||||||
|
for (int i = 0; i < size; i++) {
|
||||||
|
serialize8(buffer[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, mspPortUsage_e usage)
|
static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, mspPortUsage_e usage)
|
||||||
{
|
{
|
||||||
memset(mspPortToReset, 0, sizeof(mspPort_t));
|
memset(mspPortToReset, 0, sizeof(mspPort_t));
|
||||||
|
@ -1128,6 +1171,22 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case MSP_DATAFLASH_SUMMARY:
|
||||||
|
serializeDataflashSummaryReply();
|
||||||
|
break;
|
||||||
|
|
||||||
|
#ifdef FLASHFS
|
||||||
|
case MSP_DATAFLASH_READ:
|
||||||
|
{
|
||||||
|
uint32_t readAddress = read32();
|
||||||
|
uint8_t readSize = read8();
|
||||||
|
|
||||||
|
serializeDataflashReadReply(readAddress, readSize);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case MSP_BF_BUILD_INFO:
|
case MSP_BF_BUILD_INFO:
|
||||||
headSerialReply(11 + 4 + 4);
|
headSerialReply(11 + 4 + 4);
|
||||||
for (i = 0; i < 11; i++)
|
for (i = 0; i < 11; i++)
|
||||||
|
@ -1333,6 +1392,13 @@ static bool processInCommand(void)
|
||||||
writeEEPROM();
|
writeEEPROM();
|
||||||
readEEPROM();
|
readEEPROM();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#ifdef FLASHFS
|
||||||
|
case MSP_DATAFLASH_ERASE:
|
||||||
|
flashfsEraseCompletely();
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
case MSP_SET_RAW_GPS:
|
case MSP_SET_RAW_GPS:
|
||||||
if (read8()) {
|
if (read8()) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue