mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: add documentation for WENC, CESC, PRX, ADSB, BCN, BCL, OABR, OADF
This commit is contained in:
parent
124d8c7fdf
commit
767c010332
|
@ -1340,6 +1340,18 @@ struct PACKED log_Arm_Disarm {
|
|||
// @Field: AccY: acceleration along Y axis
|
||||
// @Field: AccZ: acceleration along Z axis
|
||||
|
||||
// @LoggerMessage: ADSB
|
||||
// @Description: Automatic Dependant Serveillance - Broadcast detected vehicle information
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: ICAO_address: Transponder address
|
||||
// @Field: Lat: Vehicle latitude
|
||||
// @Field: Lng: Vehicle longitude
|
||||
// @Field: Alt: Vehicle altitude
|
||||
// @Field: Heading: Vehicle heading
|
||||
// @Field: Hor_vel: Vehicle horizontal velocity
|
||||
// @Field: Ver_vel: Vehicle vertical velocity
|
||||
// @Field: Squark: Transponder squawk code
|
||||
|
||||
// @LoggerMessage: AHR2
|
||||
// @Description: Backup AHRS data
|
||||
// @Field: TimeUS: Time since system startup
|
||||
|
@ -1411,6 +1423,35 @@ struct PACKED log_Arm_Disarm {
|
|||
// @Field: Temp: measured temperature
|
||||
// @Field: Res: estimated temperature resistance
|
||||
|
||||
// @LoggerMessage: BCL
|
||||
// @Description: Battery cell voltage information
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Instance: battery instance number
|
||||
// @Field: Volt: battery voltage
|
||||
// @Field: V1: first cell voltage
|
||||
// @Field: V2: second cell voltage
|
||||
// @Field: V3: third cell voltage
|
||||
// @Field: V4: fourth cell voltage
|
||||
// @Field: V5: fifth cell voltage
|
||||
// @Field: V6: sixth cell voltage
|
||||
// @Field: V7: seventh cell voltage
|
||||
// @Field: V8: eighth cell voltage
|
||||
// @Field: V9: ninth cell voltage
|
||||
// @Field: V10: tenth cell voltage
|
||||
|
||||
// @LoggerMessage: BCN
|
||||
// @Description: Beacon informtaion
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Health: True if beacon sensor is healthy
|
||||
// @Field: Cnt: Number of beacons being used
|
||||
// @Field: D0: Distance to first beacon
|
||||
// @Field: D1: Distance to second beacon
|
||||
// @Field: D2: Distance to third beacon
|
||||
// @Field: D3: Distance to fouth beacon
|
||||
// @Field: PosX: Calculated beacon position, x-axis
|
||||
// @Field: PosY: Calculated beacon position, y-axis
|
||||
// @Field: PosZ: Calculated beacon position, z-axis
|
||||
|
||||
// @LoggerMessage: CAM,TRIG
|
||||
// @Description: Camera shutter information
|
||||
// @Field: TimeUS: Time since system startup
|
||||
|
@ -1425,6 +1466,17 @@ struct PACKED log_Arm_Disarm {
|
|||
// @Field: Pitch: current vehicle pitch
|
||||
// @Field: Yaw: current vehicle yaw
|
||||
|
||||
// @LoggerMessage: CESC
|
||||
// @Description: CAN ESC data
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Id: ESC identifier
|
||||
// @Field: ECnt: Error count
|
||||
// @Field: Voltage: Battery voltage measurement
|
||||
// @Field: Curr: Battery current measurement
|
||||
// @Field: Temp: Temperature
|
||||
// @Field: RPM: Measured RPM
|
||||
// @Field: Pow: Rated power output
|
||||
|
||||
// @LoggerMessage: CMD
|
||||
// @Description: Executed mission command information
|
||||
// @Field: TimeUS: Time since system startup
|
||||
|
@ -1668,6 +1720,30 @@ struct PACKED log_Arm_Disarm {
|
|||
// @Field: Id: character referenced by FMTU
|
||||
// @Field: Mult: numeric multiplier
|
||||
|
||||
// @LoggerMessage: OABR
|
||||
// @Description: Object avoidance (Bendy Ruler) diagnostics
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Active: True if Bendy Ruler avoidance is being used
|
||||
// @Field: DesYaw: Best yaw chosen to avoid obstacle
|
||||
// @Field: Yaw: Current vehicle yaw
|
||||
// @Field: Mar: Margin from path to obstacle on best yaw chosen
|
||||
// @Field: DLat: Destination latitude
|
||||
// @Field: DLng: Destination longitude
|
||||
// @Field: OALat: Intermediate location chosen for avoidance
|
||||
// @Field: OALng: Intermediate location chosen for avoidance
|
||||
|
||||
// @LoggerMessage: OADJ
|
||||
// @Description: Object avoidance (Dijkstra) diagnostics
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: State: Dijkstra avoidance library state
|
||||
// @Field: Err: Dijkstra library error condition
|
||||
// @Field: CurrPoint: Destination point in calculated path to destination
|
||||
// @Field: TotPoints: Number of points in path to destination
|
||||
// @Field: DLat: Destination latitude
|
||||
// @Field: DLng: Destination longitude
|
||||
// @Field: OALat: Object Avoidance chosen destination point latitude
|
||||
// @Field: OALng: Object Avoidance chosen destination point longitude
|
||||
|
||||
// @LoggerMessage: OF
|
||||
// @Description: Optical flow sensor data
|
||||
// @Field: TimeUS: Time since system startup
|
||||
|
@ -1734,6 +1810,22 @@ struct PACKED log_Arm_Disarm {
|
|||
// @Field: Flags: System power flags
|
||||
// @Field: Safety: Hardware Safety Switch status
|
||||
|
||||
// @LoggerMessage: PRX
|
||||
// @Description: Proximity sensor data
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Health: True if proximity sensor is healthy
|
||||
// @Field: D0: Nearest object in sector surrounding 0-degrees
|
||||
// @Field: D45: Nearest object in sector surrounding 45-degrees
|
||||
// @Field: D90: Nearest object in sector surrounding 90-degrees
|
||||
// @Field: D135: Nearest object in sector surrounding 135-degrees
|
||||
// @Field: D180: Nearest object in sector surrounding 180-degrees
|
||||
// @Field: D225: Nearest object in sector surrounding 225-degrees
|
||||
// @Field: D270: Nearest object in sector surrounding 270-degrees
|
||||
// @Field: D315: Nearest object in sector surrounding 315-degrees
|
||||
// @Field: DUp: Nearest object in upwards direction
|
||||
// @Field: CAn: Angle to closest object
|
||||
// @Field: CDis: Distance to closest object
|
||||
|
||||
// @LoggerMessage: RAD
|
||||
// @Description: Telemetry radio statistics
|
||||
// @Field: TimeUS: Time since system startup
|
||||
|
@ -1929,6 +2021,14 @@ struct PACKED log_Arm_Disarm {
|
|||
// @Field: Pitch: Pitch lean angle
|
||||
// @Field: Yaw: Yaw angle
|
||||
|
||||
// @LoggerMessage: WENC
|
||||
// @Description: Wheel encoder measurements
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Dist0: First wheel distance travelled
|
||||
// @Field: Qual0: Quality measurement of Dist0
|
||||
// @Field: Dist1: Second wheel distance travelled
|
||||
// @Field: Qual1: Quality measurement of Dist1
|
||||
|
||||
// messages for all boards
|
||||
#define LOG_BASE_STRUCTURES \
|
||||
{ LOG_FORMAT_MSG, sizeof(log_Format), \
|
||||
|
|
Loading…
Reference in New Issue