mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Add resume event to allow clean log decoding, add documentation
This commit is contained in:
parent
01632998a3
commit
53860e461c
5 changed files with 86 additions and 35 deletions
|
@ -230,6 +230,14 @@ After downloading the log, be sure to erase the chip to make it ready for reuse
|
||||||
If you try to start recording a new flight when the dataflash is already full, Blackbox logging will be disabled and
|
If you try to start recording a new flight when the dataflash is already full, Blackbox logging will be disabled and
|
||||||
nothing will be recorded.
|
nothing will be recorded.
|
||||||
|
|
||||||
|
### Usage - Logging switch
|
||||||
|
If you're recording to an onboard flash chip, you probably want to disable Blackbox recording when not required in order
|
||||||
|
to save storage space. To do this, you can add a Blackbox flight mode to one of your AUX channels on the Configurator's
|
||||||
|
modes tab. Once you've added a mode, Blackbox will only log flight data when the mode is active.
|
||||||
|
|
||||||
|
A log header will always be recorded at arming time, even if logging is paused. You can freely pause and resume logging
|
||||||
|
while in flight.
|
||||||
|
|
||||||
## Converting logs to CSV or PNG
|
## Converting logs to CSV or PNG
|
||||||
After your flights, you'll have a series of flight log files with a .TXT extension. You'll need to decode these with
|
After your flights, you'll have a series of flight log files with a .TXT extension. You'll need to decode these with
|
||||||
the `blackbox_decode` tool to create CSV (comma-separated values) files for analysis, or render them into a series of PNG
|
the `blackbox_decode` tool to create CSV (comma-separated values) files for analysis, or render them into a series of PNG
|
||||||
|
|
|
@ -256,6 +256,7 @@ typedef enum BlackboxState {
|
||||||
BLACKBOX_STATE_SEND_GPS_G_HEADER,
|
BLACKBOX_STATE_SEND_GPS_G_HEADER,
|
||||||
BLACKBOX_STATE_SEND_SLOW_HEADER,
|
BLACKBOX_STATE_SEND_SLOW_HEADER,
|
||||||
BLACKBOX_STATE_SEND_SYSINFO,
|
BLACKBOX_STATE_SEND_SYSINFO,
|
||||||
|
BLACKBOX_STATE_PAUSED,
|
||||||
BLACKBOX_STATE_RUNNING,
|
BLACKBOX_STATE_RUNNING,
|
||||||
BLACKBOX_STATE_SHUTTING_DOWN
|
BLACKBOX_STATE_SHUTTING_DOWN
|
||||||
} BlackboxState;
|
} BlackboxState;
|
||||||
|
@ -456,9 +457,6 @@ static void blackboxSetState(BlackboxState newState)
|
||||||
xmitState.headerIndex = 0;
|
xmitState.headerIndex = 0;
|
||||||
break;
|
break;
|
||||||
case BLACKBOX_STATE_RUNNING:
|
case BLACKBOX_STATE_RUNNING:
|
||||||
blackboxIteration = 0;
|
|
||||||
blackboxPFrameIndex = 0;
|
|
||||||
blackboxIFrameIndex = 0;
|
|
||||||
blackboxSlowFrameIterationTimer = SLOW_FRAME_INTERVAL; //Force a slow frame to be written on the first iteration
|
blackboxSlowFrameIterationTimer = SLOW_FRAME_INTERVAL; //Force a slow frame to be written on the first iteration
|
||||||
break;
|
break;
|
||||||
case BLACKBOX_STATE_SHUTTING_DOWN:
|
case BLACKBOX_STATE_SHUTTING_DOWN:
|
||||||
|
@ -773,7 +771,6 @@ static void validateBlackboxConfig()
|
||||||
*/
|
*/
|
||||||
void startBlackbox(void)
|
void startBlackbox(void)
|
||||||
{
|
{
|
||||||
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(currentProfile->modeActivationConditions, BOXBLACKBOX);
|
|
||||||
if (blackboxState == BLACKBOX_STATE_STOPPED) {
|
if (blackboxState == BLACKBOX_STATE_STOPPED) {
|
||||||
validateBlackboxConfig();
|
validateBlackboxConfig();
|
||||||
|
|
||||||
|
@ -799,6 +796,12 @@ void startBlackbox(void)
|
||||||
*/
|
*/
|
||||||
blackboxBuildConditionCache();
|
blackboxBuildConditionCache();
|
||||||
|
|
||||||
|
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(currentProfile->modeActivationConditions, 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
|
* 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.
|
* it finally plays the beep for this arming event.
|
||||||
|
@ -814,7 +817,7 @@ void startBlackbox(void)
|
||||||
*/
|
*/
|
||||||
void finishBlackbox(void)
|
void finishBlackbox(void)
|
||||||
{
|
{
|
||||||
if (blackboxState == BLACKBOX_STATE_RUNNING) {
|
if (blackboxState == BLACKBOX_STATE_RUNNING || blackboxState == BLACKBOX_STATE_PAUSED) {
|
||||||
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
|
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
|
||||||
|
|
||||||
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
|
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
|
||||||
|
@ -1102,7 +1105,8 @@ static bool blackboxWriteSysinfo()
|
||||||
*/
|
*/
|
||||||
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
||||||
{
|
{
|
||||||
if (blackboxState != BLACKBOX_STATE_RUNNING) {
|
// Only allow events to be logged after headers have been written
|
||||||
|
if (!(blackboxState == BLACKBOX_STATE_RUNNING || blackboxState == BLACKBOX_STATE_PAUSED)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1144,6 +1148,10 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
||||||
blackboxWriteSignedVB(data->inflightAdjustment.newValue);
|
blackboxWriteSignedVB(data->inflightAdjustment.newValue);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case FLIGHT_LOG_EVENT_LOGGING_RESUME:
|
||||||
|
blackboxWriteUnsignedVB(data->loggingResume.logIteration);
|
||||||
|
blackboxWriteUnsignedVB(data->loggingResume.currentTime);
|
||||||
|
break;
|
||||||
case FLIGHT_LOG_EVENT_LOG_END:
|
case FLIGHT_LOG_EVENT_LOG_END:
|
||||||
blackboxPrint("End of log");
|
blackboxPrint("End of log");
|
||||||
blackboxWrite(0);
|
blackboxWrite(0);
|
||||||
|
@ -1178,34 +1186,51 @@ static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
|
||||||
return (pFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num;
|
return (pFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool blackboxShouldLogIFrame() {
|
||||||
|
return blackboxPFrameIndex == 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Called once every FC loop in order to keep track of how many FC loop iterations have passed
|
||||||
|
static void blackboxAdvanceIterationTimers()
|
||||||
|
{
|
||||||
|
blackboxSlowFrameIterationTimer++;
|
||||||
|
blackboxIteration++;
|
||||||
|
blackboxPFrameIndex++;
|
||||||
|
|
||||||
|
if (blackboxPFrameIndex == BLACKBOX_I_INTERVAL) {
|
||||||
|
blackboxPFrameIndex = 0;
|
||||||
|
blackboxIFrameIndex++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Called once every FC loop in order to log the current state
|
// Called once every FC loop in order to log the current state
|
||||||
static void blackboxLogIteration(bool writeFrames)
|
static void blackboxLogIteration()
|
||||||
{
|
{
|
||||||
// Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
|
// Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
|
||||||
if (blackboxPFrameIndex == 0) {
|
if (blackboxShouldLogIFrame()) {
|
||||||
/*
|
/*
|
||||||
* Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
|
* Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
|
||||||
* an additional item to write at the same time)
|
* an additional item to write at the same time)
|
||||||
*/
|
*/
|
||||||
if (writeFrames) {
|
writeSlowFrameIfNeeded(false);
|
||||||
writeSlowFrameIfNeeded(false);
|
|
||||||
loadMainState();
|
loadMainState();
|
||||||
writeIntraframe();
|
writeIntraframe();
|
||||||
}
|
|
||||||
} else {
|
} else {
|
||||||
blackboxCheckAndLogArmingBeep();
|
blackboxCheckAndLogArmingBeep();
|
||||||
|
|
||||||
if (blackboxShouldLogPFrame(blackboxPFrameIndex) && writeFrames) {
|
if (blackboxShouldLogPFrame(blackboxPFrameIndex)) {
|
||||||
/*
|
/*
|
||||||
* We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
|
* We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
|
||||||
* So only log slow frames during loop iterations where we log a main frame.
|
* So only log slow frames during loop iterations where we log a main frame.
|
||||||
*/
|
*/
|
||||||
writeSlowFrameIfNeeded(true);
|
writeSlowFrameIfNeeded(true);
|
||||||
|
|
||||||
loadMainState();
|
loadMainState();
|
||||||
writeInterframe();
|
writeInterframe();
|
||||||
}
|
}
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
if (feature(FEATURE_GPS) && writeFrames) {
|
if (feature(FEATURE_GPS)) {
|
||||||
/*
|
/*
|
||||||
* If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
|
* If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
|
||||||
* GPS home position.
|
* GPS home position.
|
||||||
|
@ -1229,15 +1254,6 @@ static void blackboxLogIteration(bool writeFrames)
|
||||||
|
|
||||||
//Flush every iteration so that our runtime variance is minimized
|
//Flush every iteration so that our runtime variance is minimized
|
||||||
blackboxDeviceFlush();
|
blackboxDeviceFlush();
|
||||||
|
|
||||||
blackboxSlowFrameIterationTimer++;
|
|
||||||
blackboxIteration++;
|
|
||||||
blackboxPFrameIndex++;
|
|
||||||
|
|
||||||
if (blackboxPFrameIndex == BLACKBOX_I_INTERVAL) {
|
|
||||||
blackboxPFrameIndex = 0;
|
|
||||||
blackboxIFrameIndex++;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1308,18 +1324,33 @@ void handleBlackbox(void)
|
||||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case BLACKBOX_STATE_PAUSED:
|
||||||
|
// Only allow resume to occur during an I-frame iteration, so that we have an "I" base to work from
|
||||||
|
if (IS_RC_MODE_ACTIVE(BOXBLACKBOX) && blackboxShouldLogIFrame()) {
|
||||||
|
// Write a log entry so the decoder is aware that our large time/iteration skip is intended
|
||||||
|
flightLogEvent_loggingResume_t resume;
|
||||||
|
|
||||||
|
resume.logIteration = blackboxIteration;
|
||||||
|
resume.currentTime = currentTime;
|
||||||
|
|
||||||
|
blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
|
||||||
|
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||||
|
|
||||||
|
blackboxLogIteration();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Keep the logging timers ticking so our log iteration continues to advance
|
||||||
|
blackboxAdvanceIterationTimers();
|
||||||
|
break;
|
||||||
case BLACKBOX_STATE_RUNNING:
|
case BLACKBOX_STATE_RUNNING:
|
||||||
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
||||||
if (blackboxModeActivationConditionPresent) {
|
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX)) {
|
||||||
if (IS_RC_MODE_ACTIVE(BOXBLACKBOX)) {
|
blackboxSetState(BLACKBOX_STATE_PAUSED);
|
||||||
blackboxLogIteration(true);
|
|
||||||
} else {
|
|
||||||
// Log only first I frame
|
|
||||||
blackboxLogIteration(blackboxIteration == 0);
|
|
||||||
}
|
|
||||||
} else {
|
} else {
|
||||||
blackboxLogIteration(true);
|
blackboxLogIteration();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
blackboxAdvanceIterationTimers();
|
||||||
break;
|
break;
|
||||||
case BLACKBOX_STATE_SHUTTING_DOWN:
|
case BLACKBOX_STATE_SHUTTING_DOWN:
|
||||||
//On entry of this state, startTime is set and a flush is performed
|
//On entry of this state, startTime is set and a flush is performed
|
||||||
|
|
|
@ -107,6 +107,7 @@ typedef enum FlightLogEvent {
|
||||||
FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_RESULT = 11,
|
FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_RESULT = 11,
|
||||||
FLIGHT_LOG_EVENT_AUTOTUNE_TARGETS = 12,
|
FLIGHT_LOG_EVENT_AUTOTUNE_TARGETS = 12,
|
||||||
FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13,
|
FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13,
|
||||||
|
FLIGHT_LOG_EVENT_LOGGING_RESUME = 14,
|
||||||
FLIGHT_LOG_EVENT_LOG_END = 255
|
FLIGHT_LOG_EVENT_LOG_END = 255
|
||||||
} FlightLogEvent;
|
} FlightLogEvent;
|
||||||
|
|
||||||
|
@ -147,6 +148,11 @@ typedef struct flightLogEvent_inflightAdjustment_t {
|
||||||
float newFloatValue;
|
float newFloatValue;
|
||||||
} flightLogEvent_inflightAdjustment_t;
|
} flightLogEvent_inflightAdjustment_t;
|
||||||
|
|
||||||
|
typedef struct flightLogEvent_loggingResume_t {
|
||||||
|
uint32_t logIteration;
|
||||||
|
uint32_t currentTime;
|
||||||
|
} flightLogEvent_loggingResume_t;
|
||||||
|
|
||||||
typedef union flightLogEventData_t
|
typedef union flightLogEventData_t
|
||||||
{
|
{
|
||||||
flightLogEvent_syncBeep_t syncBeep;
|
flightLogEvent_syncBeep_t syncBeep;
|
||||||
|
@ -154,6 +160,7 @@ typedef union flightLogEventData_t
|
||||||
flightLogEvent_autotuneCycleResult_t autotuneCycleResult;
|
flightLogEvent_autotuneCycleResult_t autotuneCycleResult;
|
||||||
flightLogEvent_autotuneTargets_t autotuneTargets;
|
flightLogEvent_autotuneTargets_t autotuneTargets;
|
||||||
flightLogEvent_inflightAdjustment_t inflightAdjustment;
|
flightLogEvent_inflightAdjustment_t inflightAdjustment;
|
||||||
|
flightLogEvent_loggingResume_t loggingResume;
|
||||||
} flightLogEventData_t;
|
} flightLogEventData_t;
|
||||||
|
|
||||||
typedef struct flightLogEvent_t
|
typedef struct flightLogEvent_t
|
||||||
|
|
|
@ -316,8 +316,12 @@ bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationC
|
||||||
|
|
||||||
for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
|
for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
|
||||||
modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index];
|
modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index];
|
||||||
if (modeActivationCondition->modeId == modeId && IS_RANGE_USABLE(&modeActivationCondition->range)) return true;
|
|
||||||
|
if (modeActivationCondition->modeId == modeId && IS_RANGE_USABLE(&modeActivationCondition->range)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -680,7 +680,6 @@ void mspInit(serialConfig_t *serialConfig)
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXSONAR;
|
activeBoxIds[activeBoxIdCount++] = BOXSONAR;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXSERVO1;
|
activeBoxIds[activeBoxIdCount++] = BOXSERVO1;
|
||||||
|
@ -688,11 +687,13 @@ void mspInit(serialConfig_t *serialConfig)
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXSERVO3;
|
activeBoxIds[activeBoxIdCount++] = BOXSERVO3;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef BLACKBOX
|
||||||
if (feature(FEATURE_BLACKBOX)){
|
if (feature(FEATURE_BLACKBOX)){
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXBLACKBOX;
|
activeBoxIds[activeBoxIdCount++] = BOXBLACKBOX;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
memset(mspPorts, 0x00, sizeof(mspPorts));
|
memset(mspPorts, 0x00, sizeof(mspPorts));
|
||||||
mspAllocateSerialPorts(serialConfig);
|
mspAllocateSerialPorts(serialConfig);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue