From b43ae871f2de13acabfe457fe49d6c99f2fee366 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 15 Oct 2024 08:08:18 +1100 Subject: [PATCH] AP_Logger: mark CSRV non-streaming the rate of CAN servo messages is controlled by the servo. Having this streaming means we can miss logging when there is more than one CAN servo. In the future we will move to holding the CAN servo data in a data structure like we do for ESCs, and then log at a regular rate, but for now this fixes the issue --- libraries/AP_Logger/LogStructure.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index a4f853e240257..ae5197297c373 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -1218,7 +1218,7 @@ LOG_STRUCTURE_FROM_AVOIDANCE \ "TERR","QBLLHffHHf","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded,ROfs", "s-DU-mm--m", "F-GG-00--0", true }, \ LOG_STRUCTURE_FROM_ESC_TELEM \ { LOG_CSRV_MSG, sizeof(log_CSRV), \ - "CSRV","QBfffBfffffB","TimeUS,Id,Pos,Force,Speed,Pow,PosCmd,V,A,MotT,PCBT,Err", "s#---%dvAOO-", "F-000000000-", true }, \ + "CSRV","QBfffBfffffB","TimeUS,Id,Pos,Force,Speed,Pow,PosCmd,V,A,MotT,PCBT,Err", "s#---%dvAOO-", "F-000000000-", false }, \ { LOG_PIDR_MSG, sizeof(log_PID), \ "PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS, true }, \ { LOG_PIDP_MSG, sizeof(log_PID), \