From 662f7a01917ce26eb0f53e2b31c5e88bb95ac5f2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Jul 2021 18:47:45 +1000 Subject: [PATCH] AP_Logger: added LOG_FILE_RATEMAX parameter this allows for a global "maximum rate in Hz for streaming messages" setting --- libraries/AP_Logger/AP_Logger.cpp | 31 +++++++++- libraries/AP_Logger/AP_Logger.h | 6 +- libraries/AP_Logger/AP_Logger_Backend.cpp | 70 ++++++++++++++++++++++- libraries/AP_Logger/AP_Logger_Backend.h | 25 +++++++- libraries/AP_Logger/AP_Logger_File.cpp | 5 ++ libraries/AP_Logger/LogStructure.h | 63 ++++++++++---------- 6 files changed, 164 insertions(+), 36 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index b531aaf14b..5a191268a0 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -115,6 +115,14 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { // @User: Standard AP_GROUPINFO("_FILE_MB_FREE", 7, AP_Logger, _params.min_MB_free, 500), + // @Param: _FILE_RATEMAX + // @DisplayName: Maximum logging rate + // @Description: This sets the maximum rate that streaming log messages will be logged to the file backend. A value of zero means + // @Units: Hz + // @Range: 0 1000 + // @User: Standard + AP_GROUPINFO("_FILE_RATEMAX", 8, AP_Logger, _params.file_ratemax, 0), + AP_GROUPEND }; @@ -931,6 +939,24 @@ void AP_Logger::Write(const char *name, const char *labels, const char *units, c va_end(arg_list); } +void AP_Logger::WriteStreaming(const char *name, const char *labels, const char *fmt, ...) +{ + va_list arg_list; + + va_start(arg_list, fmt); + WriteV(name, labels, nullptr, nullptr, fmt, arg_list, false, true); + va_end(arg_list); +} + +void AP_Logger::WriteStreaming(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...) +{ + va_list arg_list; + + va_start(arg_list, fmt); + WriteV(name, labels, units, mults, fmt, arg_list, false, true); + va_end(arg_list); +} + void AP_Logger::WriteCritical(const char *name, const char *labels, const char *fmt, ...) { va_list arg_list; @@ -949,7 +975,8 @@ void AP_Logger::WriteCritical(const char *name, const char *labels, const char * va_end(arg_list); } -void AP_Logger::WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical) +void AP_Logger::WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, + bool is_critical, bool is_streaming) { // WriteV is not safe in replay as we can re-use IDs const bool direct_comp = APM_BUILD_TYPE(APM_BUILD_Replay); @@ -972,7 +999,7 @@ void AP_Logger::WriteV(const char *name, const char *labels, const char *units, } va_list arg_copy; va_copy(arg_copy, arg_list); - backends[i]->Write(f->msg_type, arg_copy, is_critical); + backends[i]->Write(f->msg_type, arg_copy, is_critical, is_streaming); va_end(arg_copy); } } diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index e06b5defa6..779f43906f 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -240,6 +240,7 @@ enum class LogErrorCode : uint8_t { class AP_Logger { friend class AP_Logger_Backend; // for _num_types + friend class AP_Logger_RateLimiter; public: FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void); @@ -325,9 +326,11 @@ public: void Write(const char *name, const char *labels, const char *fmt, ...); void Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...); + void WriteStreaming(const char *name, const char *labels, const char *fmt, ...); + void WriteStreaming(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...); void WriteCritical(const char *name, const char *labels, const char *fmt, ...); void WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...); - void WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical=false); + void WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical=false, bool is_streaming=false); // This structure provides information on the internal member data of a PID for logging purposes struct PID_Info { @@ -384,6 +387,7 @@ public: AP_Int8 mav_bufsize; // in kilobytes AP_Int16 file_timeout; // in seconds AP_Int16 min_MB_free; + AP_Float file_ratemax; } _params; const struct LogStructure *structure(uint16_t num) const; diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 382cea9d54..28d00b431d 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -208,7 +208,7 @@ bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type) return true; } -bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_critical) +bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_critical, bool is_streaming) { // stack-allocate a buffer so we can WriteBlock(); this could be // 255 bytes! If we were willing to lose the WriteBlock @@ -230,6 +230,14 @@ bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_ if (bufferspace_available() < msg_len) { return false; } + + // see if it should be rate limited + if (rate_limiter && + !is_critical && + !rate_limiter->should_log_streaming(msg_type)) { + return false; + } + uint8_t buffer[msg_len]; uint8_t offset = 0; buffer[offset++] = HEAD_BYTE1; @@ -411,6 +419,14 @@ bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size if (!WritesOK()) { return false; } + + if (!is_critical && rate_limiter != nullptr) { + const uint8_t *msgbuf = (const uint8_t *)pBuffer; + if (!rate_limiter->should_log(msgbuf[2])) { + return false; + } + } + return _WritePrioritisedBlock(pBuffer, size, is_critical); } @@ -606,3 +622,55 @@ void AP_Logger_Backend::df_stats_log() { Write_AP_Logger_Stats_File(stats); df_stats_clear(); } + + +// class to handle rate limiting of log messages +AP_Logger_RateLimiter::AP_Logger_RateLimiter(const AP_Logger &_front, const AP_Float &_limit_hz) + : front(_front), rate_limit_hz(_limit_hz) +{ +} + +/* + return false if a streaming message should not be sent yet + */ +bool AP_Logger_RateLimiter::should_log_streaming(uint8_t msgid) +{ + if (rate_limit_hz <= 0) { + // no limiting (user changed the parameter) + return true; + } + const uint16_t now = AP_HAL::millis16(); + uint16_t delta_ms = now - last_send_ms[msgid]; + if (delta_ms < 1000.0 / rate_limit_hz.get()) { + // too soon + return false; + } + last_send_ms[msgid] = now; + return true; +} + +/* + return true if the message is not a streaming message or the gap + from the last message is more than the message rate + */ +bool AP_Logger_RateLimiter::should_log(uint8_t msgid) +{ + if (rate_limit_hz <= 0) { + // no limiting (user changed the parameter) + return true; + } + if (last_send_ms[msgid] == 0) { + // might be non streaming. check the not_streaming bitmask + // cache + if (not_streaming.get(msgid)) { + return true; + } + const auto *mtype = front.structure_for_msg_type(msgid); + if (mtype == nullptr || + mtype->streaming == false) { + not_streaming.set(msgid); + return true; + } + } + return should_log_streaming(msgid); +} diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 0a9ccc0707..0acb0687ad 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -6,6 +6,27 @@ class LoggerMessageWriter_DFLogStart; #define MAX_LOG_FILES 500 +// class to handle rate limiting of log messages +class AP_Logger_RateLimiter +{ +public: + AP_Logger_RateLimiter(const AP_Logger &_front, const AP_Float &_limit_hz); + + // return true if message passes the rate limit test + bool should_log(uint8_t msgid); + bool should_log_streaming(uint8_t msgid); + +private: + const AP_Logger &front; + const AP_Float &rate_limit_hz; + + // time in ms we last sent this message + uint16_t last_send_ms[256]; + + // mask of message types that are not streaming + Bitmask<256> not_streaming; +}; + class AP_Logger_Backend { @@ -114,7 +135,7 @@ public: // write a log message out to the log of msg_type type, with // values contained in arg_list: - bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false); + bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false, bool is_streaming=false); // these methods are used when reporting system status over mavlink virtual bool logging_enabled() const; @@ -200,6 +221,8 @@ protected: void df_stats_log(); void df_stats_clear(); + AP_Logger_RateLimiter *rate_limiter; + private: // statistics support struct df_stats { diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 989a0c96af..f4789019a0 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -167,6 +167,11 @@ void AP_Logger_File::periodic_1Hz() _write_fd = -1; _initialised = false; } + + if (rate_limiter == nullptr && _front._params.file_ratemax > 0) { + // setup rate limiting + rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.file_ratemax); + } } void AP_Logger_File::periodic_fullrate() diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 73f7defa1a..c1cb32cf9f 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -143,6 +143,7 @@ struct LogStructure { const char *labels; const char *units; const char *multipliers; + bool streaming; // can be rate limited }; // maximum lengths of fields in LogStructure, including trailing nulls @@ -1225,68 +1226,68 @@ LOG_STRUCTURE_FROM_GPS \ { LOG_MESSAGE_MSG, sizeof(log_Message), \ "MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \ { LOG_RCIN_MSG, sizeof(log_RCIN), \ - "RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \ + "RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \ { LOG_RCIN2_MSG, sizeof(log_RCIN2), \ - "RCI2", "QHHH", "TimeUS,C15,C16,OMask", "sYY-", "F---" }, \ + "RCI2", "QHHH", "TimeUS,C15,C16,OMask", "sYY-", "F---", true }, \ { LOG_RCOUT_MSG, sizeof(log_RCOUT), \ - "RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \ + "RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \ { LOG_RSSI_MSG, sizeof(log_RSSI), \ - "RSSI", "Qff", "TimeUS,RXRSSI,RXLQ", "s--", "F--" }, \ + "RSSI", "Qff", "TimeUS,RXRSSI,RXLQ", "s--", "F--", true }, \ LOG_STRUCTURE_FROM_BARO \ LOG_STRUCTURE_FROM_PRECLAND \ { LOG_POWR_MSG, sizeof(log_POWR), \ - "POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---" }, \ + "POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---", true }, \ { LOG_CMD_MSG, sizeof(log_Cmd), \ "CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \ { LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \ "MAVC", "QBBBHBBffffiifBB","TimeUS,TS,TC,Fr,Cmd,Cur,AC,P1,P2,P3,P4,X,Y,Z,Res,WL", "s---------------", "F---------------" }, \ { LOG_RADIO_MSG, sizeof(log_Radio), \ - "RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------" }, \ + "RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------", true }, \ LOG_STRUCTURE_FROM_CAMERA \ - { LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBfB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hfp,Pri", "s#nPOPP----", "F-00B00----" }, \ + { LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBfB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hfp,Pri", "s#nPOPP----", "F-00B00----", true }, \ LOG_STRUCTURE_FROM_BATTMONITOR \ { LOG_MAG_MSG, sizeof(log_MAG), \ - "MAG", "QBhhhhhhhhhBI", "TimeUS,I,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOX,MOY,MOZ,Health,S", "s#GGGGGGGGG-s", "F-CCCCCCCCC-F" }, \ + "MAG", "QBhhhhhhhhhBI", "TimeUS,I,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOX,MOY,MOZ,Health,S", "s#GGGGGGGGG-s", "F-CCCCCCCCC-F", true }, \ { LOG_MODE_MSG, sizeof(log_Mode), \ "MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn", "s---", "F---" }, \ { LOG_RFND_MSG, sizeof(log_RFND), \ - "RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--" }, \ + "RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--", true }, \ { LOG_MAV_STATS, sizeof(log_MAV_Stats), \ "DMS", "QIIIIBBBBBBBBB", "TimeUS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "F-------------" }, \ { LOG_BEACON_MSG, sizeof(log_Beacon), \ - "BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--0000000" }, \ + "BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--0000000", true }, \ { LOG_PROXIMITY_MSG, sizeof(log_Proximity), \ - "PRX", "QBBfffffffffff", "TimeUS,Layer,He,D0,D45,D90,D135,D180,D225,D270,D315,DUp,CAn,CDis", "s#-mmmmmmmmmhm", "F--00000000000" }, \ + "PRX", "QBBfffffffffff", "TimeUS,Layer,He,D0,D45,D90,D135,D180,D225,D270,D315,DUp,CAn,CDis", "s#-mmmmmmmmmhm", "F--00000000000", true }, \ { LOG_RAW_PROXIMITY_MSG, sizeof(log_Proximity_raw), \ - "PRXR", "QBffffffff", "TimeUS,Layer,D0,D45,D90,D135,D180,D225,D270,D315", "s#mmmmmmmm", "F-00000000" }, \ + "PRXR", "QBffffffff", "TimeUS,Layer,D0,D45,D90,D135,D180,D225,D270,D315", "s#mmmmmmmm", "F-00000000", true }, \ { LOG_PERFORMANCE_MSG, sizeof(log_Performance), \ "PM", "QHHIIHHIIIIII", "TimeUS,NLon,NLoop,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "s---b%------s", "F---0A------F" }, \ { LOG_SRTL_MSG, sizeof(log_SRTL), \ "SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \ LOG_STRUCTURE_FROM_AVOIDANCE \ { LOG_SIMSTATE_MSG, sizeof(log_AHRS), \ - "SIM","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4", "sddhmDU????", "FBBB0GG????" }, \ + "SIM","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4", "sddhmDU????", "FBBB0GG????", true }, \ { LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \ - "TERR","QBLLHffHH","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded", "s-DU-mm--", "F-GG-00--" }, \ + "TERR","QBLLHffHH","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded", "s-DU-mm--", "F-GG-00--", true }, \ LOG_STRUCTURE_FROM_ESC_TELEM \ { LOG_CSRV_MSG, sizeof(log_CSRV), \ - "CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000" }, \ + "CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000", true }, \ { LOG_PIDR_MSG, sizeof(log_PID), \ - "PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS, true }, \ { LOG_PIDP_MSG, sizeof(log_PID), \ - "PIDP", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDP", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_PIDY_MSG, sizeof(log_PID), \ - "PIDY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_PIDA_MSG, sizeof(log_PID), \ - "PIDA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_PIDS_MSG, sizeof(log_PID), \ - "PIDS", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDS", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_PIDN_MSG, sizeof(log_PID), \ - "PIDN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_PIDE_MSG, sizeof(log_PID), \ - "PIDE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \ + "PIDE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_DSTL_MSG, sizeof(log_DSTL), \ - "DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" }, \ + "DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" , true }, \ LOG_STRUCTURE_FROM_INERTIALSENSOR \ LOG_STRUCTURE_FROM_DAL \ LOG_STRUCTURE_FROM_NAVEKF2 \ @@ -1296,16 +1297,16 @@ LOG_STRUCTURE_FROM_AHRS \ { LOG_DF_FILE_STATS, sizeof(log_DSF), \ "DSF", "QIHIIII", "TimeUS,Dp,Blk,Bytes,FMn,FMx,FAv", "s--b---", "F--0---" }, \ { LOG_RPM_MSG, sizeof(log_RPM), \ - "RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" }, \ + "RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" , true }, \ { LOG_RALLY_MSG, sizeof(log_Rally), \ "RALY", "QBBLLh", "TimeUS,Tot,Seq,Lat,Lng,Alt", "s--DUm", "F--GGB" }, \ { LOG_MAV_MSG, sizeof(log_MAV), \ "MAV", "QBHHHBHH", "TimeUS,chan,txp,rxp,rxdp,flags,ss,tf", "s#----s-", "F-000-C-" }, \ LOG_STRUCTURE_FROM_VISUALODOM \ { LOG_OPTFLOW_MSG, sizeof(log_Optflow), \ - "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEnn", "F-0000" }, \ + "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEnn", "F-0000" , true }, \ { LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder), \ - "WENC", "Qfbfb", "TimeUS,Dist0,Qual0,Dist1,Qual1", "sm-m-", "F0-0-" }, \ + "WENC", "Qfbfb", "TimeUS,Dist0,Qual0,Dist1,Qual1", "sm-m-", "F0-0-" , true }, \ { LOG_ADSB_MSG, sizeof(log_ADSB), \ "ADSB", "QIiiiHHhH", "TimeUS,ICAO_address,Lat,Lng,Alt,Heading,Hor_vel,Ver_vel,Squark", "s-DUmhnn-", "F-GGCBCC-" }, \ { LOG_EVENT_MSG, sizeof(log_Event), \ @@ -1317,9 +1318,9 @@ LOG_STRUCTURE_FROM_VISUALODOM \ { LOG_WINCH_MSG, sizeof(log_Winch), \ "WINC", "QBBBBBfffHfb", "TimeUS,Heal,ThEnd,Mov,Clut,Mode,DLen,Len,DRate,Tens,Vcc,Temp", "s-----mmn?vO", "F-----000000" }, \ { LOG_PSC_MSG, sizeof(log_PSC), \ - "PSC", "Qffffffffffff", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY", "smmmmnnnnoooo", "F000000000000" }, \ + "PSC", "Qffffffffffff", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY", "smmmmnnnnoooo", "F000000000000", true }, \ { LOG_PSCZ_MSG, sizeof(log_PSCZ), \ - "PSCZ", "Qfffffffff", "TimeUS,TPZ,PZ,DVZ,TVZ,VZ,DAZ,TAZ,AZ,ThO", "smmnnnooo%", "F000000002" } + "PSCZ", "Qfffffffff", "TimeUS,TPZ,PZ,DVZ,TVZ,VZ,DAZ,TAZ,AZ,ThO", "smmnnnooo%", "F000000002", true } // @LoggerMessage: SBPH // @Description: Swift Health Data @@ -1341,11 +1342,11 @@ LOG_STRUCTURE_FROM_VISUALODOM \ #define LOG_SBP_STRUCTURES \ { LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \ - "SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" }, \ + "SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" , true }, \ { LOG_MSG_SBPRAWH, sizeof(log_SbpRAWH), \ - "SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s--b----", "F--0----" }, \ + "SBRH", "QQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6", "s--b----", "F--0----" , true }, \ { LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \ - "SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" }, \ + "SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" , true }, \ { LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \ "SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" }