mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Merge branch 'blackbox-serial-budget' of https://github.com/sherlockflight/cleanflight-dev into sherlockflight-blackbox-serial-budget
Conflicts: src/main/blackbox/blackbox.c
This commit is contained in:
commit
a319394f6b
20 changed files with 364 additions and 94 deletions
|
@ -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),
|
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.
|
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).
|
You should use a hardware serial port (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the
|
||||||
SoftSerial ports cannot be used as they are too slow. Blackbox needs to be set to at least 115200 baud on this port.
|
board). SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
|
||||||
When using fast looptimes (<2500), a baud rate of 250000 should be used instead in order to reduce dropped frames.
|
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
|
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
|
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
|
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:
|
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.
|
* 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.
|
* 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
|
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 :).
|
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
|
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
|
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
|
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
|
BLACKBOX_STATE_SHUTTING_DOWN
|
||||||
} BlackboxState;
|
} BlackboxState;
|
||||||
|
|
||||||
|
#define BLACKBOX_FIRST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_HEADER
|
||||||
|
#define BLACKBOX_LAST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_SYSINFO
|
||||||
|
|
||||||
typedef struct blackboxMainState_s {
|
typedef struct blackboxMainState_s {
|
||||||
uint32_t time;
|
uint32_t time;
|
||||||
|
|
||||||
|
@ -325,7 +328,6 @@ static struct {
|
||||||
*/
|
*/
|
||||||
union {
|
union {
|
||||||
int fieldIndex;
|
int fieldIndex;
|
||||||
int serialBudget;
|
|
||||||
uint32_t startTime;
|
uint32_t startTime;
|
||||||
} u;
|
} u;
|
||||||
} xmitState;
|
} xmitState;
|
||||||
|
@ -452,6 +454,7 @@ static void blackboxSetState(BlackboxState newState)
|
||||||
//Perform initial setup required for the new state
|
//Perform initial setup required for the new state
|
||||||
switch (newState) {
|
switch (newState) {
|
||||||
case BLACKBOX_STATE_SEND_HEADER:
|
case BLACKBOX_STATE_SEND_HEADER:
|
||||||
|
blackboxHeaderBudget = 0;
|
||||||
xmitState.headerIndex = 0;
|
xmitState.headerIndex = 0;
|
||||||
xmitState.u.startTime = millis();
|
xmitState.u.startTime = millis();
|
||||||
break;
|
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 void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition)
|
||||||
{
|
{
|
||||||
const blackboxFieldDefinition_t *def;
|
const blackboxFieldDefinition_t *def;
|
||||||
int charsWritten;
|
|
||||||
unsigned int headerCount;
|
unsigned int headerCount;
|
||||||
static bool needComma = false;
|
static bool needComma = false;
|
||||||
size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions;
|
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
|
* 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.
|
* 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.u.fieldIndex == -1) {
|
||||||
if (xmitState.headerIndex >= headerCount) {
|
if (xmitState.headerIndex >= headerCount) {
|
||||||
return false; //Someone probably called us again after we had already completed transmission
|
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++;
|
xmitState.u.fieldIndex++;
|
||||||
needComma = false;
|
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);
|
def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
|
||||||
|
|
||||||
if (!conditions || testBlackboxCondition(conditions[conditionsStride * 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) {
|
if (needComma) {
|
||||||
blackboxWrite(',');
|
blackboxWrite(',');
|
||||||
charsWritten++;
|
|
||||||
} else {
|
} else {
|
||||||
needComma = true;
|
needComma = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// The first header is a field name
|
// The first header is a field name
|
||||||
if (xmitState.headerIndex == 0) {
|
if (xmitState.headerIndex == 0) {
|
||||||
charsWritten += blackboxPrint(def->name);
|
blackboxPrint(def->name);
|
||||||
|
|
||||||
// Do we need to print an index in brackets after the name?
|
// Do we need to print an index in brackets after the name?
|
||||||
if (def->fieldNameIndex != -1) {
|
if (def->fieldNameIndex != -1) {
|
||||||
charsWritten += blackboxPrintf("[%d]", def->fieldNameIndex);
|
blackboxPrintf("[%d]", def->fieldNameIndex);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
//The other headers are integers
|
//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?
|
// Did we complete this line?
|
||||||
if (xmitState.u.fieldIndex == fieldCount) {
|
if (xmitState.u.fieldIndex == fieldCount && blackboxDeviceReserveBufferSpace(1) == BLACKBOX_RESERVE_SUCCESS) {
|
||||||
|
blackboxHeaderBudget--;
|
||||||
blackboxWrite('\n');
|
blackboxWrite('\n');
|
||||||
xmitState.headerIndex++;
|
xmitState.headerIndex++;
|
||||||
xmitState.u.fieldIndex = -1;
|
xmitState.u.fieldIndex = -1;
|
||||||
|
@ -1043,68 +1075,57 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
|
||||||
*/
|
*/
|
||||||
static bool blackboxWriteSysinfo()
|
static bool blackboxWriteSysinfo()
|
||||||
{
|
{
|
||||||
if (xmitState.headerIndex == 0) {
|
// Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
|
||||||
xmitState.u.serialBudget = 0;
|
if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS) {
|
||||||
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) {
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (xmitState.headerIndex) {
|
switch (xmitState.headerIndex) {
|
||||||
case 0:
|
case 0:
|
||||||
//Shouldn't ever get here
|
blackboxPrintfHeaderLine("Firmware type:Cleanflight");
|
||||||
break;
|
break;
|
||||||
case 1:
|
case 1:
|
||||||
xmitState.u.serialBudget -= blackboxPrint("H Firmware type:Cleanflight\n");
|
blackboxPrintfHeaderLine("Firmware revision:%s", shortGitRevision);
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H Firmware revision:%s\n", shortGitRevision);
|
blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime);
|
||||||
break;
|
break;
|
||||||
case 3:
|
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;
|
break;
|
||||||
case 4:
|
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;
|
break;
|
||||||
case 5:
|
case 5:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
|
||||||
break;
|
break;
|
||||||
case 6:
|
case 6:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
|
blackboxPrintfHeaderLine("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle);
|
||||||
break;
|
break;
|
||||||
case 7:
|
case 7:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
|
blackboxPrintfHeaderLine("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
|
||||||
break;
|
break;
|
||||||
case 8:
|
case 8:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H gyro.scale:0x%x\n", castFloatBytesToInt(gyro.scale));
|
blackboxPrintfHeaderLine("acc_1G:%u", acc_1G);
|
||||||
break;
|
break;
|
||||||
case 9:
|
case 9:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H acc_1G:%u\n", acc_1G);
|
|
||||||
break;
|
|
||||||
case 10:
|
|
||||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
|
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 {
|
} else {
|
||||||
xmitState.headerIndex += 2; // Skip the next two vbat fields too
|
xmitState.headerIndex += 2; // Skip the next two vbat fields too
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 11:
|
case 10:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage,
|
blackboxPrintfHeaderLine("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage,
|
||||||
masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
|
masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
|
||||||
break;
|
break;
|
||||||
case 12:
|
case 11:
|
||||||
xmitState.u.serialBudget -= blackboxPrintf("H vbatref:%u\n", vbatReference);
|
blackboxPrintfHeaderLine("vbatref:%u", vbatReference);
|
||||||
break;
|
break;
|
||||||
case 13:
|
case 12:
|
||||||
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
|
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
|
||||||
if (feature(FEATURE_CURRENT_METER)) {
|
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;
|
break;
|
||||||
default:
|
default:
|
||||||
|
@ -1262,21 +1283,28 @@ void handleBlackbox(void)
|
||||||
{
|
{
|
||||||
int i;
|
int i;
|
||||||
|
|
||||||
|
if (blackboxState >= BLACKBOX_FIRST_HEADER_SENDING_STATE && blackboxState <= BLACKBOX_LAST_HEADER_SENDING_STATE) {
|
||||||
|
blackboxReplenishHeaderBudget();
|
||||||
|
}
|
||||||
|
|
||||||
switch (blackboxState) {
|
switch (blackboxState) {
|
||||||
case BLACKBOX_STATE_SEND_HEADER:
|
case BLACKBOX_STATE_SEND_HEADER:
|
||||||
//On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
|
//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
|
* Once the UART has had time to init, transmit the header in chunks so we don't overflow its transmit
|
||||||
* buffer.
|
* buffer, overflow the OpenLog's buffer, or keep the main loop busy for too long.
|
||||||
*/
|
*/
|
||||||
if (millis() > xmitState.u.startTime + 100) {
|
if (millis() > xmitState.u.startTime + 100) {
|
||||||
for (i = 0; i < blackboxWriteChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
|
if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION) == BLACKBOX_RESERVE_SUCCESS) {
|
||||||
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
|
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') {
|
if (blackboxHeader[xmitState.headerIndex] == '\0') {
|
||||||
blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
|
blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -64,13 +64,15 @@
|
||||||
|
|
||||||
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
|
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX
|
||||||
|
|
||||||
// How many bytes should we transmit per loop iteration?
|
// How many bytes can we transmit per loop iteration when writing headers?
|
||||||
uint8_t blackboxWriteChunkSize = 16;
|
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 serialPort_t *blackboxPort = NULL;
|
||||||
static portSharing_e blackboxPortSharing;
|
static portSharing_e blackboxPortSharing;
|
||||||
|
|
||||||
|
|
||||||
void blackboxWrite(uint8_t value)
|
void blackboxWrite(uint8_t value)
|
||||||
{
|
{
|
||||||
switch (masterConfig.blackbox_device) {
|
switch (masterConfig.blackbox_device) {
|
||||||
|
@ -92,17 +94,49 @@ static void _putc(void *p, char c)
|
||||||
blackboxWrite(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!)
|
//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, ...)
|
int blackboxPrintf(const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list va;
|
va_list va;
|
||||||
|
|
||||||
va_start(va, fmt);
|
va_start(va, fmt);
|
||||||
int written = tfp_format(NULL, _putc, fmt, va);
|
|
||||||
|
int written = blackboxPrintfv(fmt, va);
|
||||||
|
|
||||||
va_end(va);
|
va_end(va);
|
||||||
|
|
||||||
return written;
|
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 blackboxPrint(const char *s)
|
||||||
{
|
{
|
||||||
int length;
|
int length;
|
||||||
|
@ -463,15 +497,6 @@ bool blackboxDeviceFlush(void)
|
||||||
*/
|
*/
|
||||||
bool blackboxDeviceOpen(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) {
|
switch (masterConfig.blackbox_device) {
|
||||||
case BLACKBOX_DEVICE_SERIAL:
|
case BLACKBOX_DEVICE_SERIAL:
|
||||||
{
|
{
|
||||||
|
@ -499,6 +524,18 @@ bool blackboxDeviceOpen(void)
|
||||||
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex],
|
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex],
|
||||||
BLACKBOX_SERIAL_PORT_MODE, portOptions);
|
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;
|
return blackboxPort != NULL;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -508,6 +545,8 @@ bool blackboxDeviceOpen(void)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
blackboxMaxHeaderBytesPerIteration = BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -558,4 +597,88 @@ 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. Note that the USB VCP implementation doesn't use a buffer and has txBufferSize set to zero.
|
||||||
|
*/
|
||||||
|
if (blackboxPort->txBufferSize && 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
|
#endif
|
||||||
|
|
|
@ -32,11 +32,30 @@ typedef enum BlackboxDevice {
|
||||||
BLACKBOX_DEVICE_END
|
BLACKBOX_DEVICE_END
|
||||||
} BlackboxDevice;
|
} 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);
|
void blackboxWrite(uint8_t value);
|
||||||
|
|
||||||
int blackboxPrintf(const char *fmt, ...);
|
int blackboxPrintf(const char *fmt, ...);
|
||||||
|
void blackboxPrintfHeaderLine(const char *fmt, ...);
|
||||||
int blackboxPrint(const char *s);
|
int blackboxPrint(const char *s);
|
||||||
|
|
||||||
void blackboxWriteUnsignedVB(uint32_t value);
|
void blackboxWriteUnsignedVB(uint32_t value);
|
||||||
|
@ -55,3 +74,6 @@ bool blackboxDeviceOpen(void);
|
||||||
void blackboxDeviceClose(void);
|
void blackboxDeviceClose(void);
|
||||||
|
|
||||||
bool isBlackboxDeviceFull(void);
|
bool isBlackboxDeviceFull(void);
|
||||||
|
|
||||||
|
void blackboxReplenishHeaderBudget();
|
||||||
|
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes);
|
||||||
|
|
|
@ -40,9 +40,14 @@ void serialWrite(serialPort_t *instance, uint8_t ch)
|
||||||
instance->vTable->serialWrite(instance, ch);
|
instance->vTable->serialWrite(instance, ch);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t serialTotalBytesWaiting(serialPort_t *instance)
|
uint8_t serialRxBytesWaiting(serialPort_t *instance)
|
||||||
{
|
{
|
||||||
return instance->vTable->serialTotalBytesWaiting(instance);
|
return instance->vTable->serialTotalRxWaiting(instance);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t serialTxBytesFree(serialPort_t *instance)
|
||||||
|
{
|
||||||
|
return instance->vTable->serialTotalTxFree(instance);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t serialRead(serialPort_t *instance)
|
uint8_t serialRead(serialPort_t *instance)
|
||||||
|
|
|
@ -62,7 +62,8 @@ typedef struct serialPort_s {
|
||||||
struct serialPortVTable {
|
struct serialPortVTable {
|
||||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||||
|
|
||||||
uint8_t (*serialTotalBytesWaiting)(serialPort_t *instance);
|
uint8_t (*serialTotalRxWaiting)(serialPort_t *instance);
|
||||||
|
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
|
||||||
|
|
||||||
uint8_t (*serialRead)(serialPort_t *instance);
|
uint8_t (*serialRead)(serialPort_t *instance);
|
||||||
|
|
||||||
|
@ -75,7 +76,8 @@ struct serialPortVTable {
|
||||||
};
|
};
|
||||||
|
|
||||||
void serialWrite(serialPort_t *instance, uint8_t ch);
|
void serialWrite(serialPort_t *instance, uint8_t ch);
|
||||||
uint8_t serialTotalBytesWaiting(serialPort_t *instance);
|
uint8_t serialRxBytesWaiting(serialPort_t *instance);
|
||||||
|
uint8_t serialTxBytesFree(serialPort_t *instance);
|
||||||
uint8_t serialRead(serialPort_t *instance);
|
uint8_t serialRead(serialPort_t *instance);
|
||||||
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
|
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate);
|
||||||
void serialSetMode(serialPort_t *instance, portMode_t mode);
|
void serialSetMode(serialPort_t *instance, portMode_t mode);
|
||||||
|
|
|
@ -403,7 +403,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
|
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
|
||||||
{
|
{
|
||||||
if ((instance->mode & MODE_RX) == 0) {
|
if ((instance->mode & MODE_RX) == 0) {
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -414,6 +414,19 @@ uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
|
||||||
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
|
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint8_t softSerialTxBytesFree(serialPort_t *instance)
|
||||||
|
{
|
||||||
|
if ((instance->mode & MODE_TX) == 0) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
softSerial_t *s = (softSerial_t *)instance;
|
||||||
|
|
||||||
|
uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
|
||||||
|
|
||||||
|
return (s->port.txBufferSize - 1) - bytesUsed;
|
||||||
|
}
|
||||||
|
|
||||||
uint8_t softSerialReadByte(serialPort_t *instance)
|
uint8_t softSerialReadByte(serialPort_t *instance)
|
||||||
{
|
{
|
||||||
uint8_t ch;
|
uint8_t ch;
|
||||||
|
@ -422,7 +435,7 @@ uint8_t softSerialReadByte(serialPort_t *instance)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (softSerialTotalBytesWaiting(instance) == 0) {
|
if (softSerialRxBytesWaiting(instance) == 0) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -460,7 +473,8 @@ bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance)
|
||||||
const struct serialPortVTable softSerialVTable[] = {
|
const struct serialPortVTable softSerialVTable[] = {
|
||||||
{
|
{
|
||||||
softSerialWriteByte,
|
softSerialWriteByte,
|
||||||
softSerialTotalBytesWaiting,
|
softSerialRxBytesWaiting,
|
||||||
|
softSerialTxBytesFree,
|
||||||
softSerialReadByte,
|
softSerialReadByte,
|
||||||
softSerialSetBaudRate,
|
softSerialSetBaudRate,
|
||||||
isSoftSerialTransmitBufferEmpty,
|
isSoftSerialTransmitBufferEmpty,
|
||||||
|
|
|
@ -28,7 +28,8 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
||||||
|
|
||||||
// serialPort API
|
// serialPort API
|
||||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||||
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance);
|
uint8_t softSerialRxBytesWaiting(serialPort_t *instance);
|
||||||
|
uint8_t softSerialTxBytesFree(serialPort_t *instance);
|
||||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||||
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);
|
bool isSoftSerialTransmitBufferEmpty(serialPort_t *s);
|
||||||
|
|
|
@ -211,7 +211,7 @@ void uartStartTxDMA(uartPort_t *s)
|
||||||
DMA_Cmd(s->txDMAChannel, ENABLE);
|
DMA_Cmd(s->txDMAChannel, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance)
|
||||||
{
|
{
|
||||||
uartPort_t *s = (uartPort_t*)instance;
|
uartPort_t *s = (uartPort_t*)instance;
|
||||||
if (s->rxDMAChannel) {
|
if (s->rxDMAChannel) {
|
||||||
|
@ -230,6 +230,41 @@ uint8_t uartTotalBytesWaiting(serialPort_t *instance)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint8_t uartTotalTxBytesFree(serialPort_t *instance)
|
||||||
|
{
|
||||||
|
uartPort_t *s = (uartPort_t*)instance;
|
||||||
|
|
||||||
|
uint32_t bytesUsed;
|
||||||
|
|
||||||
|
if (s->port.txBufferHead >= s->port.txBufferTail) {
|
||||||
|
bytesUsed = s->port.txBufferHead - s->port.txBufferTail;
|
||||||
|
} else {
|
||||||
|
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s->txDMAChannel) {
|
||||||
|
/*
|
||||||
|
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
|
||||||
|
* the remaining size of that in-progress transfer here instead:
|
||||||
|
*/
|
||||||
|
bytesUsed += s->txDMAChannel->CNDTR;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
|
||||||
|
* space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
|
||||||
|
* than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
|
||||||
|
* transmitting a garbage mixture of old and new bytes).
|
||||||
|
*
|
||||||
|
* Be kind to callers and pretend like our buffer can only ever be 100% full.
|
||||||
|
*/
|
||||||
|
if (bytesUsed >= s->port.txBufferSize - 1) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return (s->port.txBufferSize - 1) - bytesUsed;
|
||||||
|
}
|
||||||
|
|
||||||
bool isUartTransmitBufferEmpty(serialPort_t *instance)
|
bool isUartTransmitBufferEmpty(serialPort_t *instance)
|
||||||
{
|
{
|
||||||
uartPort_t *s = (uartPort_t *)instance;
|
uartPort_t *s = (uartPort_t *)instance;
|
||||||
|
@ -281,7 +316,8 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
|
||||||
const struct serialPortVTable uartVTable[] = {
|
const struct serialPortVTable uartVTable[] = {
|
||||||
{
|
{
|
||||||
uartWrite,
|
uartWrite,
|
||||||
uartTotalBytesWaiting,
|
uartTotalRxBytesWaiting,
|
||||||
|
uartTotalTxBytesFree,
|
||||||
uartRead,
|
uartRead,
|
||||||
uartSetBaudRate,
|
uartSetBaudRate,
|
||||||
isUartTransmitBufferEmpty,
|
isUartTransmitBufferEmpty,
|
||||||
|
|
|
@ -19,6 +19,10 @@
|
||||||
|
|
||||||
// Since serial ports can be used for any function these buffer sizes should be equal
|
// Since serial ports can be used for any function these buffer sizes should be equal
|
||||||
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
|
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
|
||||||
|
|
||||||
|
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
|
||||||
|
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
|
||||||
|
// increase size further.
|
||||||
#define UART1_RX_BUFFER_SIZE 256
|
#define UART1_RX_BUFFER_SIZE 256
|
||||||
#define UART1_TX_BUFFER_SIZE 256
|
#define UART1_TX_BUFFER_SIZE 256
|
||||||
#define UART2_RX_BUFFER_SIZE 256
|
#define UART2_RX_BUFFER_SIZE 256
|
||||||
|
@ -48,7 +52,8 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
||||||
|
|
||||||
// serialPort API
|
// serialPort API
|
||||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||||
uint8_t uartTotalBytesWaiting(serialPort_t *instance);
|
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance);
|
||||||
|
uint8_t uartTotalTxBytesFree(serialPort_t *instance);
|
||||||
uint8_t uartRead(serialPort_t *instance);
|
uint8_t uartRead(serialPort_t *instance);
|
||||||
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||||
bool isUartTransmitBufferEmpty(serialPort_t *s);
|
bool isUartTransmitBufferEmpty(serialPort_t *s);
|
||||||
|
|
|
@ -99,7 +99,12 @@ void usbVcpWrite(serialPort_t *instance, uint8_t c)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
const struct serialPortVTable usbVTable[] = { { usbVcpWrite, usbVcpAvailable, usbVcpRead, usbVcpSetBaudRate, isUsbVcpTransmitBufferEmpty, usbVcpSetMode } };
|
uint8_t usbTxBytesFree() {
|
||||||
|
// Because we block upon transmit and don't buffer bytes, our "buffer" capacity is effectively unlimited.
|
||||||
|
return 255;
|
||||||
|
}
|
||||||
|
|
||||||
|
const struct serialPortVTable usbVTable[] = { { usbVcpWrite, usbVcpAvailable, usbTxBytesFree, usbVcpRead, usbVcpSetBaudRate, isUsbVcpTransmitBufferEmpty, usbVcpSetMode } };
|
||||||
|
|
||||||
serialPort_t *usbVcpOpen(void)
|
serialPort_t *usbVcpOpen(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -114,11 +114,6 @@ uint32_t flashfsGetSize()
|
||||||
return m25p16_getGeometry()->totalSize;
|
return m25p16_getGeometry()->totalSize;
|
||||||
}
|
}
|
||||||
|
|
||||||
const flashGeometry_t* flashfsGetGeometry()
|
|
||||||
{
|
|
||||||
return m25p16_getGeometry();
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint32_t flashfsTransmitBufferUsed()
|
static uint32_t flashfsTransmitBufferUsed()
|
||||||
{
|
{
|
||||||
if (bufferHead >= bufferTail)
|
if (bufferHead >= bufferTail)
|
||||||
|
@ -127,6 +122,27 @@ static uint32_t flashfsTransmitBufferUsed()
|
||||||
return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead;
|
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
|
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
|
||||||
* each write.
|
* each write.
|
||||||
|
|
|
@ -32,6 +32,8 @@ void flashfsEraseRange(uint32_t start, uint32_t end);
|
||||||
|
|
||||||
uint32_t flashfsGetSize();
|
uint32_t flashfsGetSize();
|
||||||
uint32_t flashfsGetOffset();
|
uint32_t flashfsGetOffset();
|
||||||
|
uint32_t flashfsGetWriteBufferFreeSpace();
|
||||||
|
uint32_t flashfsGetWriteBufferSize();
|
||||||
int flashfsIdentifyStartOfFreeSpace();
|
int flashfsIdentifyStartOfFreeSpace();
|
||||||
const flashGeometry_t* flashfsGetGeometry();
|
const flashGeometry_t* flashfsGetGeometry();
|
||||||
|
|
||||||
|
|
|
@ -360,7 +360,7 @@ void gpsThread(void)
|
||||||
{
|
{
|
||||||
// read out available GPS bytes
|
// read out available GPS bytes
|
||||||
if (gpsPort) {
|
if (gpsPort) {
|
||||||
while (serialTotalBytesWaiting(gpsPort))
|
while (serialRxBytesWaiting(gpsPort))
|
||||||
gpsNewData(serialRead(gpsPort));
|
gpsNewData(serialRead(gpsPort));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1036,14 +1036,14 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
|
||||||
#endif
|
#endif
|
||||||
char c;
|
char c;
|
||||||
while(1) {
|
while(1) {
|
||||||
if (serialTotalBytesWaiting(gpsPort)) {
|
if (serialRxBytesWaiting(gpsPort)) {
|
||||||
LED0_ON;
|
LED0_ON;
|
||||||
c = serialRead(gpsPort);
|
c = serialRead(gpsPort);
|
||||||
gpsNewData(c);
|
gpsNewData(c);
|
||||||
serialWrite(gpsPassthroughPort, c);
|
serialWrite(gpsPassthroughPort, c);
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
}
|
}
|
||||||
if (serialTotalBytesWaiting(gpsPassthroughPort)) {
|
if (serialRxBytesWaiting(gpsPassthroughPort)) {
|
||||||
LED1_ON;
|
LED1_ON;
|
||||||
serialWrite(gpsPort, serialRead(gpsPassthroughPort));
|
serialWrite(gpsPort, serialRead(gpsPassthroughPort));
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
|
|
|
@ -2155,7 +2155,7 @@ void cliProcess(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
while (serialTotalBytesWaiting(cliPort)) {
|
while (serialRxBytesWaiting(cliPort)) {
|
||||||
uint8_t c = serialRead(cliPort);
|
uint8_t c = serialRead(cliPort);
|
||||||
if (c == '\t' || c == '?') {
|
if (c == '\t' || c == '?') {
|
||||||
// do tab completion
|
// do tab completion
|
||||||
|
|
|
@ -1807,7 +1807,7 @@ void mspProcess(void)
|
||||||
|
|
||||||
setCurrentPort(candidatePort);
|
setCurrentPort(candidatePort);
|
||||||
|
|
||||||
while (serialTotalBytesWaiting(mspSerialPort)) {
|
while (serialRxBytesWaiting(mspSerialPort)) {
|
||||||
|
|
||||||
uint8_t c = serialRead(mspSerialPort);
|
uint8_t c = serialRead(mspSerialPort);
|
||||||
bool consumed = mspProcessReceivedData(c);
|
bool consumed = mspProcessReceivedData(c);
|
||||||
|
|
|
@ -514,7 +514,7 @@ void init(void)
|
||||||
void processLoopback(void) {
|
void processLoopback(void) {
|
||||||
if (loopbackPort) {
|
if (loopbackPort) {
|
||||||
uint8_t bytesWaiting;
|
uint8_t bytesWaiting;
|
||||||
while ((bytesWaiting = serialTotalBytesWaiting(loopbackPort))) {
|
while ((bytesWaiting = serialRxBytesWaiting(loopbackPort))) {
|
||||||
uint8_t b = serialRead(loopbackPort);
|
uint8_t b = serialRead(loopbackPort);
|
||||||
serialWrite(loopbackPort, b);
|
serialWrite(loopbackPort, b);
|
||||||
};
|
};
|
||||||
|
|
|
@ -374,7 +374,7 @@ static void processBinaryModeRequest(uint8_t address) {
|
||||||
|
|
||||||
static void flushHottRxBuffer(void)
|
static void flushHottRxBuffer(void)
|
||||||
{
|
{
|
||||||
while (serialTotalBytesWaiting(hottPort) > 0) {
|
while (serialRxBytesWaiting(hottPort) > 0) {
|
||||||
serialRead(hottPort);
|
serialRead(hottPort);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -383,7 +383,7 @@ static void hottCheckSerialData(uint32_t currentMicros)
|
||||||
{
|
{
|
||||||
static bool lookingForRequest = true;
|
static bool lookingForRequest = true;
|
||||||
|
|
||||||
uint8_t bytesWaiting = serialTotalBytesWaiting(hottPort);
|
uint8_t bytesWaiting = serialRxBytesWaiting(hottPort);
|
||||||
|
|
||||||
if (bytesWaiting <= 1) {
|
if (bytesWaiting <= 1) {
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -160,7 +160,7 @@ static void smartPortDataReceive(uint16_t c)
|
||||||
static uint8_t lastChar;
|
static uint8_t lastChar;
|
||||||
if (lastChar == FSSP_START_STOP) {
|
if (lastChar == FSSP_START_STOP) {
|
||||||
smartPortState = SPSTATE_WORKING;
|
smartPortState = SPSTATE_WORKING;
|
||||||
if (c == FSSP_SENSOR_ID1 && (serialTotalBytesWaiting(smartPortSerialPort) == 0)) {
|
if (c == FSSP_SENSOR_ID1 && (serialRxBytesWaiting(smartPortSerialPort) == 0)) {
|
||||||
smartPortLastRequestTime = now;
|
smartPortLastRequestTime = now;
|
||||||
smartPortHasRequest = 1;
|
smartPortHasRequest = 1;
|
||||||
// we only responde to these IDs
|
// we only responde to these IDs
|
||||||
|
@ -282,7 +282,7 @@ void handleSmartPortTelemetry(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
while (serialTotalBytesWaiting(smartPortSerialPort) > 0) {
|
while (serialRxBytesWaiting(smartPortSerialPort) > 0) {
|
||||||
uint8_t c = serialRead(smartPortSerialPort);
|
uint8_t c = serialRead(smartPortSerialPort);
|
||||||
smartPortDataReceive(c);
|
smartPortDataReceive(c);
|
||||||
}
|
}
|
||||||
|
|
|
@ -177,7 +177,12 @@ uint32_t millis(void) {
|
||||||
|
|
||||||
uint32_t micros(void) { return 0; }
|
uint32_t micros(void) { return 0; }
|
||||||
|
|
||||||
uint8_t serialTotalBytesWaiting(serialPort_t *instance) {
|
uint8_t serialRxBytesWaiting(serialPort_t *instance) {
|
||||||
|
UNUSED(instance);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t serialTxBytesFree(serialPort_t *instance) {
|
||||||
UNUSED(instance);
|
UNUSED(instance);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue