1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Adding blackbox device setting and basic flashfs support for it

This commit is contained in:
Nicholas Sherlock 2015-01-28 22:14:49 +13:00
parent f9e22a0461
commit 5a57dda665
7 changed files with 110 additions and 40 deletions

View file

@ -605,6 +605,10 @@ static void validateBlackboxConfig()
masterConfig.blackbox_rate_num /= div; masterConfig.blackbox_rate_num /= div;
masterConfig.blackbox_rate_denom /= div; masterConfig.blackbox_rate_denom /= div;
} }
if (!(masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL || masterConfig.blackbox_device == BLACKBOX_DEVICE_FLASH)) {
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
}
} }
void startBlackbox(void) void startBlackbox(void)

View file

@ -55,6 +55,8 @@
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "io/flashfs.h"
#define BLACKBOX_BAUDRATE 115200 #define BLACKBOX_BAUDRATE 115200
#define BLACKBOX_INITIAL_PORT_MODE MODE_TX #define BLACKBOX_INITIAL_PORT_MODE MODE_TX
@ -67,7 +69,17 @@ static uint32_t previousBaudRate;
void blackboxWrite(uint8_t value) void blackboxWrite(uint8_t value)
{ {
switch (masterConfig.blackbox_device) {
#ifdef FLASHFS
case BLACKBOX_DEVICE_FLASH:
flashfsWriteByte(value);
break;
#endif
case BLACKBOX_DEVICE_SERIAL:
default:
serialWrite(blackboxPort, value); serialWrite(blackboxPort, value);
break;
}
} }
static void _putc(void *p, char c) static void _putc(void *p, char c)
@ -378,7 +390,16 @@ void blackboxWriteTag8_8SVB(int32_t *values, int valueCount)
*/ */
void blackboxDeviceFlush(void) void blackboxDeviceFlush(void)
{ {
//Presently a no-op on serial switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
//Presently a no-op on serial, as serial is continuously being drained out of its buffer
break;
#ifdef FLASHFS
case BLACKBOX_DEVICE_FLASH:
flashfsFlushSync();
break;
#endif
}
} }
/** /**
@ -386,6 +407,17 @@ void 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) {
case BLACKBOX_DEVICE_SERIAL:
blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX);
if (blackboxPort) { if (blackboxPort) {
previousPortMode = blackboxPort->mode; previousPortMode = blackboxPort->mode;
@ -403,20 +435,25 @@ 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);
return blackboxPort != NULL; return blackboxPort != NULL;
break;
#ifdef FLASHFS
case BLACKBOX_DEVICE_FLASH:
if (flashfsGetSize() == 0)
return false;
return true;
break;
#endif
default:
return false;
}
} }
void blackboxDeviceClose(void) void blackboxDeviceClose(void)
{ {
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
serialSetMode(blackboxPort, previousPortMode); serialSetMode(blackboxPort, previousPortMode);
serialSetBaudRate(blackboxPort, previousBaudRate); serialSetBaudRate(blackboxPort, previousBaudRate);
@ -429,9 +466,28 @@ void blackboxDeviceClose(void)
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) { if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
mspAllocateSerialPorts(&masterConfig.serialConfig); mspAllocateSerialPorts(&masterConfig.serialConfig);
} }
break;
#ifdef FLASHFS
case BLACKBOX_DEVICE_FLASH:
flashfsFlushSync();
break;
#endif
}
} }
bool isBlackboxDeviceIdle(void) bool isBlackboxDeviceIdle(void)
{ {
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
return isSerialTransmitBufferEmpty(blackboxPort); return isSerialTransmitBufferEmpty(blackboxPort);
#ifdef FLASHFS
case BLACKBOX_DEVICE_FLASH:
flashfsFlushSync();
return true;
#endif
default:
return false;
}
} }

View file

@ -20,6 +20,9 @@
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <stdbool.h>
#define BLACKBOX_DEVICE_SERIAL 0
#define BLACKBOX_DEVICE_FLASH 1
uint8_t blackboxWriteChunkSize; uint8_t blackboxWriteChunkSize;
void blackboxWrite(uint8_t value); void blackboxWrite(uint8_t value);

View file

@ -450,6 +450,7 @@ static void resetConf(void)
#endif #endif
#ifdef BLACKBOX #ifdef BLACKBOX
masterConfig.blackbox_device = 0;
masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1; masterConfig.blackbox_rate_denom = 1;
#endif #endif

View file

@ -85,6 +85,7 @@ typedef struct master_t {
uint8_t current_profile_index; uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT]; controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
uint8_t blackbox_device;
uint8_t blackbox_rate_num; uint8_t blackbox_rate_num;
uint8_t blackbox_rate_denom; uint8_t blackbox_rate_denom;

View file

@ -131,17 +131,14 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes,
{ {
const flashGeometry_t *geometry = m25p16_getGeometry(); const flashGeometry_t *geometry = m25p16_getGeometry();
uint32_t bytesTotalToWrite = 0; uint32_t bytesTotalRemaining = 0;
uint32_t bytesTotalRemaining;
int i; int i;
for (i = 0; i < bufferCount; i++) { for (i = 0; i < bufferCount; i++) {
bytesTotalToWrite += bufferSizes[i]; bytesTotalRemaining += bufferSizes[i];
} }
bytesTotalRemaining = bytesTotalToWrite;
while (bytesTotalRemaining > 0) { while (bytesTotalRemaining > 0) {
uint32_t bytesTotalThisIteration; uint32_t bytesTotalThisIteration;
uint32_t bytesRemainThisIteration; uint32_t bytesRemainThisIteration;
@ -188,7 +185,7 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes,
bytesTotalRemaining -= bytesTotalThisIteration; bytesTotalRemaining -= bytesTotalThisIteration;
// 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 + bytesTotalToWrite); flashfsSetTailAddress(tailAddress + bytesTotalThisIteration);
} }
} }
@ -219,6 +216,7 @@ static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t buffer
void flashfsFlushAsync() void flashfsFlushAsync()
{ {
if (bufferHead == bufferTail) { if (bufferHead == bufferTail) {
shouldFlush = false;
return; // Nothing to flush return; // Nothing to flush
} }
@ -230,6 +228,8 @@ void flashfsFlushAsync()
flashfsWriteBuffers(buffers, bufferSizes, 2); flashfsWriteBuffers(buffers, bufferSizes, 2);
flashfsClearBuffer(); flashfsClearBuffer();
shouldFlush = false;
} else { } else {
shouldFlush = true; shouldFlush = true;
} }
@ -243,8 +243,10 @@ void flashfsFlushAsync()
*/ */
void flashfsFlushSync() void flashfsFlushSync()
{ {
if (bufferHead == bufferTail) if (bufferHead == bufferTail) {
shouldFlush = false;
return; // Nothing to write return; // Nothing to write
}
m25p16_waitForReady(10); //TODO caller should customize timeout m25p16_waitForReady(10); //TODO caller should customize timeout
@ -273,7 +275,7 @@ void flashfsWriteByte(uint8_t byte)
bufferHead = 0; bufferHead = 0;
} }
if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { if (shouldFlush || flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) {
flashfsFlushAsync(); flashfsFlushAsync();
} }
} }
@ -281,7 +283,7 @@ 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 // Would writing this cause our buffer to reach the flush threshold? If so just write it now
if (len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN || shouldFlush) { 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];
@ -297,6 +299,8 @@ void flashfsWrite(const uint8_t *data, unsigned int len)
// And now our buffer is empty // And now our buffer is empty
flashfsClearBuffer(); flashfsClearBuffer();
return;
} }
// 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

View file

@ -422,6 +422,7 @@ const clivalue_t valueTable[] = {
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 }, { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 }, { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_device, 0, 1 },
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 }, { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 }, { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
}; };
@ -800,7 +801,7 @@ static void cliFlashRead(char *cmdline)
flashfsSeekAbs(address); flashfsSeekAbs(address);
while (length > 0) { while (length > 0) {
int bytesToRead = length < 32 ? length : 32; uint32_t bytesToRead = length < 32 ? length : 32;
flashfsRead(buffer, bytesToRead); flashfsRead(buffer, bytesToRead);