From 1770199c4124bf6758b413c9441c778eff01b441 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Apr 2020 08:37:53 +1100 Subject: [PATCH] AP_Logger: add documentation for MAV and PARM --- libraries/AP_Logger/LogStructure.h | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 668f70f024..f7364d76b7 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -1402,6 +1402,16 @@ struct PACKED log_Arm_Disarm { // @Field: Health: true if the compass is considered healthy // @Field: S: time measurement was taken +// @LoggerMessage: MAV +// @Description: GCS MAVLink link statistics +// @Field: TimeUS: microseconds since system startup +// @Field: chan: mavlink channel number +// @Field: txp: transmitted packet count +// @Field: rxp: received packet count +// @Field: rxdp: perceived number of packets we never received +// @Field: flags: compact representation of some stage of the channel +// @Field: ss: stream slowdown is the number of ms being added to each message to fit within bandwidth + // @LoggerMessage: MODE // @Description: vehicle control mode information // @Field: TimeUS: microseconds since system startup @@ -1415,6 +1425,12 @@ struct PACKED log_Arm_Disarm { // @Field: Id: character referenced by FMTU // @Field: Mult: numeric multiplier +// @LoggerMessage: PARM +// @Description: parameter value +// @Field: TimeUS: microseconds since system startup +// @Field: Name: parameter name +// @Field: Value: parameter vlaue + // @LoggerMessage: PIDR,PIDP,PIDY,PIDA,PIDS // @Description: Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Z/Steering // @Field: TimeUS: microseconds since system startup