Optimal logging settings for flight controllers with suboptimal dataflash? (F405, H7 Mini)

It’s 2025, and some of us are still using flight controllers with slow processors and low capacity flash chips. Yes, you did try to warn us.

I have small quadcopters with Matek H743-Slim v3, Holybro Kakute H7 Mini v1.3 and Speedybee F405 Mini. All perform adequately well, but with the F405 Mini (8MB) and H7 Mini (16MB) I’ve frequently experienced logging failures due to a full dataflash chip. IMU batch logging for a minute or two to in order to set up the notch filtering generally hasn’t been a problem. Once I’ve set and tested the filters I disable IMU batch logging.

With my current logging parameters, the F405 can log for around five minutes before the dataflash is full and logging fails. I’d like to extend that time to around seven or eight minutes, but without “throwing the baby out with the bath water”. Ideally I’d like the logs to be usable with some of the Ardupilot web tools (although some of these seem not to work with data from the F405 for reasons that aren’t clear).

My current logging parameters are:

EK3_LOG_LEVEL,0
INS_LOG_BAT_CNT,1024
INS_LOG_BAT_LGCT,32
INS_LOG_BAT_LGIN,50
INS_LOG_BAT_MASK,0
INS_LOG_BAT_OPT,2
INS_RAW_LOG_OPT,0
LOG_BACKEND_TYPE,4
LOG_BITMASK,145406
LOG_BLK_RATEMAX,0
LOG_DARM_RATEMAX,0
LOG_DISARMED,0
LOG_FILE_BUFSIZE,16
LOG_FILE_DSRMROT,1
LOG_FILE_MB_FREE,7
LOG_FILE_RATEMAX,0
LOG_FILE_TIMEOUT,5
LOG_MAV_BUFSIZE,8
LOG_MAV_RATEMAX,0
LOG_MAX_FILES,500
LOG_REPLAY,0
SERVO_BLH_TRATE,5

I’ve experimented with INS_LOG_BAT_LGIN & INS_LOG_BAT_LGCT (I believe these are only relevant with IMU batch logging on) and also with low values for LOG_BLK_RATEMAX. IIRC setting LOG_BLK_RATEMAX to 5 or 10 reduces the log file sizes a bit, but not as much as I’d expected.

I’d be grateful for any pointers on how to reduce log file sizes further.

I’ve done a bit more digging.

The HardwareReport tool indicates that over 40% of the log file content is ESC telemetry.

Looking at the logs in APM Planner, it looks like ESC log records for all four ESCs are added at roughly 10 millisecond intervals. Aside from the timestamp, each ESC record has nine elements, four of which are always zero. Of the other elements, RPM & RawRPM seem redundant, Err (%) is typically 0, and Temp R is slow moving. That’s sparse data at a high rate.

I’m using DShot300 and have SERVO_DSHOT_ESC set for BlueJay+EDT. Setting SERVO_DSHOT_ESC for BlueJay (without EDT) disables RPM logging per motor, which I think is the most useful of the ESC metrics. Is there a way to reduce the ESC data logging significantly whilst retaining the useful data at a sensible rate?

ESCs are only filtered by LOG_BLK_RATEMAX (when logging to flash) and LOG_FILE_RATEMAX (when logging to SD cards). On machines with 8Mb of flash I have these set to 5 or 10, depending on the craft, and this actually helps. With the value of 5, I believe about 15 minutes of logs are possible (the most recent flight of 500 seconds took just above 4 megs).

This is I believe a bit less than what is tested on a regular basis, and occasionally some entry descriptors appear to get logged in a way some GCSs do not expect, but generally it works.

That said, I use these sparse logs mainly for battery discharge tracking and debugging occasional in-flight issues that are big enough to manifest at 5Hz logging. They may not show you particular problems with tuning, for instance, if that problem requires a high logging rate, so whenever I evaluate tunings, I perform short flights with ratemax back at zero.

P.S.: I have once proposed a patch introducing bitmask to limit which ESCs get logged (e.g. only one problematic motor, or turning them off), mostly for the same reason of getting log sizes down, but it was not accepted pretty much because of the presence of the ratemax option.

1 Like

Where is your PR Max?

It was this one: AP_ESC_Telem: Add ESC_TLM_LOG_MASK to control which motors are logged by mbuzdalov · Pull Request #24199 · ArduPilot/ardupilot · GitHub.

Thanks @MaxBuzz !
I’ve re-tested with LOG_BLK_RATEMAX,5 and the log files from todays flights were all under 5MB. The ESC portion of the logs is now down around 7.5%. The longest flight time was 6m35s.
It’d be preferable to have higher resolution log data, but I estimate that with LOG_BLK_RATEMAX,10 the dataflash would be filled in a fraction over six minutes, which tallies with my previous experience of logging failures during gentle full flights.

For reference, these settings seem to be ok for general flying with the Speedybee F405 Mini:

EK3_LOG_LEVEL,0
INS_LOG_BAT_CNT,1024
INS_LOG_BAT_LGCT,32
INS_LOG_BAT_LGIN,50
INS_LOG_BAT_MASK,0
INS_LOG_BAT_OPT,2
INS_RAW_LOG_OPT,0
LOG_BACKEND_TYPE,4
LOG_BITMASK,145406
LOG_BLK_RATEMAX,5
LOG_DARM_RATEMAX,0
LOG_DISARMED,0
LOG_FILE_BUFSIZE,16
LOG_FILE_DSRMROT,1
LOG_FILE_MB_FREE,7
LOG_FILE_RATEMAX,0
LOG_FILE_TIMEOUT,10
LOG_MAV_BUFSIZE,8
LOG_MAV_RATEMAX,0
LOG_MAX_FILES,500
LOG_REPLAY,0
SERVO_BLH_TRATE,5

INS_LOG_BAT_LGIN,50 is probably unnecessary, but allows slightly longer flight logs when IMU batch logging is enabled.