diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 1259c6417c..bde0a6c38b 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -817,7 +817,8 @@ struct PACKED log_VER { // @Field: TimeUS: Time since system startup // @Field: LandingGear: Current landing gear state // @FieldValueEnum: LandingGear: AP_LandingGear::LG_LandingGear_State -// @Field: WeightOnWheels: True if there is weight on wheels +// @Field: WeightOnWheels: Weight on wheels state +// @FieldValueEnum: WeightOnWheels: AP_LandingGear::LG_WOW_State // @LoggerMessage: MAG // @Description: Information received from compasses @@ -901,8 +902,20 @@ struct PACKED log_VER { // @Field: Value: parameter value // @Field: Default: default parameter value for this board and config -// @LoggerMessage: PIDR,PIDP,PIDY,PIDA,PIDS,PIDN,PIDE -// @Description: Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Altitude/Steering +// @LoggerMessage: PIDR +// @Description: Proportional/Integral/Derivative gain values for Roll rate +// @LoggerMessage: PIDP +// @Description: Proportional/Integral/Derivative gain values for Pitch rate +// @LoggerMessage: PIDY +// @Description: Proportional/Integral/Derivative gain values for Yaw rate +// @LoggerMessage: PIDA +// @Description: Proportional/Integral/Derivative gain values for vertical acceleration +// @LoggerMessage: PIDS +// @Description: Proportional/Integral/Derivative gain values for ground steering yaw rate +// @LoggerMessage: PIDN +// @Description: Proportional/Integral/Derivative gain values for North/South velocity +// @LoggerMessage: PIDE +// @Description: Proportional/Integral/Derivative gain values for East/West velocity // @Field: TimeUS: Time since system startup // @Field: Tar: desired value // @Field: Act: achieved value @@ -1257,7 +1270,7 @@ LOG_STRUCTURE_FROM_MOUNT \ "SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \ LOG_STRUCTURE_FROM_AVOIDANCE \ { LOG_SIMSTATE_MSG, sizeof(log_AHRS), \ - "SIM","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4", "sddhmDU????", "FBBB0GG????", true }, \ + "SIM","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4", "sddhmDU----", "FBBB0GG0000", true }, \ { LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \ "TERR","QBLLHffHHf","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded,ROfs", "s-DU-mm--m", "F-GG-00--0", true }, \ LOG_STRUCTURE_FROM_ESC_TELEM \