mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: support for units on fields
This commit is contained in:
parent
dc99a29dfc
commit
6ed0d645a3
@ -365,42 +365,45 @@ void Plane::Log_Write_Home_And_Origin()
|
||||
}
|
||||
}
|
||||
|
||||
// type and unit information can be found in
|
||||
// libraries/DataFlash/Logstructure.h; search for "log_Units" for
|
||||
// units and "Format characters" for field type information
|
||||
const struct LogStructure Plane::log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "QHHIIII", "TimeUS,NLon,NLoop,MaxT,MinT,LogDrop,Mem" },
|
||||
"PM", "QHHIIII", "TimeUS,NLon,NLoop,MaxT,MinT,LogDrop,Mem", "ss----b", "FC----0" },
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "QBH", "TimeUS,SType,CTot" },
|
||||
"STRT", "QBH", "TimeUS,SType,CTot", "s--", "F--" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
"CTUN", "Qcccchhhf", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,ThrDem,Aspd" },
|
||||
"CTUN", "Qcccchhhf", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,ThrDem,Aspd", "sdddd---n", "FBBBB---0" },
|
||||
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
||||
"NTUN", "Qfcccfff", "TimeUS,WpDist,TargBrg,NavBrg,AltErr,XT,XTi,ArspdErr" },
|
||||
"NTUN", "Qfcccfff", "TimeUS,WpDist,TargBrg,NavBrg,AltErr,XT,XTi,ArspdErr", "smddmmmn", "F0BBB0B0" },
|
||||
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
||||
"SONR", "QffBf", "TimeUS,Dist,Volt,Cnt,Corr" },
|
||||
"SONR", "QffBf", "TimeUS,Dist,Volt,Cnt,Corr", "smv--", "FB0--" },
|
||||
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
|
||||
"ARM", "QBH", "TimeUS,ArmState,ArmChecks" },
|
||||
"ARM", "QBH", "TimeUS,ArmState,ArmChecks", "s--", "F--" },
|
||||
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
|
||||
"ATRP", "QBBcfff", "TimeUS,Type,State,Servo,Demanded,Achieved,P" },
|
||||
"ATRP", "QBBcfff", "TimeUS,Type,State,Servo,Demanded,Achieved,P", "s---dd-", "F---00-" },
|
||||
{ LOG_STATUS_MSG, sizeof(log_Status),
|
||||
"STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit" },
|
||||
"STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit", "s--------", "F--------" },
|
||||
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
|
||||
"QTUN", "Qffffhhfffff", "TimeUS,AngBst,ThrOut,DAlt,Alt,DCRt,CRt,DVx,DVy,DAx,DAy,TMix" },
|
||||
"QTUN", "Qffffhhfffff", "TimeUS,AngBst,ThrOut,DAlt,Alt,DCRt,CRt,DVx,DVy,DAx,DAy,TMix", "s--mmnnnnoo-", "F--BBBB0000-" },
|
||||
{ LOG_AOA_SSA_MSG, sizeof(log_AOA_SSA),
|
||||
"AOA", "Qff", "TimeUS,AOA,SSA" },
|
||||
"AOA", "Qff", "TimeUS,AOA,SSA", "sdd", "F00" },
|
||||
#if OPTFLOW == ENABLED
|
||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
|
||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" },
|
||||
#endif
|
||||
{ LOG_PIQR_MSG, sizeof(log_PID), \
|
||||
"PIQR", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
"PIQR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
||||
{ LOG_PIQP_MSG, sizeof(log_PID), \
|
||||
"PIQP", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
"PIQP", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
||||
{ LOG_PIQY_MSG, sizeof(log_PID), \
|
||||
"PIQY", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
"PIQY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
||||
{ LOG_PIQA_MSG, sizeof(log_PID), \
|
||||
"PIQA", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
"PIQA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, \
|
||||
{ LOG_AETR_MSG, sizeof(log_AETR), \
|
||||
"AETR", "Qhhhhh", "TimeUS,Ail,Elev,Thr,Rudd,Flap" }, \
|
||||
"AETR", "Qhhhhh", "TimeUS,Ail,Elev,Thr,Rudd,Flap", "s-----", "F-----" }, \
|
||||
};
|
||||
|
||||
void Plane::Log_Write_Vehicle_Startup_Messages()
|
||||
|
Loading…
Reference in New Issue
Block a user