Added blackbox erase for flashchips
revert back initBlackbox Fixed blackbox erase when full. Change BOXBLACKBOXERASE to the end Blackbox erase changes Moved the ARM detect into the blackbox statemachine Added blackbox erase start and end beep Tab to space
This commit is contained in:
parent
51b19855dd
commit
22d11e35b2
|
@ -241,21 +241,21 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
|
|||
|
||||
typedef enum BlackboxState {
|
||||
BLACKBOX_STATE_DISABLED = 0,
|
||||
BLACKBOX_STATE_STOPPED,
|
||||
BLACKBOX_STATE_PREPARE_LOG_FILE,
|
||||
BLACKBOX_STATE_SEND_HEADER,
|
||||
BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
|
||||
BLACKBOX_STATE_SEND_GPS_H_HEADER,
|
||||
BLACKBOX_STATE_SEND_GPS_G_HEADER,
|
||||
BLACKBOX_STATE_SEND_SLOW_HEADER,
|
||||
BLACKBOX_STATE_SEND_SYSINFO,
|
||||
BLACKBOX_STATE_PAUSED,
|
||||
BLACKBOX_STATE_RUNNING,
|
||||
BLACKBOX_STATE_SHUTTING_DOWN
|
||||
BLACKBOX_STATE_STOPPED, //1
|
||||
BLACKBOX_STATE_PREPARE_LOG_FILE, //2
|
||||
BLACKBOX_STATE_SEND_HEADER, //3
|
||||
BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER, //4
|
||||
BLACKBOX_STATE_SEND_GPS_H_HEADER, //5
|
||||
BLACKBOX_STATE_SEND_GPS_G_HEADER, //6
|
||||
BLACKBOX_STATE_SEND_SLOW_HEADER, //7
|
||||
BLACKBOX_STATE_SEND_SYSINFO, //8
|
||||
BLACKBOX_STATE_PAUSED, //9
|
||||
BLACKBOX_STATE_RUNNING, //10
|
||||
BLACKBOX_STATE_SHUTTING_DOWN, //11
|
||||
BLACKBOX_STATE_START_ERASE, //12
|
||||
BLACKBOX_STATE_ERASING, //13
|
||||
} 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 {
|
||||
uint32_t time;
|
||||
|
@ -804,47 +804,44 @@ void validateBlackboxConfig()
|
|||
*/
|
||||
void startBlackbox(void)
|
||||
{
|
||||
if (blackboxState == BLACKBOX_STATE_STOPPED) {
|
||||
validateBlackboxConfig();
|
||||
validateBlackboxConfig();
|
||||
|
||||
if (!blackboxDeviceOpen()) {
|
||||
blackboxSetState(BLACKBOX_STATE_DISABLED);
|
||||
return;
|
||||
}
|
||||
|
||||
memset(&gpsHistory, 0, sizeof(gpsHistory));
|
||||
|
||||
blackboxHistory[0] = &blackboxHistoryRing[0];
|
||||
blackboxHistory[1] = &blackboxHistoryRing[1];
|
||||
blackboxHistory[2] = &blackboxHistoryRing[2];
|
||||
|
||||
vbatReference = vbatLatest;
|
||||
|
||||
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
|
||||
|
||||
/*
|
||||
* We use conditional tests to decide whether or not certain fields should be logged. Since our headers
|
||||
* must always agree with the logged data, the results of these tests must not change during logging. So
|
||||
* cache those now.
|
||||
*/
|
||||
blackboxBuildConditionCache();
|
||||
|
||||
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(modeActivationConditions(0), BOXBLACKBOX);
|
||||
|
||||
blackboxIteration = 0;
|
||||
blackboxPFrameIndex = 0;
|
||||
blackboxIFrameIndex = 0;
|
||||
|
||||
/*
|
||||
* Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
|
||||
* it finally plays the beep for this arming event.
|
||||
*/
|
||||
blackboxLastArmingBeep = getArmingBeepTimeMicros();
|
||||
blackboxLastFlightModeFlags = rcModeActivationMask; // record startup status
|
||||
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
|
||||
if (!blackboxDeviceOpen()) {
|
||||
blackboxSetState(BLACKBOX_STATE_DISABLED);
|
||||
return;
|
||||
}
|
||||
|
||||
memset(&gpsHistory, 0, sizeof(gpsHistory));
|
||||
|
||||
blackboxHistory[0] = &blackboxHistoryRing[0];
|
||||
blackboxHistory[1] = &blackboxHistoryRing[1];
|
||||
blackboxHistory[2] = &blackboxHistoryRing[2];
|
||||
|
||||
vbatReference = vbatLatest;
|
||||
|
||||
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
|
||||
|
||||
/*
|
||||
* We use conditional tests to decide whether or not certain fields should be logged. Since our headers
|
||||
* must always agree with the logged data, the results of these tests must not change during logging. So
|
||||
* cache those now.
|
||||
*/
|
||||
blackboxBuildConditionCache();
|
||||
|
||||
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(modeActivationConditions(0), BOXBLACKBOX);
|
||||
|
||||
blackboxIteration = 0;
|
||||
blackboxPFrameIndex = 0;
|
||||
blackboxIFrameIndex = 0;
|
||||
|
||||
/*
|
||||
* Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
|
||||
* it finally plays the beep for this arming event.
|
||||
*/
|
||||
blackboxLastArmingBeep = getArmingBeepTimeMicros();
|
||||
blackboxLastFlightModeFlags = rcModeActivationMask; // record startup status
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -1469,18 +1466,26 @@ static void blackboxLogIteration(timeUs_t currentTimeUs)
|
|||
void handleBlackbox(timeUs_t currentTimeUs)
|
||||
{
|
||||
int i;
|
||||
|
||||
if (blackboxState >= BLACKBOX_FIRST_HEADER_SENDING_STATE && blackboxState <= BLACKBOX_LAST_HEADER_SENDING_STATE) {
|
||||
blackboxReplenishHeaderBudget();
|
||||
}
|
||||
static bool erasedOnce = false; //Only allow one erase per FC reboot.
|
||||
|
||||
switch (blackboxState) {
|
||||
case BLACKBOX_STATE_STOPPED:
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
blackboxOpen();
|
||||
startBlackbox();
|
||||
}
|
||||
if (IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE) && !erasedOnce) {
|
||||
blackboxSetState(BLACKBOX_STATE_START_ERASE);
|
||||
erasedOnce = true;
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_PREPARE_LOG_FILE:
|
||||
if (blackboxDeviceBeginLog()) {
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_HEADER:
|
||||
blackboxReplenishHeaderBudget();
|
||||
//On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
|
||||
|
||||
/*
|
||||
|
@ -1501,6 +1506,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER:
|
||||
blackboxReplenishHeaderBudget();
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAY_LENGTH(blackboxMainFields),
|
||||
&blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
|
||||
|
@ -1514,6 +1520,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
break;
|
||||
#ifdef GPS
|
||||
case BLACKBOX_STATE_SEND_GPS_H_HEADER:
|
||||
blackboxReplenishHeaderBudget();
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition('H', 0, blackboxGpsHFields, blackboxGpsHFields + 1, ARRAY_LENGTH(blackboxGpsHFields),
|
||||
NULL, NULL)) {
|
||||
|
@ -1521,6 +1528,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_GPS_G_HEADER:
|
||||
blackboxReplenishHeaderBudget();
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition('G', 0, blackboxGpsGFields, blackboxGpsGFields + 1, ARRAY_LENGTH(blackboxGpsGFields),
|
||||
&blackboxGpsGFields[0].condition, &blackboxGpsGFields[1].condition)) {
|
||||
|
@ -1529,6 +1537,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
break;
|
||||
#endif
|
||||
case BLACKBOX_STATE_SEND_SLOW_HEADER:
|
||||
blackboxReplenishHeaderBudget();
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition('S', 0, blackboxSlowFields, blackboxSlowFields + 1, ARRAY_LENGTH(blackboxSlowFields),
|
||||
NULL, NULL)) {
|
||||
|
@ -1536,6 +1545,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_SYSINFO:
|
||||
blackboxReplenishHeaderBudget();
|
||||
//On entry of this state, xmitState.headerIndex is 0
|
||||
|
||||
//Keep writing chunks of the system info headers until it returns true to signal completion
|
||||
|
@ -1565,7 +1575,6 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
|
||||
blackboxLogIteration(currentTimeUs);
|
||||
}
|
||||
|
||||
// Keep the logging timers ticking so our log iteration continues to advance
|
||||
blackboxAdvanceIterationTimers();
|
||||
break;
|
||||
|
@ -1577,7 +1586,6 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
} else {
|
||||
blackboxLogIteration(currentTimeUs);
|
||||
}
|
||||
|
||||
blackboxAdvanceIterationTimers();
|
||||
break;
|
||||
case BLACKBOX_STATE_SHUTTING_DOWN:
|
||||
|
@ -1594,15 +1602,29 @@ void handleBlackbox(timeUs_t currentTimeUs)
|
|||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_START_ERASE:
|
||||
blackboxEraseAll();
|
||||
blackboxSetState(BLACKBOX_STATE_ERASING);
|
||||
beeper(BEEPER_BLACKBOX_ERASE);
|
||||
break;
|
||||
case BLACKBOX_STATE_ERASING:
|
||||
if (isBlackboxErased()) {
|
||||
//Done eraseing
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
beeper(BEEPER_BLACKBOX_ERASE);
|
||||
}
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// Did we run out of room on the device? Stop!
|
||||
if (isBlackboxDeviceFull()) {
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
// ensure we reset the test mode flag if we stop due to full memory card
|
||||
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
|
||||
if (blackboxState != BLACKBOX_STATE_ERASING && blackboxState != BLACKBOX_STATE_START_ERASE) {
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
// ensure we reset the test mode flag if we stop due to full memory card
|
||||
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
|
||||
}
|
||||
} else { // Only log in test mode if there is room!
|
||||
|
||||
if(blackboxConfig()->on_motor_test) {
|
||||
|
|
|
@ -66,6 +66,14 @@ static struct {
|
|||
|
||||
#endif
|
||||
|
||||
void blackboxOpen()
|
||||
{
|
||||
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
|
||||
if (sharedBlackboxAndMspPort) {
|
||||
mspSerialReleasePortIfAllocated(sharedBlackboxAndMspPort);
|
||||
}
|
||||
}
|
||||
|
||||
void blackboxWrite(uint8_t value)
|
||||
{
|
||||
switch (blackboxConfig()->device) {
|
||||
|
@ -602,6 +610,43 @@ bool blackboxDeviceOpen(void)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Erase all blackbox logs
|
||||
*/
|
||||
void blackboxEraseAll(void)
|
||||
{
|
||||
switch (blackboxConfig()->device) {
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
flashfsEraseCompletely();
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
//not supported
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check to see if erasing is done
|
||||
*/
|
||||
bool isBlackboxErased(void)
|
||||
{
|
||||
switch (blackboxConfig()->device) {
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
return flashfsIsReady();
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
//not supported
|
||||
return true;
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Close the Blackbox logging device immediately without attempting to flush any remaining data.
|
||||
*/
|
||||
|
|
|
@ -49,6 +49,7 @@ typedef enum {
|
|||
|
||||
extern int32_t blackboxHeaderBudget;
|
||||
|
||||
void blackboxOpen(void);
|
||||
void blackboxWrite(uint8_t value);
|
||||
|
||||
int blackboxPrintf(const char *fmt, ...);
|
||||
|
@ -71,6 +72,9 @@ bool blackboxDeviceFlushForce(void);
|
|||
bool blackboxDeviceOpen(void);
|
||||
void blackboxDeviceClose(void);
|
||||
|
||||
void blackboxEraseAll(void);
|
||||
bool isBlackboxErased(void);
|
||||
|
||||
bool blackboxDeviceBeginLog(void);
|
||||
bool blackboxDeviceEndLog(bool retainLog);
|
||||
|
||||
|
|
|
@ -46,6 +46,7 @@
|
|||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -63,6 +64,7 @@ static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
|||
delay(100);
|
||||
}
|
||||
|
||||
beeper(BEEPER_BLACKBOX_ERASE);
|
||||
displayClearScreen(pDisplay);
|
||||
displayResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
|
||||
|
||||
|
|
|
@ -2729,7 +2729,7 @@ static void cliFlashErase(char *cmdline)
|
|||
#endif
|
||||
delay(100);
|
||||
}
|
||||
|
||||
beeper(BEEPER_BLACKBOX_ERASE);
|
||||
cliPrintf("\r\nDone.\r\n");
|
||||
}
|
||||
|
||||
|
|
|
@ -188,15 +188,6 @@ void mwArm(void)
|
|||
ENABLE_ARMING_FLAG(WAS_EVER_ARMED);
|
||||
headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
|
||||
|
||||
#ifdef BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
|
||||
if (sharedBlackboxAndMspPort) {
|
||||
mspSerialReleasePortIfAllocated(sharedBlackboxAndMspPort);
|
||||
}
|
||||
startBlackbox();
|
||||
}
|
||||
#endif
|
||||
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
|
||||
//beep to indicate arming
|
||||
|
|
|
@ -150,6 +150,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ BOXAIRMODE, "AIR MODE;", 28 },
|
||||
{ BOX3DDISABLESWITCH, "DISABLE 3D SWITCH;", 29},
|
||||
{ BOXFPVANGLEMIX, "FPV ANGLE MIX;", 30},
|
||||
{ BOXBLACKBOXERASE, "BLACKBOX ERASE;", 31 },
|
||||
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
|
||||
};
|
||||
|
||||
|
@ -378,6 +379,7 @@ void initActiveBoxIds(void)
|
|||
#ifdef BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXBLACKBOX;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXBLACKBOXERASE;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -442,6 +444,7 @@ static uint32_t packFlightModeFlags(void)
|
|||
IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR |
|
||||
IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE)) << BOXBLACKBOXERASE |
|
||||
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)) << BOXAIRMODE |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX)) << BOXFPVANGLEMIX;
|
||||
|
|
|
@ -53,6 +53,7 @@ typedef enum {
|
|||
BOXAIRMODE,
|
||||
BOX3DDISABLESWITCH,
|
||||
BOXFPVANGLEMIX,
|
||||
BOXBLACKBOXERASE,
|
||||
CHECKBOX_ITEM_COUNT
|
||||
} boxId_e;
|
||||
|
||||
|
|
|
@ -171,9 +171,9 @@ typedef struct beeperTableEntry_s {
|
|||
{ BEEPER_ENTRY(BEEPER_ARMED, 15, beep_armedBeep, "ARMED") },
|
||||
{ BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 16, NULL, "SYSTEM_INIT") },
|
||||
{ BEEPER_ENTRY(BEEPER_USB, 17, NULL, "ON_USB") },
|
||||
|
||||
{ BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") },
|
||||
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERRED") },
|
||||
{ BEEPER_ENTRY(BEEPER_BLACKBOX_ERASE, 18, beep_2shortBeeps, "BLACKBOX_ERASE") },
|
||||
{ BEEPER_ENTRY(BEEPER_ALL, 19, NULL, "ALL") },
|
||||
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 20, NULL, "PREFERRED") },
|
||||
};
|
||||
|
||||
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||
|
|
|
@ -41,7 +41,7 @@ typedef enum {
|
|||
BEEPER_ARMED, // Warning beeps when board is armed (repeats until board is disarmed or throttle is increased)
|
||||
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
|
||||
BEEPER_USB, // Some boards have beeper powered USB connected
|
||||
|
||||
BEEPER_BLACKBOX_ERASE, // Beep when blackbox erase completes
|
||||
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||
BEEPER_PREFERENCE // Save preferred beeper configuration
|
||||
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
|
||||
|
|
Loading…
Reference in New Issue