mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Logger: add documentation for MAV and PARM
This commit is contained in:
parent
6f685b8ac5
commit
1770199c41
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user