this fixes a problem with sdcards where file open is very slow. It can
trigger a watchdog if it is slow enough. Peter and I hit this issue on
a pixracer today with a new sd card
this fixes an issue where the sd card fails in flight and then
re-mounts. When that happens the logging backend can trigger a new log
open. That causes filesystem operations in the main thread while
flying. That can cause long delays or even a watchdog.
Thanks to Giacomo for noticing this on his flying wing
These were only being called directly after Init(), so just tacked them
onto the end of those functions.
The checks in NeedPrep turned out to be mostly redundant.
add support for log time to block logger
refactor rotation into backed. Don't start logs when erasing
correct log start logic
separate read and write points so that requesting log information does not corrupt the current log
when starting a new log stop logging first
clear the write buffer when starting a new log
insert utc time when requesting info for the current log
stop logging and request formats again when starting a new log
cope with erase happening while we are logging
keep pushing out startup messages even when format messages are done
don't log to the gcs in the io thread
don't start new logs in the io thread
don't validate logs while erasing
flush logs when stopping logging
account for page header when calculating logs sizes
don't return data when asked for more data than in the log
optimize locking and use separate semaphore to mediate ring buffer access
stop logging when the chip is full and send a notification
calculate logs sizes correctly even when they wrap
read log data correctly even when it wraps
add stats support to block logger
reset dropped when starting a new log
fail logging when the chip is full
refactor critical bufferspace checks
increase messagewriter budget to 250us and to 300us for FMT
If anything in start_new_log did logging (for example, by sending a
statustext), we end up infinitely recursing.
With the patch:
diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp
index 69b8ef0431..eb422d10f8 100644
--- a/libraries/AP_Logger/AP_Logger_File.cpp
+++ b/libraries/AP_Logger/AP_Logger_File.cpp
@@ -778,6 +778,7 @@ void AP_Logger_File::PrepForArming()
*/
void AP_Logger_File::start_new_log(void)
{
+ gcs().send_text(MAV_SEVERITY_WARNING, "Starting new log");
stop_logging();
start_new_log_reset_variables();
pbarker@bluebottle:~/rc/ardupilot(master)$
We see:
at ../../libraries/AP_Logger/AP_Logger_File.cpp:781
this=0x555555ad9d30, pBuffer=0x7fffff8209d0, size=75, is_critical=true)
at ../../libraries/AP_Logger/AP_Logger_Backend.cpp:372
this=0x555555ad9d30, pBuffer=0x7fffff8209d0, size=75)
at ../../libraries/AP_Logger/AP_Logger_Backend.h:32
this=0x555555ad9d30, message=0x7fffff820b10 "Starting new log")
at ../../libraries/AP_Logger/LogFile.cpp:466
this=0x555555a6d758 <copter+11384>,
message=0x7fffff820b10 "Starting new log")
at ../../libraries/AP_Logger/AP_Logger.cpp:752
this=0x555555a6e708 <copter+15400>, severity=MAV_SEVERITY_WARNING,
fmt=0x5555557d64d0 "Starting new log", arg_list=0x7fffff820be0,
dest_bitmask=1 '\001') at ../../libraries/GCS_MAVLink/GCS_Common.cpp:1847
this=0x555555a6e708 <copter+15400>, severity=MAV_SEVERITY_WARNING,
fmt=0x5555557d64d0 "Starting new log", arg_list=0x7fffff820be0)
at ../../libraries/GCS_MAVLink/GCS.cpp:53
this=0x555555a6e708 <copter+15400>, severity=MAV_SEVERITY_WARNING,
fmt=0x5555557d64d0 "Starting new log")
at ../../libraries/GCS_MAVLink/GCS.cpp:60
at ../../libraries/AP_Logger/AP_Logger_File.cpp:781
this=0x555555ad9d30, pBuffer=0x7fffff820dc0, size=75, is_critical=true)
at ../../libraries/AP_Logger/AP_Logger_Backend.cpp:372
I'm not aware of any instances in the code where this will actually
happen - but it could easily sneak in.
now that we persist logging for 15s after disarm we need to also delay
the log rotation if LOG_FILE_DSRMROT=1. Otherwise we will put the log
data into the next log, which defeats the purpose of the 15s
persistance