mirror of https://github.com/ArduPilot/ardupilot
Copter: fix CTUN log msg TAlt scaling
This commit is contained in:
parent
0af830bbb7
commit
b16d0740c8
|
@ -457,7 +457,7 @@ const struct LogStructure Copter::log_structure[] = {
|
|||
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
|
||||
"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----" },
|
||||
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
||||
"CTUN", "Qffffffefffhhf", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt,N", "s----mmmmmmnnz", "F----00B0BBBB-" },
|
||||
"CTUN", "Qffffffefffhhf", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt,N", "s----mmmmmmnnz", "F----00B0B0BB-" },
|
||||
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
||||
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
|
||||
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
|
||||
|
|
Loading…
Reference in New Issue