Units are not associated with the CurrTot message. AP_BattMonitor.h indicates the total current consumed is reported in mAh. This change sets the units for CurrTot to Ampere seconds and applies a multiplier of 3.6 to convert the reported mAh value to Ampere seconds.
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.
These appear to have been replaced with instance fields on the UBX1 and
UBX2 messages.
Also mark the Instance field on UBX1, UBX2 as an instance field.
Instead of creating a MessageWriter explicitly to log uploaded missions
we fiddle the state of the one stored in the startup message writer.
This has the advantage of being much more likely to log the entire
mission (as the buffer constraint is removed), and with the addition of
a time-remaining check much less likely to cause a timing glitch.