Plane: mark log messages as streaming

This commit is contained in:
Andrew Tridgell 2021-07-27 18:48:10 +10:00
parent e1094bc845
commit e7702a4216
1 changed files with 12 additions and 12 deletions

View File

@ -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
@ -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
@ -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
@ -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
@ -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
@ -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.
@ -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
@ -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.
@ -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)