Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Logging: added LOG_FILE_RATEMAX parameter #18137

Merged
merged 20 commits into from Aug 3, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
4 changes: 2 additions & 2 deletions AntennaTracker/Log.cpp
Expand Up @@ -87,9 +87,9 @@ void Tracker::Log_Write_Vehicle_Pos(int32_t lat, int32_t lng, int32_t alt, const
const struct LogStructure Tracker::log_structure[] = {
LOG_COMMON_STRUCTURES,
{LOG_V_BAR_MSG, sizeof(log_Vehicle_Baro),
"VBAR", "Qff", "TimeUS,Press,AltDiff", "sPm", "F00" },
"VBAR", "Qff", "TimeUS,Press,AltDiff", "sPm", "F00" , true },
{LOG_V_POS_MSG, sizeof(log_Vehicle_Pos),
"VPOS", "QLLefff", "TimeUS,Lat,Lng,Alt,VelX,VelY,VelZ", "sddmnnn", "FGGB000" }
"VPOS", "QLLefff", "TimeUS,Lat,Lng,Alt,VelX,VelY,VelZ", "sddmnnn", "FGGB000", true }
};

void Tracker::Log_Write_Vehicle_Startup_Messages()
Expand Down
12 changes: 6 additions & 6 deletions ArduCopter/Log.cpp
Expand Up @@ -472,7 +472,7 @@ const struct LogStructure Copter::log_structure[] = {
// @Field: Value: Value

{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" },
"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" , true },

// @LoggerMessage: MOTB
// @Description: Battery information
Expand All @@ -483,7 +483,7 @@ const struct LogStructure Copter::log_structure[] = {
// @Field: ThLimit: Throttle limit set due to battery current limitations

{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" , true },
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
Expand All @@ -504,7 +504,7 @@ const struct LogStructure Copter::log_structure[] = {
// @Field: Throt: Throttle output
#if FRAME_CONFIG == HELI_FRAME
{ LOG_HELI_MSG, sizeof(log_Heli),
"HELI", "Qffff", "TimeUS,DRRPM,ERRPM,Gov,Throt", "s----", "F----" },
"HELI", "Qffff", "TimeUS,DRRPM,ERRPM,Gov,Throt", "s----", "F----" , true },
#endif

// @LoggerMessage: SIDD
Expand All @@ -521,7 +521,7 @@ const struct LogStructure Copter::log_structure[] = {
// @Field: Az: Delta velocity, Z-Axis

{ LOG_SYSIDD_MSG, sizeof(log_SysIdD),
"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" },
"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" , true },

// @LoggerMessage: SIDS
// @Description: System ID settings
Expand All @@ -536,7 +536,7 @@ const struct LogStructure Copter::log_structure[] = {
// @Field: TFout: Time to reach zero amplitude after chirp finishes

{ LOG_SYSIDS_MSG, sizeof(log_SysIdS),
"SIDS", "QBfffffff", "TimeUS,Ax,Mag,FSt,FSp,TFin,TC,TR,TFout", "s--ssssss", "F--------" },
"SIDS", "QBfffffff", "TimeUS,Ax,Mag,FSt,FSp,TFin,TC,TR,TFout", "s--ssssss", "F--------" , true },

// @LoggerMessage: GUID
// @Description: Guided mode target information
Expand All @@ -554,7 +554,7 @@ const struct LogStructure Copter::log_structure[] = {
// @Field: aZ: Target acceleration, Z-Axis

{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
"GUID", "QBfffbffffff", "TimeUS,Type,pX,pY,pZ,Terrain,vX,vY,vZ,aX,aY,aZ", "s-mmm-nnnooo", "F-BBB-BBBBBB" },
"GUID", "QBfffbffffff", "TimeUS,Type,pX,pY,pZ,Terrain,vX,vY,vZ,aX,aY,aZ", "s-mmm-nnnooo", "F-BBB-BBBBBB" , true },
};

void Copter::Log_Write_Vehicle_Startup_Messages()
Expand Down
24 changes: 12 additions & 12 deletions ArduPlane/Log.cpp
Expand Up @@ -309,7 +309,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: E2T: equivalent to true airspeed ratio

{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qcccchhhfff", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThO,RdrOut,ThD,As,SAs,E2T", "sdddd---nn-", "FBBBB---00-" },
"CTUN", "Qcccchhhfff", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThO,RdrOut,ThD,As,SAs,E2T", "sdddd---nn-", "FBBBB---00-" , true },

// @LoggerMessage: NTUN
// @Description: Navigation Tuning information - e.g. vehicle destination
Expand All @@ -326,7 +326,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: TAlt: target altitude
// @Field: TAspd: target airspeed
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
"NTUN", "QfcccfffLLii", "TimeUS,Dist,TBrg,NavBrg,AltErr,XT,XTi,AspdE,TLat,TLng,TAlt,TAspd", "smddmmmnDUmn", "F0BBB0B0GGBB" },
"NTUN", "QfcccfffLLii", "TimeUS,Dist,TBrg,NavBrg,AltErr,XT,XTi,AspdE,TLat,TLng,TAlt,TAspd", "smddmmmnDUmn", "F0BBB0B0GGBB" , true },

// @LoggerMessage: ATRP
// @Description: Plane AutoTune
Expand All @@ -346,7 +346,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: RMAX: Rate maximum
// @Field: TAU: time constant
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
"ATRP", "QBBffffffffBff", "TimeUS,Axis,State,Sur,PSlew,DSlew,FF0,FF,P,I,D,Action,RMAX,TAU", "s#-dkk------ks", "F--00000000-00" },
"ATRP", "QBBffffffffBff", "TimeUS,Axis,State,Sur,PSlew,DSlew,FF0,FF,P,I,D,Action,RMAX,TAU", "s#-dkk------ks", "F--00000000-00" , true },

// @LoggerMessage: STAT
// @Description: Current status of the aircraft
Expand All @@ -360,7 +360,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: Stage: Current stage of the flight
// @Field: Hit: True if impact is detected
{ LOG_STATUS_MSG, sizeof(log_Status),
"STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit", "s--------", "F--------" },
"STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit", "s--------", "F--------" , true },

// @LoggerMessage: QTUN
// @Description: QuadPlane vertical tuning message
Expand All @@ -379,7 +379,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: Trn: Transistion state
// @Field: Ast: Q assist active state
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
"QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" },
"QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" , true },

// @LoggerMessage: PIQR,PIQP,PIQY,PIQA
// @Description: QuadPlane Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Z
Expand All @@ -395,13 +395,13 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: SRate: slew rate
// @Field: Limit: 1 if I term is limited due to output saturation
{ LOG_PIQR_MSG, sizeof(log_PID),
"PIQR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS },
"PIQR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },
{ LOG_PIQP_MSG, sizeof(log_PID),
"PIQP", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS },
"PIQP", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },
{ LOG_PIQY_MSG, sizeof(log_PID),
"PIQY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS },
"PIQY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },
{ LOG_PIQA_MSG, sizeof(log_PID),
"PIQA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS },
"PIQA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },

// @LoggerMessage: PIDG
// @Description: Plane Proportional/Integral/Derivative gain values for Heading when using COMMAND_INT control.
Expand All @@ -417,7 +417,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: SRate: slew rate
// @Field: Limit: 1 if I term is limited due to output saturation
{ LOG_PIDG_MSG, sizeof(log_PID),
"PIDG", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS },
"PIDG", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true },

// @LoggerMessage: AETR
// @Description: Normalised pre-mixer control surface outputs
Expand All @@ -429,7 +429,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: Flap: Pre-mixer value for flaps output (between -4500 to 4500)
// @Field: SS: Surface movement / airspeed scaling value
{ LOG_AETR_MSG, sizeof(log_AETR),
"AETR", "Qhhhhhf", "TimeUS,Ail,Elev,Thr,Rudd,Flap,SS", "s------", "F------" },
"AETR", "Qhhhhhf", "TimeUS,Ail,Elev,Thr,Rudd,Flap,SS", "s------", "F------" , true },

// @LoggerMessage: OFG
// @Description: OFfboard-Guided - an advanced version of GUIDED for companion computers that includes rate/s.
Expand All @@ -442,7 +442,7 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: Hdg: target heading
// @Field: HdgA: target heading lim
{ LOG_OFG_MSG, sizeof(log_OFG_Guided),
"OFG", "QffffBff", "TimeUS,Arsp,ArspA,Alt,AltA,AltF,Hdg,HdgA", "s-------", "F-------" },
"OFG", "QffffBff", "TimeUS,Arsp,ArspA,Alt,AltA,AltF,Hdg,HdgA", "s-------", "F-------" , true },

// @LoggerMessage: CMDI
// @Description: Generic CommandInt message logger(CMDI)
Expand Down
10 changes: 5 additions & 5 deletions Tools/autotest/common.py
Expand Up @@ -1946,7 +1946,7 @@ def all_log_format_ids(self):
for message_info in message_infos:
for define in defines:
message_info = re.sub(define, defines[define], message_info)
m = re.match(r'\s*LOG_\w+\s*,\s*sizeof\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*$', message_info) # noqa
m = re.match(r'\s*LOG_\w+\s*,\s*sizeof\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*true)?\s*$', message_info) # noqa
if m is None:
continue
(name, fmt, labels, units, multipliers) = (m.group(1), m.group(2), m.group(3), m.group(4), m.group(5))
Expand Down Expand Up @@ -1983,8 +1983,8 @@ def all_log_format_ids(self):
if type(line) == bytes:
line = line.decode("utf-8")
if state == state_outside:
if (re.match(r"\s*AP::logger\(\)[.]Write\(", line) or
re.match(r"\s*logger[.]Write\(", line)):
if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or
re.match(r"\s*logger[.]Write(?:Streaming)?\(", line)):
state = state_inside
line = re.sub("//.*", "", line) # trim comments
log_write_statement = line
Expand All @@ -2008,10 +2008,10 @@ def all_log_format_ids(self):
log_write_statement = re.sub(define, defines[define], log_write_statement)
# fair warning: order is important here because of the
# NKT/XKT special case below....
my_re = r' logger[.]Write\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
my_re = r' logger[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
m = re.match(my_re, log_write_statement)
if m is None:
my_re = r' AP::logger\(\)[.]Write\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
my_re = r' AP::logger\(\)[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
m = re.match(my_re, log_write_statement)
if m is None:
raise NotAchievedException("Did not match (%s) with (%s)" % (log_write_statement, str(my_re)))
Expand Down
6 changes: 3 additions & 3 deletions libraries/AC_Avoidance/LogStructure.h
Expand Up @@ -91,8 +91,8 @@ struct PACKED log_SimpleAvoid {

#define LOG_STRUCTURE_FROM_AVOIDANCE \
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
"OABR","QBBHHHBfLLiLLi","TimeUS,Type,Act,DYaw,Yaw,DP,RChg,Mar,DLt,DLg,DAlt,OLt,OLg,OAlt", "s-bddd-mDUmDUm", "F-------GGBGGB" }, \
"OABR","QBBHHHBfLLiLLi","TimeUS,Type,Act,DYaw,Yaw,DP,RChg,Mar,DLt,DLg,DAlt,OLt,OLg,OAlt", "s-bddd-mDUmDUm", "F-------GGBGGB" , true }, \
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" }, \
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" , true }, \
{ LOG_SIMPLE_AVOID_MSG, sizeof(log_SimpleAvoid), \
"SA", "QBffffffB","TimeUS,State,DVelX,DVelY,DVelZ,MVelX,MVelY,MVelZ,Back", "sbnnnnnnb", "F--------"},
"SA", "QBffffffB","TimeUS,State,DVelX,DVelY,DVelZ,MVelX,MVelY,MVelZ,Back", "sbnnnnnnb", "F--------", true },
2 changes: 1 addition & 1 deletion libraries/AC_PrecLand/LogStructure.h
Expand Up @@ -41,4 +41,4 @@ struct PACKED log_Precland {

#define LOG_STRUCTURE_FROM_PRECLAND \
{ LOG_PRECLAND_MSG, sizeof(log_Precland), \
"PL", "QBBfffffffIIB", "TimeUS,Heal,TAcq,pX,pY,vX,vY,mX,mY,mZ,LastMeasMS,EKFOutl,Est", "s--mmnnmmms--","F--BBBBBBBC--" },
"PL", "QBBfffffffIIB", "TimeUS,Heal,TAcq,pX,pY,vX,vY,mX,mY,mZ,LastMeasMS,EKFOutl,Est", "s--mmnnmmms--","F--BBBBBBBC--" , true },
10 changes: 5 additions & 5 deletions libraries/AP_AHRS/LogStructure.h
Expand Up @@ -142,14 +142,14 @@ struct PACKED log_Rate {

#define LOG_STRUCTURE_FROM_AHRS \
{ LOG_AHR2_MSG, sizeof(log_AHRS), \
"AHR2","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4","sddhmDU????", "FBBB0GG????" }, \
"AHR2","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4","sddhmDU????", "FBBB0GG????" , true }, \
{ LOG_AOA_SSA_MSG, sizeof(log_AOA_SSA), \
"AOA", "Qff", "TimeUS,AOA,SSA", "sdd", "F00" }, \
"AOA", "Qff", "TimeUS,AOA,SSA", "sdd", "F00" , true }, \
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
"ATT", "QccccCCCCB", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw,AEKF", "sddddhhdh-", "FBBBBBBBB-" }, \
"ATT", "QccccCCCCB", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw,AEKF", "sddddhhdh-", "FBBBBBBBB-" , true }, \
{ LOG_ORGN_MSG, sizeof(log_ORGN), \
"ORGN","QBLLe","TimeUS,Type,Lat,Lng,Alt", "s-DUm", "F-GGB" }, \
{ LOG_POS_MSG, sizeof(log_POS), \
"POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" }, \
"POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" , true }, \
{ LOG_RATE_MSG, sizeof(log_Rate), \
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut", "skk-kk-kk-oo-", "F?????????BB-" },
"RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut", "skk-kk-kk-oo-", "F?????????BB-" , true },
2 changes: 1 addition & 1 deletion libraries/AP_Baro/LogStructure.h
Expand Up @@ -33,4 +33,4 @@ struct PACKED log_BARO {

#define LOG_STRUCTURE_FROM_BARO \
{ LOG_BARO_MSG, sizeof(log_BARO), \
"BARO", "QBffcfIffB", "TimeUS,I,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health", "s#mPOnsmO-", "F-00B0C?0-" },
"BARO", "QBffcfIffB", "TimeUS,I,Alt,Press,Temp,CRt,SMS,Offset,GndTemp,Health", "s#mPOnsmO-", "F-00B0C?0-" , true },
4 changes: 2 additions & 2 deletions libraries/AP_BattMonitor/LogStructure.h
Expand Up @@ -59,6 +59,6 @@ struct PACKED log_BCL {

#define LOG_STRUCTURE_FROM_BATTMONITOR \
{ LOG_BAT_MSG, sizeof(log_BAT), \
"BAT", "QBfffffcfB", "TimeUS,Instance,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res,RemPct", "s#vvAaXOw%", "F-000C0?00" }, \
"BAT", "QBfffffcfB", "TimeUS,Instance,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res,RemPct", "s#vvAaXOw%", "F-000C0?00" , true }, \
{ LOG_BCL_MSG, sizeof(log_BCL), \
"BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" },
"BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" , true },
2 changes: 1 addition & 1 deletion libraries/AP_ESC_Telem/LogStructure.h
Expand Up @@ -31,4 +31,4 @@ struct PACKED log_Esc {

#define LOG_STRUCTURE_FROM_ESC_TELEM \
{ LOG_ESC_MSG, sizeof(log_Esc), \
"ESC", "QBeffcfcf", "TimeUS,Instance,RPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qvAOaO%", "F-B--BCB-" },
"ESC", "QBeffcfcf", "TimeUS,Instance,RPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qvAOaO%", "F-B--BCB-" , true },
14 changes: 7 additions & 7 deletions libraries/AP_GPS/LogStructure.h
Expand Up @@ -196,16 +196,16 @@ struct PACKED log_GPS_RAWS {

#define LOG_STRUCTURE_FROM_GPS \
{ LOG_GPS_MSG, sizeof(log_GPS), \
"GPS", "QBBIHBcLLeffffB", "TimeUS,I,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U", "s#---SmDUmnhnh-", "F----0BGGB000--" }, \
"GPS", "QBBIHBcLLeffffB", "TimeUS,I,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U", "s#---SmDUmnhnh-", "F----0BGGB000--" , true }, \
{ LOG_GPA_MSG, sizeof(log_GPA), \
"GPA", "QBCCCCfBIH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta", "s#mmmnd-ss", "F-BBBB0-CC" }, \
"GPA", "QBCCCCfBIH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta", "s#mmmnd-ss", "F-BBBB0-CC" , true }, \
{ LOG_GPS_UBX1_MSG, sizeof(log_Ubx1), \
"UBX1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s#-----", "F------" }, \
"UBX1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s#-----", "F------" , true }, \
{ LOG_GPS_UBX2_MSG, sizeof(log_Ubx2), \
"UBX2", "QBbBbB", "TimeUS,Instance,ofsI,magI,ofsQ,magQ", "s#----", "F-----" }, \
"UBX2", "QBbBbB", "TimeUS,Instance,ofsI,magI,ofsQ,magQ", "s#----", "F-----" , true }, \
{ LOG_GPS_RAW_MSG, sizeof(log_GPS_RAW), \
"GRAW", "QIHBBddfBbB", "TimeUS,WkMS,Week,numSV,sv,cpMes,prMes,doMes,mesQI,cno,lli", "s--S-------", "F--0-------" }, \
"GRAW", "QIHBBddfBbB", "TimeUS,WkMS,Week,numSV,sv,cpMes,prMes,doMes,mesQI,cno,lli", "s--S-------", "F--0-------" , true }, \
{ LOG_GPS_RAWH_MSG, sizeof(log_GPS_RAWH), \
"GRXH", "QdHbBB", "TimeUS,rcvTime,week,leapS,numMeas,recStat", "s-----", "F-----" }, \
"GRXH", "QdHbBB", "TimeUS,rcvTime,week,leapS,numMeas,recStat", "s-----", "F-----" , true }, \
{ LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \
"GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" },
"GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" , true },
8 changes: 4 additions & 4 deletions libraries/AP_InertialSensor/LogStructure.h
Expand Up @@ -113,13 +113,13 @@ struct PACKED log_Vibe {

#define LOG_STRUCTURE_FROM_INERTIALSENSOR \
{ LOG_ACC_MSG, sizeof(log_ACC), \
"ACC", "QBQfff", "TimeUS,I,SampleUS,AccX,AccY,AccZ", "s#sooo", "F-F000" }, \
"ACC", "QBQfff", "TimeUS,I,SampleUS,AccX,AccY,AccZ", "s#sooo", "F-F000" , true }, \
{ LOG_GYR_MSG, sizeof(log_GYR), \
"GYR", "QBQfff", "TimeUS,I,SampleUS,GyrX,GyrY,GyrZ", "s#sEEE", "F-F000" }, \
"GYR", "QBQfff", "TimeUS,I,SampleUS,GyrX,GyrY,GyrZ", "s#sEEE", "F-F000" , true }, \
{ LOG_IMU_MSG, sizeof(log_IMU), \
"IMU", "QBffffffIIfBBHH", "TimeUS,I,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,EG,EA,T,GH,AH,GHz,AHz", "s#EEEooo--O--zz", "F-000000-----00" }, \
"IMU", "QBffffffIIfBBHH", "TimeUS,I,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,EG,EA,T,GH,AH,GHz,AHz", "s#EEEooo--O--zz", "F-000000-----00" , true }, \
{ LOG_VIBE_MSG, sizeof(log_Vibe), \
"VIBE", "QBfffI", "TimeUS,IMU,VibeX,VibeY,VibeZ,Clip", "s#----", "F-----" }, \
"VIBE", "QBfffI", "TimeUS,IMU,VibeX,VibeY,VibeZ,Clip", "s#----", "F-----" , true }, \
{ LOG_ISBH_MSG, sizeof(log_ISBH), \
"ISBH", "QHBBHHQf", "TimeUS,N,type,instance,mul,smp_cnt,SampleUS,smp_rate", "s-----sz", "F-----F-" }, \
{ LOG_ISBD_MSG, sizeof(log_ISBD), \
Expand Down