1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-22 07:45:29 +03:00

Discard logged files when blackbox was paused for the entire flight

This commit is contained in:
Nicholas Sherlock 2015-11-19 21:44:43 +13:00 committed by borisbstyle
parent a35ccd28de
commit e572ccebad
4 changed files with 101 additions and 39 deletions

View file

@ -347,6 +347,7 @@ STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION
static uint32_t blackboxIteration;
static uint16_t blackboxPFrameIndex, blackboxIFrameIndex;
static uint16_t blackboxSlowFrameIterationTimer;
static bool blackboxLoggedAnyFrames;
/*
* We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
@ -460,6 +461,9 @@ static void blackboxSetState(BlackboxState newState)
{
//Perform initial setup required for the new state
switch (newState) {
case BLACKBOX_STATE_PREPARE_LOG_FILE:
blackboxLoggedAnyFrames = false;
break;
case BLACKBOX_STATE_SEND_HEADER:
blackboxHeaderBudget = 0;
xmitState.headerIndex = 0;
@ -578,6 +582,8 @@ static void writeIntraframe(void)
blackboxHistory[2] = blackboxHistory[0];
//And advance the current state over to a blank space ready to be filled
blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
blackboxLoggedAnyFrames = true;
}
static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHistory, int count)
@ -693,6 +699,8 @@ static void writeInterframe(void)
blackboxHistory[2] = blackboxHistory[1];
blackboxHistory[1] = blackboxHistory[0];
blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
blackboxLoggedAnyFrames = true;
}
/* Write the contents of the global "slowHistory" to the log as an "S" frame. Because this data is logged so
@ -855,18 +863,20 @@ void startBlackbox(void)
*/
void finishBlackbox(void)
{
if (blackboxState == BLACKBOX_STATE_RUNNING || blackboxState == BLACKBOX_STATE_PAUSED) {
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
switch (blackboxState) {
case BLACKBOX_STATE_DISABLED:
case BLACKBOX_STATE_STOPPED:
case BLACKBOX_STATE_SHUTTING_DOWN:
// We're already stopped/shutting down
break;
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
} else if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED
&& blackboxState != BLACKBOX_STATE_SHUTTING_DOWN) {
/*
* We're shutting down in the middle of transmitting headers, so we can't log a "log completed" event.
* Just give the port back and stop immediately.
*/
blackboxDeviceClose();
blackboxSetState(BLACKBOX_STATE_STOPPED);
case BLACKBOX_STATE_RUNNING:
case BLACKBOX_STATE_PAUSED:
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
// Fall through
default:
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
}
}
@ -1426,7 +1436,7 @@ void handleBlackbox(void)
*
* Don't wait longer than it could possibly take if something funky happens.
*/
if (blackboxDeviceEndLog() && (millis() > xmitState.u.startTime + BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS || blackboxDeviceFlush())) {
if (blackboxDeviceEndLog(blackboxLoggedAnyFrames) && (millis() > xmitState.u.startTime + BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS || blackboxDeviceFlush())) {
blackboxDeviceClose();
blackboxSetState(BLACKBOX_STATE_STOPPED);
}