Fix truncated blackbox headers on fast looptimes/slow UARTs
As a consequence, now supports 19200 baud for Blackbox logging
This commit is contained in:
parent
6e504ca52a
commit
94affd5841
|
@ -98,9 +98,12 @@ save.
|
|||
You need to let Cleanflight know which of [your serial ports][] you connect your OpenLog to (i.e. the Blackbox port),
|
||||
which you can do on the Configurator's Ports tab.
|
||||
|
||||
A hardware serial port is required (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the board).
|
||||
SoftSerial ports cannot be used as they are too slow. Blackbox needs to be set to at least 115200 baud on this port.
|
||||
When using fast looptimes (<2500), a baud rate of 250000 should be used instead in order to reduce dropped frames.
|
||||
You should use a hardware serial port (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the
|
||||
board). SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
|
||||
rate will need to be severely reduced to compensate. Therefore the use of SoftSerial is not recommended.
|
||||
|
||||
When using a hardware serial port, Blackbox should be set to at least 115200 baud on that port. When using fast
|
||||
looptimes (<2500), a baud rate of 250000 should be used instead in order to reduce dropped frames.
|
||||
|
||||
The serial port used for Blackbox cannot be shared with any other function (e.g. GPS, telemetry) except the MSP
|
||||
protocol. If MSP is used on the same port as Blackbox, then MSP will be active when the board is disarmed, and Blackbox
|
||||
|
@ -132,7 +135,7 @@ then you can use a spare motor header's +5V and GND pins to power the OpenLog wi
|
|||
Boards other than the Naze32 may have more accessible hardware serial devices, in which case refer to their
|
||||
documentation to decide how to wire up the logger. The key criteria are:
|
||||
|
||||
* Must be a hardware serial port. Not SoftSerial.
|
||||
* Should be a hardware serial port rather than SoftSerial.
|
||||
* Cannot be shared with any other function (GPS, telemetry) except MSP.
|
||||
* If MSP is used on the same UART, MSP will stop working when the board is armed.
|
||||
|
||||
|
@ -214,6 +217,9 @@ set blackbox_rate_denom = 2
|
|||
The data rate for my quadcopter using a looptime of 2400 and a rate of 1/1 is about 10.25kB/s. This allows about 18
|
||||
days of flight logs to fit on my OpenLog's 16GB MicroSD card, which ought to be enough for anybody :).
|
||||
|
||||
If you are logging using SoftSerial, you will almost certainly need to reduce your logging rate to 1/32. Even at that
|
||||
logging rate, looptimes faster than about 1000 cannot be successfully logged.
|
||||
|
||||
If you're logging to an onboard dataflash chip instead of an OpenLog, be aware that the 2MB of storage space it offers
|
||||
is pretty small. At the default 1/1 logging rate, and a 2400 looptime, this is only enough for about 3 minutes of
|
||||
flight. This could be long enough for you to investigate some flying problem with your craft, but you may want to reduce
|
||||
|
|
|
@ -264,6 +264,9 @@ typedef enum BlackboxState {
|
|||
BLACKBOX_STATE_SHUTTING_DOWN
|
||||
} BlackboxState;
|
||||
|
||||
#define BLACKBOX_FIRST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_HEADER
|
||||
#define BLACKBOX_LAST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_SYSINFO
|
||||
|
||||
typedef struct blackboxMainState_t {
|
||||
uint32_t time;
|
||||
|
||||
|
@ -325,7 +328,6 @@ static struct {
|
|||
*/
|
||||
union {
|
||||
int fieldIndex;
|
||||
int serialBudget;
|
||||
uint32_t startTime;
|
||||
} u;
|
||||
} xmitState;
|
||||
|
@ -452,6 +454,7 @@ static void blackboxSetState(BlackboxState newState)
|
|||
//Perform initial setup required for the new state
|
||||
switch (newState) {
|
||||
case BLACKBOX_STATE_SEND_HEADER:
|
||||
blackboxHeaderBudget = 0;
|
||||
xmitState.headerIndex = 0;
|
||||
xmitState.u.startTime = millis();
|
||||
break;
|
||||
|
@ -973,7 +976,6 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
|
|||
const void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition)
|
||||
{
|
||||
const blackboxFieldDefinition_t *def;
|
||||
int charsWritten;
|
||||
unsigned int headerCount;
|
||||
static bool needComma = false;
|
||||
size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions;
|
||||
|
@ -989,46 +991,76 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
|
|||
* We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
|
||||
* the whole header.
|
||||
*/
|
||||
|
||||
// On our first call we need to print the name of the header and a colon
|
||||
if (xmitState.u.fieldIndex == -1) {
|
||||
if (xmitState.headerIndex >= headerCount) {
|
||||
return false; //Someone probably called us again after we had already completed transmission
|
||||
}
|
||||
|
||||
charsWritten = blackboxPrintf("H Field %c %s:", xmitState.headerIndex >= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT ? deltaFrameChar : mainFrameChar, blackboxFieldHeaderNames[xmitState.headerIndex]);
|
||||
uint32_t charsToBeWritten = strlen("H Field x :") + strlen(blackboxFieldHeaderNames[xmitState.headerIndex]);
|
||||
|
||||
if (blackboxDeviceReserveBufferSpace(charsToBeWritten) != BLACKBOX_RESERVE_SUCCESS) {
|
||||
return true; // Try again later
|
||||
}
|
||||
|
||||
blackboxHeaderBudget -= blackboxPrintf("H Field %c %s:", xmitState.headerIndex >= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT ? deltaFrameChar : mainFrameChar, blackboxFieldHeaderNames[xmitState.headerIndex]);
|
||||
|
||||
xmitState.u.fieldIndex++;
|
||||
needComma = false;
|
||||
} else
|
||||
charsWritten = 0;
|
||||
}
|
||||
|
||||
for (; xmitState.u.fieldIndex < fieldCount && charsWritten < blackboxWriteChunkSize; xmitState.u.fieldIndex++) {
|
||||
// The longest we expect an integer to be as a string:
|
||||
const uint32_t LONGEST_INTEGER_STRLEN = 2;
|
||||
|
||||
for (; xmitState.u.fieldIndex < fieldCount; xmitState.u.fieldIndex++) {
|
||||
def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
|
||||
|
||||
if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
|
||||
// First (over)estimate the length of the string we want to print
|
||||
|
||||
int32_t bytesToWrite = 1; // Leading comma
|
||||
|
||||
// The first header is a field name
|
||||
if (xmitState.headerIndex == 0) {
|
||||
bytesToWrite += strlen(def->name) + strlen("[]") + LONGEST_INTEGER_STRLEN;
|
||||
} else {
|
||||
//The other headers are integers
|
||||
bytesToWrite += LONGEST_INTEGER_STRLEN;
|
||||
}
|
||||
|
||||
// Now perform the write if the buffer is large enough
|
||||
if (blackboxDeviceReserveBufferSpace(bytesToWrite) != BLACKBOX_RESERVE_SUCCESS) {
|
||||
// Ran out of space!
|
||||
return true;
|
||||
}
|
||||
|
||||
blackboxHeaderBudget -= bytesToWrite;
|
||||
|
||||
if (needComma) {
|
||||
blackboxWrite(',');
|
||||
charsWritten++;
|
||||
} else {
|
||||
needComma = true;
|
||||
}
|
||||
|
||||
// The first header is a field name
|
||||
if (xmitState.headerIndex == 0) {
|
||||
charsWritten += blackboxPrint(def->name);
|
||||
blackboxPrint(def->name);
|
||||
|
||||
// Do we need to print an index in brackets after the name?
|
||||
if (def->fieldNameIndex != -1) {
|
||||
charsWritten += blackboxPrintf("[%d]", def->fieldNameIndex);
|
||||
blackboxPrintf("[%d]", def->fieldNameIndex);
|
||||
}
|
||||
} else {
|
||||
//The other headers are integers
|
||||
charsWritten += blackboxPrintf("%d", def->arr[xmitState.headerIndex - 1]);
|
||||
blackboxPrintf("%d", def->arr[xmitState.headerIndex - 1]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Did we complete this line?
|
||||
if (xmitState.u.fieldIndex == fieldCount) {
|
||||
if (xmitState.u.fieldIndex == fieldCount && blackboxDeviceReserveBufferSpace(1) == BLACKBOX_RESERVE_SUCCESS) {
|
||||
blackboxHeaderBudget--;
|
||||
blackboxWrite('\n');
|
||||
xmitState.headerIndex++;
|
||||
xmitState.u.fieldIndex = -1;
|
||||
|
@ -1043,68 +1075,57 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
|
|||
*/
|
||||
static bool blackboxWriteSysinfo()
|
||||
{
|
||||
if (xmitState.headerIndex == 0) {
|
||||
xmitState.u.serialBudget = 0;
|
||||
xmitState.headerIndex = 1;
|
||||
}
|
||||
|
||||
// How many bytes can we afford to transmit this loop?
|
||||
xmitState.u.serialBudget = MIN(xmitState.u.serialBudget + blackboxWriteChunkSize, 64);
|
||||
|
||||
// Most headers will consume at least 20 bytes so wait until we've built up that much link budget
|
||||
if (xmitState.u.serialBudget < 20) {
|
||||
// Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
|
||||
if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS) {
|
||||
return false;
|
||||
}
|
||||
|
||||
switch (xmitState.headerIndex) {
|
||||
case 0:
|
||||
//Shouldn't ever get here
|
||||
blackboxPrintfHeaderLine("Firmware type:Cleanflight");
|
||||
break;
|
||||
case 1:
|
||||
xmitState.u.serialBudget -= blackboxPrint("H Firmware type:Cleanflight\n");
|
||||
blackboxPrintfHeaderLine("Firmware revision:%s", shortGitRevision);
|
||||
break;
|
||||
case 2:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H Firmware revision:%s\n", shortGitRevision);
|
||||
blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime);
|
||||
break;
|
||||
case 3:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime);
|
||||
blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
break;
|
||||
case 4:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
blackboxPrintfHeaderLine("rcRate:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
break;
|
||||
case 5:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
|
||||
break;
|
||||
case 6:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
|
||||
blackboxPrintfHeaderLine("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle);
|
||||
break;
|
||||
case 7:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
|
||||
blackboxPrintfHeaderLine("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
|
||||
break;
|
||||
case 8:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H gyro.scale:0x%x\n", castFloatBytesToInt(gyro.scale));
|
||||
blackboxPrintfHeaderLine("acc_1G:%u", acc_1G);
|
||||
break;
|
||||
case 9:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H acc_1G:%u\n", acc_1G);
|
||||
break;
|
||||
case 10:
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale);
|
||||
blackboxPrintfHeaderLine("vbatscale:%u", masterConfig.batteryConfig.vbatscale);
|
||||
} else {
|
||||
xmitState.headerIndex += 2; // Skip the next two vbat fields too
|
||||
}
|
||||
break;
|
||||
case 11:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage,
|
||||
case 10:
|
||||
blackboxPrintfHeaderLine("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage,
|
||||
masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
|
||||
break;
|
||||
case 12:
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H vbatref:%u\n", vbatReference);
|
||||
case 11:
|
||||
blackboxPrintfHeaderLine("vbatref:%u", vbatReference);
|
||||
break;
|
||||
case 13:
|
||||
case 12:
|
||||
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
|
||||
if (feature(FEATURE_CURRENT_METER)) {
|
||||
xmitState.u.serialBudget -= blackboxPrintf("H currentMeter:%d,%d\n", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
|
||||
blackboxPrintfHeaderLine("currentMeter:%d,%d", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
|
@ -1278,21 +1299,28 @@ void handleBlackbox(void)
|
|||
{
|
||||
int i;
|
||||
|
||||
if (blackboxState >= BLACKBOX_FIRST_HEADER_SENDING_STATE && blackboxState <= BLACKBOX_LAST_HEADER_SENDING_STATE) {
|
||||
blackboxReplenishHeaderBudget();
|
||||
}
|
||||
|
||||
switch (blackboxState) {
|
||||
case BLACKBOX_STATE_SEND_HEADER:
|
||||
//On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
|
||||
|
||||
/*
|
||||
* Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit
|
||||
* buffer.
|
||||
* Once the UART has had time to init, transmit the header in chunks so we don't overflow its transmit
|
||||
* buffer, overflow the OpenLog's buffer, or keep the main loop busy for too long.
|
||||
*/
|
||||
if (millis() > xmitState.u.startTime + 100) {
|
||||
for (i = 0; i < blackboxWriteChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
|
||||
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
|
||||
}
|
||||
if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION) == BLACKBOX_RESERVE_SUCCESS) {
|
||||
for (i = 0; i < BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
|
||||
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
|
||||
blackboxHeaderBudget--;
|
||||
}
|
||||
|
||||
if (blackboxHeader[xmitState.headerIndex] == '\0') {
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
|
||||
if (blackboxHeader[xmitState.headerIndex] == '\0') {
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -64,13 +64,15 @@
|
|||
|
||||
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
|
||||
|
||||
// How many bytes should we transmit per loop iteration?
|
||||
uint8_t blackboxWriteChunkSize = 16;
|
||||
// How many bytes can we transmit per loop iteration when writing headers?
|
||||
static uint8_t blackboxMaxHeaderBytesPerIteration;
|
||||
|
||||
// How many bytes can we write *this* iteration without overflowing transmit buffers or overstressing the OpenLog?
|
||||
int32_t blackboxHeaderBudget;
|
||||
|
||||
static serialPort_t *blackboxPort = NULL;
|
||||
static portSharing_e blackboxPortSharing;
|
||||
|
||||
|
||||
void blackboxWrite(uint8_t value)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
|
@ -92,17 +94,49 @@ static void _putc(void *p, char c)
|
|||
blackboxWrite(c);
|
||||
}
|
||||
|
||||
static int blackboxPrintfv(const char *fmt, va_list va)
|
||||
{
|
||||
return tfp_format(NULL, _putc, fmt, va);
|
||||
}
|
||||
|
||||
|
||||
//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!)
|
||||
int blackboxPrintf(const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
|
||||
va_start(va, fmt);
|
||||
int written = tfp_format(NULL, _putc, fmt, va);
|
||||
|
||||
int written = blackboxPrintfv(fmt, va);
|
||||
|
||||
va_end(va);
|
||||
|
||||
return written;
|
||||
}
|
||||
|
||||
// Print the null-terminated string 's' to the serial port and return the number of bytes written
|
||||
/*
|
||||
* printf a Blackbox header line with a leading "H " and trailing "\n" added automatically. blackboxHeaderBudget is
|
||||
* decreased to account for the number of bytes written.
|
||||
*/
|
||||
void blackboxPrintfHeaderLine(const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
|
||||
blackboxWrite('H');
|
||||
blackboxWrite(' ');
|
||||
|
||||
va_start(va, fmt);
|
||||
|
||||
int written = blackboxPrintfv(fmt, va);
|
||||
|
||||
va_end(va);
|
||||
|
||||
blackboxWrite('\n');
|
||||
|
||||
blackboxHeaderBudget -= written + 3;
|
||||
}
|
||||
|
||||
// Print the null-terminated string 's' to the blackbox device and return the number of bytes written
|
||||
int blackboxPrint(const char *s)
|
||||
{
|
||||
int length;
|
||||
|
@ -463,15 +497,6 @@ bool blackboxDeviceFlush(void)
|
|||
*/
|
||||
bool blackboxDeviceOpen(void)
|
||||
{
|
||||
/*
|
||||
* We want to write at about 7200 bytes per second to give the OpenLog a good chance to save to disk. If
|
||||
* about looptime microseconds elapse between our writes, this is the budget of how many bytes we should
|
||||
* transmit with each write.
|
||||
*
|
||||
* 9 / 1250 = 7200 / 1000000
|
||||
*/
|
||||
blackboxWriteChunkSize = MAX((masterConfig.looptime * 9) / 1250, 4);
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
{
|
||||
|
@ -499,6 +524,18 @@ bool blackboxDeviceOpen(void)
|
|||
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex],
|
||||
BLACKBOX_SERIAL_PORT_MODE, portOptions);
|
||||
|
||||
/*
|
||||
* The slowest MicroSD cards have a write latency approaching 150ms. The OpenLog's buffer is about 900
|
||||
* bytes. In order for its buffer to be able to absorb this latency we must write slower than 6000 B/s.
|
||||
*
|
||||
* So:
|
||||
* Bytes per loop iteration = floor((looptime_ns / 1000000.0) * 6000)
|
||||
* = floor((looptime_ns * 6000) / 1000000.0)
|
||||
* = floor((looptime_ns * 3) / 500.0)
|
||||
* = (looptime_ns * 3) / 500
|
||||
*/
|
||||
blackboxMaxHeaderBytesPerIteration = constrain((masterConfig.looptime * 3) / 500, 1, BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION);
|
||||
|
||||
return blackboxPort != NULL;
|
||||
}
|
||||
break;
|
||||
|
@ -508,6 +545,8 @@ bool blackboxDeviceOpen(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
blackboxMaxHeaderBytesPerIteration = BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION;
|
||||
|
||||
return true;
|
||||
break;
|
||||
#endif
|
||||
|
@ -558,4 +597,85 @@ bool isBlackboxDeviceFull(void)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Call once every loop iteration in order to maintain the global blackboxHeaderBudget with the number of bytes we can
|
||||
* transmit this iteration.
|
||||
*/
|
||||
void blackboxReplenishHeaderBudget()
|
||||
{
|
||||
int32_t freeSpace;
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
freeSpace = serialTxBytesFree(blackboxPort);
|
||||
break;
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
freeSpace = flashfsGetWriteBufferFreeSpace();
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
freeSpace = 0;
|
||||
}
|
||||
|
||||
blackboxHeaderBudget = MIN(MIN(freeSpace, blackboxHeaderBudget + blackboxMaxHeaderBytesPerIteration), BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET);
|
||||
}
|
||||
|
||||
/**
|
||||
* You must call this function before attempting to write Blackbox header bytes to ensure that the write will not
|
||||
* cause buffers to overflow. The number of bytes you can write is capped by the blackboxHeaderBudget. Calling this
|
||||
* reservation function doesn't decrease blackboxHeaderBudget, so you must manually decrement that variable by the
|
||||
* number of bytes you actually wrote.
|
||||
*
|
||||
* When the Blackbox device is FlashFS, a successful return code guarantees that no data will be lost if you write that
|
||||
* many bytes to the device (i.e. FlashFS's buffers won't overflow).
|
||||
*
|
||||
* When the device is a serial port, a successful return code guarantees that Cleanflight's serial Tx buffer will not
|
||||
* overflow, and the outgoing bandwidth is likely to be small enough to give the OpenLog time to absorb MicroSD card
|
||||
* latency. However the OpenLog could still end up silently dropping data.
|
||||
*
|
||||
* Returns:
|
||||
* BLACKBOX_RESERVE_SUCCESS - Upon success
|
||||
* BLACKBOX_RESERVE_TEMPORARY_FAILURE - The buffer is currently too full to service the request, try again later
|
||||
* BLACKBOX_RESERVE_PERMANENT_FAILURE - The buffer is too small to ever service this request
|
||||
*/
|
||||
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
|
||||
{
|
||||
if (bytes <= blackboxHeaderBudget) {
|
||||
return BLACKBOX_RESERVE_SUCCESS;
|
||||
}
|
||||
|
||||
// Handle failure:
|
||||
switch (masterConfig.blackbox_device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
// One byte of the tx buffer isn't available for user data (due to its circular list implementation), hence the -1
|
||||
if (bytes > (int32_t) blackboxPort->txBufferSize - 1) {
|
||||
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
|
||||
}
|
||||
|
||||
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
if (bytes > (int32_t) flashfsGetWriteBufferSize()) {
|
||||
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
|
||||
}
|
||||
|
||||
if (bytes > (int32_t) flashfsGetWriteBufferFreeSpace()) {
|
||||
/*
|
||||
* The write doesn't currently fit in the buffer, so try to make room for it. Our flushing here means
|
||||
* that the Blackbox header writing code doesn't have to guess about the best time to ask flashfs to
|
||||
* flush, and doesn't stall waiting for a flush that would otherwise not automatically be called.
|
||||
*/
|
||||
flashfsFlushAsync();
|
||||
}
|
||||
|
||||
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -32,11 +32,30 @@ typedef enum BlackboxDevice {
|
|||
BLACKBOX_DEVICE_END
|
||||
} BlackboxDevice;
|
||||
|
||||
extern uint8_t blackboxWriteChunkSize;
|
||||
typedef enum {
|
||||
BLACKBOX_RESERVE_SUCCESS,
|
||||
BLACKBOX_RESERVE_TEMPORARY_FAILURE,
|
||||
BLACKBOX_RESERVE_PERMANENT_FAILURE
|
||||
} blackboxBufferReserveStatus_e;
|
||||
|
||||
/*
|
||||
* We want to limit how bursty our writes to the device are. Note that this will also restrict the maximum size of a
|
||||
* header write we can make:
|
||||
*/
|
||||
#define BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET 256
|
||||
|
||||
/*
|
||||
* Ideally, each iteration in which we are logging headers would write a similar amount of data to the device as a
|
||||
* regular logging iteration. This way we won't hog the CPU by making a gigantic write:
|
||||
*/
|
||||
#define BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION 64
|
||||
|
||||
extern int32_t blackboxHeaderBudget;
|
||||
|
||||
void blackboxWrite(uint8_t value);
|
||||
|
||||
int blackboxPrintf(const char *fmt, ...);
|
||||
void blackboxPrintfHeaderLine(const char *fmt, ...);
|
||||
int blackboxPrint(const char *s);
|
||||
|
||||
void blackboxWriteUnsignedVB(uint32_t value);
|
||||
|
@ -55,3 +74,6 @@ bool blackboxDeviceOpen(void);
|
|||
void blackboxDeviceClose(void);
|
||||
|
||||
bool isBlackboxDeviceFull(void);
|
||||
|
||||
void blackboxReplenishHeaderBudget();
|
||||
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes);
|
||||
|
|
|
@ -114,11 +114,6 @@ uint32_t flashfsGetSize()
|
|||
return m25p16_getGeometry()->totalSize;
|
||||
}
|
||||
|
||||
const flashGeometry_t* flashfsGetGeometry()
|
||||
{
|
||||
return m25p16_getGeometry();
|
||||
}
|
||||
|
||||
static uint32_t flashfsTransmitBufferUsed()
|
||||
{
|
||||
if (bufferHead >= bufferTail)
|
||||
|
@ -127,6 +122,27 @@ static uint32_t flashfsTransmitBufferUsed()
|
|||
return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the size of the largest single write that flashfs could ever accept without blocking or data loss.
|
||||
*/
|
||||
uint32_t flashfsGetWriteBufferSize()
|
||||
{
|
||||
return FLASHFS_WRITE_BUFFER_USABLE;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of bytes that can currently be written to flashfs without any blocking or data loss.
|
||||
*/
|
||||
uint32_t flashfsGetWriteBufferFreeSpace()
|
||||
{
|
||||
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
|
||||
}
|
||||
|
||||
const flashGeometry_t* flashfsGetGeometry()
|
||||
{
|
||||
return m25p16_getGeometry();
|
||||
}
|
||||
|
||||
/**
|
||||
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
|
||||
* each write.
|
||||
|
|
|
@ -32,6 +32,8 @@ void flashfsEraseRange(uint32_t start, uint32_t end);
|
|||
|
||||
uint32_t flashfsGetSize();
|
||||
uint32_t flashfsGetOffset();
|
||||
uint32_t flashfsGetWriteBufferFreeSpace();
|
||||
uint32_t flashfsGetWriteBufferSize();
|
||||
int flashfsIdentifyStartOfFreeSpace();
|
||||
const flashGeometry_t* flashfsGetGeometry();
|
||||
|
||||
|
|
Loading…
Reference in New Issue