Copter: add CTUN log information

This commit is contained in:
Peter Barker 2020-03-20 16:37:55 +11:00 committed by Peter Barker
parent 1065317332
commit 1fbace608d

View File

@ -453,6 +453,22 @@ const struct LogStructure Copter::log_structure[] = {
LOG_COMMON_STRUCTURES,
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----" },
// @LoggerMessage: CTUN
// @Description: Control Tuning information
// @Field: TimeUS: microseconds since system startup
// @Field: ThI: throttle input
// @Field: ThO: throttle output
// @Field: ThH: calculated hover throttle
// @Field: DAlt: desired altitude
// @Field: Alt: achieved altitude
// @Field: BAlt: barometric altitude
// @Field: DSAlt: desired rangefinder altitude
// @Field: SAlt: achived rangefinder altitude
// @Field: TAlt: terrain altitude
// @Field: DCRt: desired climb rate
// @Field: CRt: climb rate
{ 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" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),