Onboard Message Log Messages

This is a list of log messages which may be present in logs produced and stored onboard ArduPilot vehicles.

ACC

IMU accelerometer data

TimeUS

μs

Time since system startup

I

instance

accelerometer sensor instance number

SampleUS

μs

time since system startup this sample was taken

AccX

m/s/s

acceleration along X axis

AccY

m/s/s

acceleration along Y axis

AccZ

m/s/s

acceleration along Z axis

ADSB

Automatic Dependent Serveillance - Broadcast detected vehicle information

TimeUS

μs

Time since system startup

ICAO_address

Transponder address

Lat

1e-7 deglatitude

Vehicle latitude

Lng

1e-7 deglongitude

Vehicle longitude

Alt

mm

Vehicle altitude

Heading

cdegheading

Vehicle heading

Hor_vel

mm/s

Vehicle horizontal velocity

Ver_vel

mm/s

Vehicle vertical velocity

Squark

Transponder squawk code

AHR2

Backup AHRS data

TimeUS

μs

Time since system startup

Roll

deg

Estimated roll

Pitch

deg

Estimated pitch

Yaw

degheading

Estimated yaw

Alt

m

Estimated altitude

Lat

deglatitude

Estimated latitude

Lng

deglongitude

Estimated longitude

Q1

Estimated attitude quaternion component 1

Q2

Estimated attitude quaternion component 2

Q3

Estimated attitude quaternion component 3

Q4

Estimated attitude quaternion component 4

AIS1

Contents of ‘position report’ AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_types_1_2_and_3_position_report_class_a

US

μs

Time since system startup

typ

Message Type

rep

Repeat Indicator

mmsi

MMSI

nav

Navigation Status

rot

Rate of Turn (ROT)

sog

Speed Over Ground (SOG)

pos

Position Accuracy

lon

Longitude

lat

Latitude

cog

Course Over Ground (COG)

hed

True Heading (HDG)

sec

Time Stamp

man

Maneuver Indicator

raim

RAIM flag

rad

Radio status

AIS4

Contents of ‘Base Station Report’ AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_type_4_base_station_report

US

μs

Time since system startup

rep

Repeat Indicator

mmsi

MMSI

year

Year (UTC)

mth

Month (UTC)

day

Day (UTC)

h

Hour (UTC)

m

Minute (UTC)

s

Second (UTC)

fix

Fix quality

lon

Longitude

lat

Latitude

epfd

Type of EPFD

raim

RAIM flag

rad

Radio status

AIS5

Contents of ‘static and voyage related data’ AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_type_5_static_and_voyage_related_data

US

μs

Time since system startup

rep

Repeat Indicator

mmsi

MMSI

ver

AIS Version

imo

IMO Number

cal

char[16]

Call Sign

nam

char[64]

Vessel Name

typ

Ship Type

bow

m

Dimension to Bow

stn

m

Dimension to Stern

prt

m

Dimension to Port

str

m

Dimension to Starboard

fix

Position Fix Type

dght

dm

Draught

dst

char[64]

Destination

dte

DTE

AISR

Raw AIS AVDIM messages contents, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_aivdmaivdo_sentence_layer

TimeUS

μs

Time since system startup

num

count of fragments in the currently accumulating message

total

fragment number of this sentence

ID

sequential message ID for multi-sentence messages

payload

char[64]

data payload

AOA

Angle of attack and Side Slip Angle values

TimeUS

μs

Time since system startup

AOA

deg

Angle of Attack calculated from airspeed, wind vector,velocity vector

SSA

deg

Side Slip Angle calculated from airspeed, wind vector,velocity vector

ARM

Arming status changes

TimeUS

μs

Time since system startup

ArmState

true if vehicle is now armed

ArmChecks

bitmask

arming bitmask at time of arming Bitmask values:

ARMING_CHECK_ALL

1

ARMING_CHECK_BARO

2

ARMING_CHECK_COMPASS

4

ARMING_CHECK_GPS

8

ARMING_CHECK_INS

16

ARMING_CHECK_PARAMETERS

32

ARMING_CHECK_RC

64

ARMING_CHECK_VOLTAGE

128

ARMING_CHECK_BATTERY

256

ARMING_CHECK_AIRSPEED

512

ARMING_CHECK_LOGGING

1024

ARMING_CHECK_SWITCH

2048

ARMING_CHECK_GPS_CONFIG

4096

ARMING_CHECK_SYSTEM

8192

ARMING_CHECK_MISSION

16384

ARMING_CHECK_RANGEFINDER

32768

ARMING_CHECK_CAMERA

65536

ARMING_CHECK_AUX_AUTH

131072

ARMING_CHECK_VISION

262144

ARMING_CHECK_FFT

524288

ARMING_CHECK_OSD

1048576

Forced

true if arm/disarm was forced

Method

enum

method used for arming Values:

RUDDER

0

MAVLINK

1

AUXSWITCH

2

MOTORTEST

3

SCRIPTING

4

TERMINATION

5

only disarm uses this…

CPUFAILSAFE

6

only disarm uses this…

BATTERYFAILSAFE

7

only disarm uses this…

SOLOPAUSEWHENLANDED

8

only disarm uses this…

AFS

9

only disarm uses this…

ADSBCOLLISIONACTION

10

only disarm uses this…

PARACHUTE_RELEASE

11

only disarm uses this…

CRASH

12

only disarm uses this…

LANDED

13

only disarm uses this…

MISSIONEXIT

14

only disarm uses this…

FENCEBREACH

15

only disarm uses this…

RADIOFAILSAFE

16

only disarm uses this…

DISARMDELAY

17

only disarm uses this…

GCSFAILSAFE

18

only disarm uses this…

TERRRAINFAILSAFE

19

only disarm uses this…

FAILSAFE_ACTION_TERMINATE

20

only disarm uses this…

TERRAINFAILSAFE

21

only disarm uses this…

MOTORDETECTDONE

22

only disarm uses this…

BADFLOWOFCONTROL

23

only disarm uses this…

EKFFAILSAFE

24

only disarm uses this…

GCS_FAILSAFE_SURFACEFAILED

25

only disarm uses this…

GCS_FAILSAFE_HOLDFAILED

26

only disarm uses this…

TAKEOFFTIMEOUT

27

only disarm uses this…

AUTOLANDED

28

only disarm uses this…

PILOT_INPUT_FAILSAFE

29

only disarm uses this…

TOYMODELANDTHROTTLE

30

only disarm uses this…

TOYMODELANDFORCE

31

only disarm uses this…

LANDING

32

only disarm uses this…

DEADRECKON_FAILSAFE

33

only disarm uses this…

BLACKBOX

34

DDS

35

UNKNOWN

100

ARSP

Airspeed sensor data

TimeUS

μs

Time since system startup

I

instance

Airspeed sensor instance number

Airspeed

m/s

Current airspeed

DiffPress

Pa

Pressure difference between static and dynamic port

Temp

degC

Temperature used for calculation

RawPress

Pa

Raw pressure less offset

Offset

Pa

Offset from parameter

U

True if sensor is being used

H

True if sensor is healthy

Hp

Probability sensor is healthy

TR

innovation test ratio

Pri

True if sensor is the primary sensor

ASM1

AirSim simulation data

TimeUS

Time since system startup

TUS

Simulation’s timestamp

R

Simulation’s roll

P

Simulation’s pitch

Y

Simulation’s yaw

GX

Simulated gyroscope, X-axis

GY

Simulated gyroscope, Y-axis

GZ

Simulated gyroscope, Z-axis

ASM2

More AirSim simulation data

TimeUS

Time since system startup

AX

simulation’s acceleration, X-axis

AY

simulation’s acceleration, Y-axis

AZ

simulation’s acceleration, Z-axis

VX

simulation’s velocity, X-axis

VY

simulation’s velocity, Y-axis

VZ

simulation’s velocity, Z-axis

PX

simulation’s position, X-axis

PY

simulation’s position, Y-axis

PZ

simulation’s position, Z-axis

Alt

simulation’s gps altitude

SD

simulation’s earth-frame speed-down

ATDE

AutoTune data packet

TimeUS

μs

Time since system startup

Angle

deg

current angle

Rate

deg/s

current angular rate

ATSC

Scale factors for attitude controller

TimeUS

μs

Time since system startup

AngPScX

Angle P scale X

AngPScY

Angle P scale Y

AngPScZ

Angle P scale Z

PDScX

PD scale X

PDScY

PD scale Y

PDScZ

PD scale Z

ATT

Canonical vehicle attitude

TimeUS

μs

Time since system startup

DesRoll

deg

vehicle desired roll

Roll

deg

achieved vehicle roll

DesPitch

deg

vehicle desired pitch

Pitch

deg

achieved vehicle pitch

DesYaw

degheading

vehicle desired yaw

Yaw

degheading

achieved vehicle yaw

ErrRP

deg

lowest estimated gyro drift error

ErrYaw

degheading

difference between measured yaw and DCM yaw estimate

AEKF

active EKF type

AUXF

Auxiliary function invocation information

TimeUS

μs

Time since system startup

function

instance

ID of triggered function Values:

DO_NOTHING

0

aux switch disabled

FLIP

2

flip

SIMPLE_MODE

3

change to simple mode

RTL

4

change to RTL flight mode

SAVE_TRIM

5

save current position as level

SAVE_WP

7

save mission waypoint or RTL if in auto mode

CAMERA_TRIGGER

9

trigger camera servo or relay

RANGEFINDER

10

allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground

FENCE

11

allow enabling or disabling fence in flight

RESETTOARMEDYAW

12

UNUSED

SUPERSIMPLE_MODE

13

change to simple mode in middle, super simple at top

ACRO_TRAINER

14

low = disabled, middle = leveled, high = leveled and limited

SPRAYER

15

enable/disable the crop sprayer

AUTO

16

change to auto flight mode

AUTOTUNE

17

auto tune

LAND

18

change to LAND flight mode

GRIPPER

19

Operate cargo grippers low=off, middle=neutral, high=on

PARACHUTE_ENABLE

21

Parachute enable/disable

PARACHUTE_RELEASE

22

Parachute release

PARACHUTE_3POS

23

Parachute disable, enable, release with 3 position switch

MISSION_RESET

24

Reset auto mission to start from first command

ATTCON_FEEDFWD

25

enable/disable the roll and pitch rate feed forward

ATTCON_ACCEL_LIM

26

enable/disable the roll, pitch and yaw accel limiting

RETRACT_MOUNT1

27

Retract Mount1

RELAY

28

Relay pin on/off (only supports first relay)

LANDING_GEAR

29

Landing gear controller

LOST_VEHICLE_SOUND

30

Play lost vehicle sound

MOTOR_ESTOP

31

Emergency Stop Switch

MOTOR_INTERLOCK

32

Motor On/Off switch

BRAKE

33

Brake flight mode

RELAY2

34

Relay2 pin on/off

RELAY3

35

Relay3 pin on/off

RELAY4

36

Relay4 pin on/off

THROW

37

change to THROW flight mode

AVOID_ADSB

38

enable AP_Avoidance library

PRECISION_LOITER

39

enable precision loiter

AVOID_PROXIMITY

40

enable object avoidance using proximity sensors (ie. horizontal lidar)

ARMDISARM_UNUSED

41

UNUSED

SMART_RTL

42

change to SmartRTL flight mode

INVERTED

43

enable inverted flight

WINCH_ENABLE

44

winch enable/disable

WINCH_CONTROL

45

winch control

RC_OVERRIDE_ENABLE

46

enable RC Override

USER_FUNC1

47

user function #1

USER_FUNC2

48

user function #2

USER_FUNC3

49

user function #3

LEARN_CRUISE

50

learn cruise throttle (Rover)

MANUAL

51

manual mode

ACRO

52

acro mode

STEERING

53

steering mode

HOLD

54

hold mode

GUIDED

55

guided mode

LOITER

56

loiter mode

FOLLOW

57

follow mode

CLEAR_WP

58

clear waypoints

SIMPLE

59

simple mode

ZIGZAG

60

zigzag mode

ZIGZAG_SaveWP

61

zigzag save waypoint

COMPASS_LEARN

62

learn compass offsets

SAILBOAT_TACK

63

rover sailboat tack

REVERSE_THROTTLE

64

reverse throttle input

GPS_DISABLE

65

disable GPS for testing

RELAY5

66

Relay5 pin on/off

RELAY6

67

Relay6 pin on/off

STABILIZE

68

stabilize mode

POSHOLD

69

poshold mode

ALTHOLD

70

althold mode

FLOWHOLD

71

flowhold mode

CIRCLE

72

circle mode

DRIFT

73

drift mode

SAILBOAT_MOTOR_3POS

74

Sailboat motoring 3pos

SURFACE_TRACKING

75

Surface tracking upwards or downwards

STANDBY

76

Standby mode

TAKEOFF

77

takeoff

RUNCAM_CONTROL

78

control RunCam device

RUNCAM_OSD_CONTROL

79

control RunCam OSD

VISODOM_ALIGN

80

align visual odometry camera’s attitude to AHRS

DISARM

81

disarm vehicle

Q_ASSIST

82

disable, enable and force Q assist

ZIGZAG_Auto

83

zigzag auto switch

AIRMODE

84

enable / disable airmode for copter

GENERATOR

85

generator control

TER_DISABLE

86

disable terrain following in CRUISE/FBWB modes

CROW_SELECT

87

select CROW mode for diff spoilers;high disables,mid forces progressive

SOARING

88

three-position switch to set soaring mode

LANDING_FLARE

89

force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up

EKF_POS_SOURCE

90

change EKF position source between primary, secondary and tertiary sources

ARSPD_CALIBRATE

91

calibrate airspeed ratio

FBWA

92

Fly-By-Wire-A

RELOCATE_MISSION

93

used in separate branch MISSION_RELATIVE

VTX_POWER

94

VTX power level

FBWA_TAILDRAGGER

95

enables FBWA taildragger takeoff mode. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA.

MODE_SWITCH_RESET

96

trigger re-reading of mode switch

WIND_VANE_DIR_OFSSET

97

flag for windvane direction offset input, used with windvane type 2

TRAINING

98

mode training

AUTO_RTL

99

AUTO RTL via DO_LAND_START

KILL_IMU1

100

disable first IMU (for IMU failure testing)

KILL_IMU2

101

disable second IMU (for IMU failure testing)

CAM_MODE_TOGGLE

102

Momentary switch to cycle camera modes

EKF_LANE_SWITCH

103

trigger lane switch attempt

EKF_YAW_RESET

104

trigger yaw reset attempt

GPS_DISABLE_YAW

105

disable GPS yaw for testing

DISABLE_AIRSPEED_USE

106

equivalent to AIRSPEED_USE 0

FW_AUTOTUNE

107

fixed wing auto tune

QRTL

108

QRTL mode

CUSTOM_CONTROLLER

109

use Custom Controller

KILL_IMU3

110

disable third IMU (for IMU failure testing)

LOWEHEISER_STARTER

111

allows for manually running starter

AHRS_TYPE

112

change AHRS_EKF_TYPE

CRUISE

150

CRUISE mode

TURTLE

151

Turtle mode - flip over after crash

SIMPLE_HEADING_RESET

152

reset simple mode reference heading to current

ARMDISARM

153

arm or disarm vehicle

ARMDISARM_AIRMODE

154

arm or disarm vehicle enabling airmode

TRIM_TO_CURRENT_SERVO_RC

155

trim to current servo and RC

TORQEEDO_CLEAR_ERR

156

clear torqeedo error

EMERGENCY_LANDING_EN

157

Force long FS action to FBWA for landing out of range

OPTFLOW_CAL

158

optical flow calibration

FORCEFLYING

159

enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_max

WEATHER_VANE_ENABLE

160

enable/disable weathervaning

TURBINE_START

161

initialize turbine start sequence

FFT_NOTCH_TUNE

162

FFT notch tuning function

MOUNT_LOCK

163

Mount yaw lock vs follow

LOG_PAUSE

164

Pauses logging if under logging rate control

ARM_EMERGENCY_STOP

165

ARM on high, MOTOR_ESTOP on low

CAMERA_REC_VIDEO

166

start recording on high, stop recording on low

CAMERA_ZOOM

167

camera zoom high = zoom in, middle = hold, low = zoom out

CAMERA_MANUAL_FOCUS

168

camera manual focus. high = long shot, middle = stop focus, low = close shot

CAMERA_AUTO_FOCUS

169

camera auto focus

QSTABILIZE

170

QuadPlane QStabilize mode

MAG_CAL

171

Calibrate compasses (disarmed only)

BATTERY_MPPT_ENABLE

172

Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs.

PLANE_AUTO_LANDING_ABORT

173

Abort Glide-slope or VTOL landing during payload place or do_land type mission items

CAMERA_IMAGE_TRACKING

174

camera image tracking

CAMERA_LENS

175

camera lens selection

VFWD_THR_OVERRIDE

176

force enabled VTOL forward throttle method

MOUNT_LRF_ENABLE

177

mount LRF enable/disable

FLIGHTMODE_PAUSE

178

e.g. pause movement towards waypoint

ROLL

201

roll input

PITCH

202

pitch input

THROTTLE

203

throttle pilot input

YAW

204

yaw pilot input

MAINSAIL

207

mainsail input

FLAP

208

flap input

FWD_THR

209

VTOL manual forward throttle

AIRBRAKE

210

manual airbrake control

WALKING_HEIGHT

211

walking robot height input

MOUNT1_ROLL

212

mount1 roll input

MOUNT1_PITCH

213

mount1 pitch input

MOUNT1_YAW

214

mount1 yaw input

MOUNT2_ROLL

215

mount2 roll input

MOUNT2_PITCH

216

mount3 pitch input

MOUNT2_YAW

217

mount4 yaw input

LOWEHEISER_THROTTLE

218

allows for throttle on slider

SCRIPTING_1

300

SCRIPTING_2

301

SCRIPTING_3

302

SCRIPTING_4

303

SCRIPTING_5

304

SCRIPTING_6

305

SCRIPTING_7

306

SCRIPTING_8

307

AUX_FUNCTION_MAX

308

pos

enum

switch position when function triggered Values:

LOW

0

indicates auxiliary switch is in the low position (pwm <1200)

MIDDLE

1

indicates auxiliary switch is in the middle position (pwm >1200, <1800)

HIGH

2

indicates auxiliary switch is in the high position (pwm >1800)

source

enum

source of auxiliary function invocation Values:

INIT

0

RC

1

BUTTON

2

MAVLINK

3

MISSION

4

SCRIPTING

5

result

true if function was successful

BARD

Barometer dynamic data

TimeUS

μs

Time since system startup

I

instance

barometer sensor instance number

DynPrX

Pa

calculated dynamic pressure in the bodyframe X-axis

DynPrY

Pa

calculated dynamic pressure in the bodyframe Y-axis

DynPrZ

Pa

calculated dynamic pressure in the bodyframe Z-axis

BARO

Gathered Barometer data

TimeUS

μs

Time since system startup

I

instance

barometer sensor instance number

Alt

m

calculated altitude

Press

Pa

measured atmospheric pressure

Temp

degC

measured atmospheric temperature

CRt

m/s

derived climb rate from primary barometer

SMS

ms

time last sample was taken

Offset

m

raw adjustment of barometer altitude, zeroed on calibration, possibly set by GCS

GndTemp

degC

temperature on ground, specified by parameter or measured while on ground

Health

true if barometer is considered healthy

BAT

Gathered battery data

TimeUS

μs

Time since system startup

Inst

instance

battery instance number

Volt

V

measured voltage

VoltR

V

estimated resting voltage

Curr

A

measured current

CurrTot

mAh

consumed Ah, current * time

EnrgTot

W.h

consumed Wh, energy this battery has expended

Temp

degC

measured temperature

Res

Ohm

estimated battery resistance

RemPct

%

remaining percentage

H

health

SH

%

state of health percentage. 0 if unknown

BCL

Battery cell voltage information

TimeUS

μs

Time since system startup

Instance

instance

battery instance number

Volt

V

battery voltage

V1

mV

first cell voltage

V2

mV

second cell voltage

V3

mV

third cell voltage

V4

mV

fourth cell voltage

V5

mV

fifth cell voltage

V6

mV

sixth cell voltage

V7

mV

seventh cell voltage

V8

mV

eighth cell voltage

V9

mV

ninth cell voltage

V10

mV

tenth cell voltage

V11

mV

eleventh cell voltage

V12

mV

twelfth cell voltage

BCL2

Battery cell voltage information

TimeUS

μs

Time since system startup

Instance

instance

battery instance number

V13

mV

thirteenth cell voltage

V14

mV

fourteenth cell voltage

BCN

Beacon information

TimeUS

μs

Time since system startup

Health

True if beacon sensor is healthy

Cnt

Number of beacons being used

D0

m

Distance to first beacon

D1

m

Distance to second beacon

D2

m

Distance to third beacon

D3

m

Distance to fourth beacon

PosX

m

Calculated beacon position, x-axis

PosY

m

Calculated beacon position, y-axis

PosZ

m

Calculated beacon position, z-axis

CAM

Camera shutter information

TimeUS

μs

Time since system startup

I

instance

Instance number

Img

Image number

GPSTime

milliseconds since start of GPS week

GPSWeek

weeks since 5 Jan 1980

Lat

deglatitude

current latitude

Lng

deglongitude

current longitude

Alt

m

current altitude

RelAlt

m

current altitude relative to home

GPSAlt

m

altitude as reported by GPS

R

deg

current vehicle roll

P

deg

current vehicle pitch

Y

deg

current vehicle yaw

CAND

Info from GetNodeInfo request

TimeUS

μs

Time since system startup

Driver

Driver index

NodeId

instance

Node ID

UID1

Hardware ID, part 1

UID2

Hardware ID, part 2

Name

char[64]

Name string

Major

major revision id

Minor

minor revision id

Version

AP_Periph git hash

CMD

Executed mission command information

TimeUS

μs

Time since system startup

CTot

Total number of mission commands

CNum

This command’s offset in mission

CId

Command type

Prm1

Parameter 1

Prm2

Parameter 2

Prm3

Parameter 3

Prm4

Parameter 4

Lat

deglatitude

Command latitude

Lng

deglongitude

Command longitude

Alt

m

Command altitude

Frame

Frame used for position

CRSE

Cruise Learn messages

TimeUS

Time since system startup

State

True if Cruise Learn has started

Speed

Determined target Cruise speed in auto missions

Throttle

Determined base throttle percentage to be used in auto missions

CSRV

Servo feedback data

TimeUS

μs

Time since system startup

Id

instance

Servo number this data relates to

Pos

Current servo position

Force

Force being applied

Speed

Current servo movement speed

Pow

%

Amount of rated power being applied

PosCmd

deg

commanded servo position

V

V

Voltage

A

A

Current

MotT

degC

motor temperature

PCBT

degC

PCB temperature

Err

error flags

CTRL

Attitude Control oscillation monitor diagnostics

TimeUS

Time since system startup

RMSRollP

LPF Root-Mean-Squared Roll Rate controller P gain

RMSRollD

LPF Root-Mean-Squared Roll rate controller D gain

RMSPitchP

LPF Root-Mean-Squared Pitch Rate controller P gain

RMSPitchD

LPF Root-Mean-Squared Pitch Rate controller D gain

RMSYaw

LPF Root-Mean-Squared Yaw Rate controller P+D gain

DMS

DataFlash-Over-MAVLink statistics

TimeUS

μs

Time since system startup

N

Current block number

Dp

Number of times we rejected a write to the backend

RT

Number of blocks sent from the retry queue

RS

Number of resends of unacknowledged data made

Fa

Average number of blocks on the free list

Fmn

Minimum number of blocks on the free list

Fmx

Maximum number of blocks on the free list

Pa

Average number of blocks on the pending list

Pmn

Minimum number of blocks on the pending list

Pmx

Maximum number of blocks on the pending list

Sa

Average number of blocks on the sent list

Smn

Minimum number of blocks on the sent list

Smx

Maximum number of blocks on the sent list

DOCK

Dock mode target information

TimeUS

μs

Time since system startup

DockX

cm

Docking Station position, X-Axis

DockY

cm

Docking Station position, Y-Axis

DockDist

m

Distance to docking station

TPosX

cm

Current Position Target, X-Axis

TPosY

cm

Current Position Target, Y-Axis

DSpd

m/s

Desired speed

DTrnRt

rad/s

Desired Turn Rate

DPTH

Depth messages on boats with downwards facing range finder

TimeUS

μs

Time since system startup

Inst

instance

Instance

Lat

deglatitude

Latitude

Lng

deglongitude

Longitude

Depth

m

Depth as detected by the sensor

Temp

degC

Temperature

DSF

Onboard logging statistics

TimeUS

μs

Time since system startup

Dp

Number of times we rejected a write to the backend

Blk

Current block number

Bytes

B

Current write offset

FMn

Minimum free space in write buffer in last time period

FMx

Maximum free space in write buffer in last time period

FAv

Average free space in write buffer in last time period

DSTL

Deepstall Landing data

TimeUS

μs

Time since system startup

Stg

Deepstall landing stage

THdg

degheading

Target heading

Lat

deglatitude

Landing point latitude

Lng

deglongitude

Landing point longitude

Alt

m

Landing point altitude

XT

Crosstrack error

Travel

Expected travel distance vehicle will travel from this point

L1I

L1 controller crosstrack integrator value

Loiter

wind estimate loiter angle flown

Des

Deepstall steering PID desired value

P

Deepstall steering PID Proportional response component

I

Deepstall steering PID Integral response component

D

Deepstall steering PID Derivative response component

EAH3

External AHRS data

TimeUS

μs

Time since system startup

Temp

deg

Temprature

Pres

Pa

Pressure

MX

Gauss

Magnetic feild X-axis

MY

Gauss

Magnetic feild Y-axis

MZ

Gauss

Magnetic feild Z-axis

AX

m/s/s

Acceleration X-axis

AY

m/s/s

Acceleration Y-axis

AZ

m/s/s

Acceleration Z-axis

GX

rad/s

Rotation rate X-axis

GY

rad/s

Rotation rate Y-axis

GZ

rad/s

Rotation rate Z-axis

Q1

Attitude quaternion 1

Q2

Attitude quaternion 2

Q3

Attitude quaternion 3

Q4

Attitude quaternion 4

EAHR

External AHRS data

TimeUS

μs

Time since system startup

Roll

deg

euler roll

Pitch

deg

euler pitch

Yaw

deg

euler yaw

VN

m/s

velocity north

VE

m/s

velocity east

VD

m/s

velocity down

Lat

deglatitude

latitude

Lon

deglongitude

longitude

Alt

m

altitude AMSL

Flg

nav status flags

ECYL

EFI per-cylinder information

TimeUS

μs

Time since system startup

Inst

instance

Cylinder this data belongs to

IgnT

deg

Ignition timing

InjT

ms

Injection time

CHT

degC

Cylinder head temperature

EGT

degC

Exhaust gas temperature

Lambda

Estimated lambda coefficient (dimensionless ratio)

CHT2

degC

Cylinder2 head temperature

EGT2

degC

Cylinder2 Exhaust gas temperature

IDX

Index of the publishing ECU

EFI

Electronic Fuel Injection system data

TimeUS

μs

Time since system startup

LP

%

Reported engine load

Rpm

rpm

Reported engine RPM

SDT

ms

Spark Dwell Time

ATM

Pa

Atmospheric pressure

IMP

Pa

Intake manifold pressure

IMT

degC

Intake manifold temperature

ECT

degC

Engine Coolant Temperature

OilP

Pa

Oil Pressure

OilT

degC

Oil temperature

FP

Pa

Fuel Pressure

FCR

Fuel Consumption Rate

CFV

Consumed fueld volume

TPS

%

Throttle Position

IDX

Index of the publishing ECU

EFI2

Electronic Fuel Injection system data - redux

TimeUS

μs

Time since system startup

Healthy

True if EFI is healthy

ES

Engine state

GE

General error

CSE

Crankshaft sensor status

TS

Temperature status

FPS

Fuel pressure status

OPS

Oil pressure status

DS

Detonation status

MS

Misfire status

DebS

Debris status

SPU

Spark plug usage

IDX

Index of the publishing ECU

EFIS

Electronic Fuel Injection data - Hirth specific Status information

TimeUS

μs

Time since system startup

ETS1

Status of EGT1 excess temperature error

ETS2

Status of EGT2 excess temperature error

CTS1

Status of CHT1 excess temperature error

CTS2

Status of CHT2 excess temperature error

ETSS

Status of Engine temperature sensor

ATSS

Status of Air temperature sensor

APSS

Status of Air pressure sensor

TSS

Status of Temperature sensor

CRCF

CRC failure count

AckF

ACK failure count

Up

Uptime between 2 messages

ThrO

Throttle output as received by the engine

ERR

Specifically coded error messages

TimeUS

μs

Time since system startup

Subsys

enum

Subsystem in which the error occurred Values:

MAIN

1

RADIO

2

COMPASS

3

OPTFLOW

4

not used

FAILSAFE_RADIO

5

FAILSAFE_BATT

6

FAILSAFE_GPS

7

not used

FAILSAFE_GCS

8

FAILSAFE_FENCE

9

FLIGHT_MODE

10

GPS

11

CRASH_CHECK

12

FLIP

13

AUTOTUNE

14

not used

PARACHUTES

15

EKFCHECK

16

FAILSAFE_EKFINAV

17

BARO

18

CPU

19

FAILSAFE_ADSB

20

TERRAIN

21

NAVIGATION

22

FAILSAFE_TERRAIN

23

EKF_PRIMARY

24

THRUST_LOSS_CHECK

25

FAILSAFE_SENSORS

26

FAILSAFE_LEAK

27

PILOT_INPUT

28

FAILSAFE_VIBE

29

INTERNAL_ERROR

30

FAILSAFE_DEADRECKON

31

ECode

Subsystem-specific error code

ESC

Feedback received from ESCs

TimeUS

μs

microseconds since system startup

Instance

instance

ESC instance number

RPM

rpm

reported motor rotation rate

RawRPM

rpm

reported motor rotation rate without slew adjustment

Volt

V

Perceived input voltage for the ESC

Curr

A

Perceived current through the ESC

Temp

degC

ESC temperature in centi-degrees C

CTot

mAh

current consumed total mAh

MotTemp

degC

measured motor temperature in centi-degrees C

Err

%

error rate

EV

Specifically coded event messages

TimeUS

μs

Time since system startup

Id

enum

Event identifier Values:

ARMED

10

DISARMED

11

AUTO_ARMED

15

LAND_COMPLETE_MAYBE

17

LAND_COMPLETE

18

NOT_LANDED

28

LOST_GPS

19

FLIP_START

21

FLIP_END

22

SET_HOME

25

SET_SIMPLE_ON

26

SET_SIMPLE_OFF

27

SET_SUPERSIMPLE_ON

29

AUTOTUNE_INITIALISED

30

AUTOTUNE_OFF

31

AUTOTUNE_RESTART

32

AUTOTUNE_SUCCESS

33

AUTOTUNE_FAILED

34

AUTOTUNE_REACHED_LIMIT

35

AUTOTUNE_PILOT_TESTING

36

AUTOTUNE_SAVEDGAINS

37

SAVE_TRIM

38

SAVEWP_ADD_WP

39

FENCE_ENABLE

41

FENCE_DISABLE

42

ACRO_TRAINER_OFF

43

ACRO_TRAINER_LEVELING

44

ACRO_TRAINER_LIMITED

45

GRIPPER_GRAB

46

GRIPPER_RELEASE

47

PARACHUTE_DISABLED

49

PARACHUTE_ENABLED

50

PARACHUTE_RELEASED

51

LANDING_GEAR_DEPLOYED

52

LANDING_GEAR_RETRACTED

53

MOTORS_EMERGENCY_STOPPED

54

MOTORS_EMERGENCY_STOP_CLEARED

55

MOTORS_INTERLOCK_DISABLED

56

MOTORS_INTERLOCK_ENABLED

57

ROTOR_RUNUP_COMPLETE

58

Heli only

ROTOR_SPEED_BELOW_CRITICAL

59

Heli only

EKF_ALT_RESET

60

LAND_CANCELLED_BY_PILOT

61

EKF_YAW_RESET

62

AVOIDANCE_ADSB_ENABLE

63

AVOIDANCE_ADSB_DISABLE

64

AVOIDANCE_PROXIMITY_ENABLE

65

AVOIDANCE_PROXIMITY_DISABLE

66

GPS_PRIMARY_CHANGED

67

ZIGZAG_STORE_A

71

ZIGZAG_STORE_B

72

LAND_REPO_ACTIVE

73

STANDBY_ENABLE

74

STANDBY_DISABLE

75

FENCE_FLOOR_ENABLE

80

FENCE_FLOOR_DISABLE

81

EK3_SOURCES_SET_TO_PRIMARY

85

EK3_SOURCES_SET_TO_SECONDARY

86

EK3_SOURCES_SET_TO_TERTIARY

87

AIRSPEED_PRIMARY_CHANGED

90

SURFACED

163

NOT_SURFACED

164

BOTTOMED

165

NOT_BOTTOMED

166

FCN

Filter Center Message - per motor

TimeUS

μs

microseconds since system startup

I

instance

instance

NF

total number of active harmonic notches

CF1

Hz

First harmonic centre frequency for motor 1

CF2

Hz

First harmonic centre frequency for motor 2

CF3

Hz

First harmonic centre frequency for motor 3

CF4

Hz

First harmonic centre frequency for motor 4

CF5

Hz

First harmonic centre frequency for motor 5

CF6

Hz

First harmonic centre frequency for motor 6

HF1

Hz

Second harmonic centre frequency for motor 1

HF2

Hz

Second harmonic centre frequency for motor 2

HF3

Hz

Second harmonic centre frequency for motor 3

HF4

Hz

Second harmonic centre frequency for motor 4

HF5

Hz

Second harmonic centre frequency for motor 5

HF6

Hz

Second harmonic centre frequency for motor 6

FCNS

Filter Center Message

TimeUS

μs

microseconds since system startup

I

instance

instance

CF

Hz

notch centre frequency

HF

Hz

2nd harmonic frequency

FILE

File data

FileName

char[16]

File name

Offset

Offset into the file of this block

Length

Length of this data block

Data

char[64]

File data of this block

FMT

Message defining the format of messages in this file

Type

unique-to-this-log identifier for message being defined

Length

B

the number of bytes taken up by this message (including all headers)

Name

char[4]

name of the message being defined

Format

char[16]

character string defining the C-storage-type of the fields in this message

Columns

char[64]

the labels of the message being defined

FMTU

Message defining units and multipliers used for fields of other messages

TimeUS

μs

Time since system startup

FmtType

numeric reference to associated FMT message

UnitIds

char[16]

each character refers to a UNIT message. The unit at an offset corresponds to the field at the same offset in FMT.Format

MultIds

char[16]

each character refers to a MULT message. The multiplier at an offset corresponds to the field at the same offset in FMT.Format

FNCE

currently loaded Geo Fence points

TimeUS

μs

Time since system startup

Tot

total number of stored items

Seq

index in current sequence

Type

point type

Lat

deglatitude

point latitude

Lng

deglongitude

point longitude

Count

vertex cound in polygon if applicable

Radius

m

radius of circle if applicable

FOLL

Follow library diagnostic data

TimeUS

μs

Time since system startup

Lat

deglatitude

Target latitude

Lon

deglongitude

Target longitude

Alt

cm

Target absolute altitude

VelN

m/s

Target earth-frame velocity, North

VelE

m/s

Target earth-frame velocity, East

VelD

m/s

Target earth-frame velocity, Down

LatE

deglatitude

Vehicle latitude

LonE

deglongitude

Vehicle longitude

AltE

cm

Vehicle absolute altitude

FTN

Filter Tuning Message - per motor

TimeUS

μs

microseconds since system startup

I

instance

instance

NDn

number of active harmonic notches

NF1

Hz

desired harmonic notch centre frequency for motor 1

NF2

Hz

desired harmonic notch centre frequency for motor 2

NF3

Hz

desired harmonic notch centre frequency for motor 3

NF4

Hz

desired harmonic notch centre frequency for motor 4

NF5

Hz

desired harmonic notch centre frequency for motor 5

NF6

Hz

desired harmonic notch centre frequency for motor 6

NF7

Hz

desired harmonic notch centre frequency for motor 7

NF8

Hz

desired harmonic notch centre frequency for motor 8

NF9

Hz

desired harmonic notch centre frequency for motor 9

NF10

Hz

desired harmonic notch centre frequency for motor 10

NF11

Hz

desired harmonic notch centre frequency for motor 11

NF12

Hz

desired harmonic notch centre frequency for motor 12

FTN1

FFT Filter Tuning

TimeUS

μs

microseconds since system startup

PkAvg

Hz

peak noise frequency as an energy-weighted average of roll and pitch peak frequencies

BwAvg

Hz

bandwidth of weighted peak frequency where edges are determined by FFT_ATT_REF

SnX

signal-to-noise ratio on the roll axis

SnY

signal-to-noise ratio on the pitch axis

SnZ

signal-to-noise ratio on the yaw axis

FtX

%

harmonic fit on roll of the highest noise peak to the second highest noise peak

FtY

%

harmonic fit on pitch of the highest noise peak to the second highest noise peak

FtZ

%

harmonic fit on yaw of the highest noise peak to the second highest noise peak

FHX

FFT health, X-axis

FHY

FFT health, Y-axis

FHZ

FFT health, Z-axis

Tc

μs

FFT cycle time

FTN2

FFT Noise Frequency Peak

TimeUS

μs

microseconds since system startup

Id

instance

peak id where 0 is the centre peak, 1 is the lower shoulder and 2 is the upper shoulder

PkX

Hz

noise frequency of the peak on roll

PkY

Hz

noise frequency of the peak on pitch

PkZ

Hz

noise frequency of the peak on yaw

BwX

Hz

bandwidth of the peak frequency on roll where edges are determined by FFT_ATT_REF

BwY

Hz

bandwidth of the peak frequency on pitch where edges are determined by FFT_ATT_REF

BwZ

Hz

bandwidth of the peak frequency on yaw where edges are determined by FFT_ATT_REF

SnX

signal-to-noise ratio on the roll axis

SnY

signal-to-noise ratio on the pitch axis

SnZ

signal-to-noise ratio on the yaw axis

EnX

power spectral density bin energy of the peak on roll

EnY

power spectral density bin energy of the peak on roll

EnZ

power spectral density bin energy of the peak on roll

FTNS

Filter Tuning Message

TimeUS

μs

microseconds since system startup

I

instance

instance

NF

Hz

desired harmonic notch centre frequency

GPA

GPS accuracy information

I

μs

GPS instance number

TimeUS

instance

Time since system startup

VDop

vertical degree of procession

HAcc

m

horizontal position accuracy

VAcc

m

vertical position accuracy

SAcc

m/s

speed accuracy

YAcc

deg

yaw accuracy

VV

true if vertical velocity is available

SMS

ms

time since system startup this sample was taken

Delta

ms

system time delta between the last two reported positions

Und

m

Undulation

RTCMFU

RTCM fragments used

RTCMFD

RTCM fragments discarded

GPS

Information received from GNSS systems attached to the autopilot

TimeUS

μs

Time since system startup

I

instance

GPS instance number

Status

enum

GPS Fix type; 2D fix, 3D fix etc. Values:

NO_GPS

0

No GPS connected/detected

NO_FIX

1

Receiving valid GPS messages but no lock

GPS_OK_FIX_2D

2

Receiving valid messages and 2D lock

GPS_OK_FIX_3D

3

Receiving valid messages and 3D lock

GPS_OK_FIX_3D_DGPS

4

Receiving valid messages and 3D lock with differential improvements

GPS_OK_FIX_3D_RTK_FLOAT

5

Receiving valid messages and 3D RTK Float

GPS_OK_FIX_3D_RTK_FIXED

6

Receiving valid messages and 3D RTK Fixed

GMS

ms

milliseconds since start of GPS Week

GWk

weeks since 5 Jan 1980

NSats

satellites

number of satellites visible

HDop

horizontal precision

Lat

deglatitude

latitude

Lng

deglongitude

longitude

Alt

m

altitude

Spd

m/s

ground speed

GCrs

degheading

ground course

VZ

m/s

vertical speed

Yaw

degheading

vehicle yaw

U

boolean value indicating whether this GPS is in use

GPYW

GPS Yaw

TimeUS

μs

Time since system startup

Id

instance

instance

RHD

deg

reported heading,deg

RDist

m

antenna separation,m

RDown

m

vertical antenna separation,m

MinCDown

m

minimum tolerable vertical antenna separation,m

MaxCDown

m

maximum tolerable vertical antenna separation,m

OK

1 if have yaw

GRAW

Raw uBlox data

TimeUS

μs

Time since system startup

WkMS

ms

receiver TimeOfWeek measurement

Week

GPS week

numSV

satellites

number of space vehicles seen

sv

space vehicle number of first vehicle

cpMes

carrier phase measurement

prMes

pseudorange measurement

doMes

Doppler measurement

mesQI

measurement quality index

cno

carrier-to-noise density ratio

lli

loss of lock indicator

GRXH

Raw uBlox data - header

TimeUS

μs

Time since system startup

rcvTime

receiver TimeOfWeek measurement

week

GPS week

leapS

GPS leap seconds

numMeas

number of space-vehicle measurements to follow

recStat

receiver tracking status bitfield

GRXS

Raw uBlox data - space-vehicle data

TimeUS

μs

Time since system startup

prMes

Pseudorange measurement

cpMes

Carrier phase measurement

doMes

Doppler measurement

gnss

GNSS identifier

sv

Satellite identifier

freq

GLONASS frequency slot

lock

carrier phase locktime counter

cno

carrier-to-noise density ratio

prD

estimated pseudorange measurement standard deviation

cpD

estimated carrier phase measurement standard deviation

doD

estimated Doppler measurement standard deviation

trk

tracking status bitfield

GUIP

Guided mode target information

TimeUS

μs

Time since system startup

Type

Type of guided mode

pX

m

Target position, X-Axis

pY

m

Target position, Y-Axis

pZ

m

Target position, Z-Axis

vX

m/s

Target velocity, X-Axis

vY

m/s

Target velocity, Y-Axis

vZ

m/s

Target velocity, Z-Axis

GYR

IMU gyroscope data

TimeUS

μs

Time since system startup

I

instance

gyroscope sensor instance number

SampleUS

μs

time since system startup this sample was taken

GyrX

rad/s

measured rotation rate about X axis

GyrY

rad/s

measured rotation rate about Y axis

GyrZ

rad/s

measured rotation rate about Z axis

HEAT

IMU Heater data

TimeUS

Time since system startup

Temp

Current IMU temperature

Targ

Target IMU temperature

P

Proportional portion of response

I

Integral portion of response

Out

Controller output to heating element

HYGR

Hygrometer data

TimeUS

μs

Time since system startup

Id

instance

sensor ID

Humidity

%

percentage humidity

Temp

degC

temperature in degrees C

ICMB

ICM20789 diagnostics

TimeUS

Time since system startup

Traw

raw temperature from sensor

Praw

raw pressure from sensor

P

pressure

T

temperature

ILB1

InertialLabs AHRS data1

TimeUS

μs

Time since system startup

PosVarN

m

position variance north

PosVarE

m

position variance east

PosVarD

m

position variance down

VelVarN

m/s

velocity variance north

VelVarE

m/s

velocity variance east

VelVarD

m/s

velocity variance down

ILB2

InertialLabs AHRS data3

TimeUS

μs

Time since system startup

Stat1

unit status1

Stat2

unit status2

FType

fix type

SpStat

spoofing status

GI1

GNSS Info1

GI2

GNSS Info2

GJS

GNSS jamming status

TAS

true airspeed

WVN

Wind velocity north

WVE

Wind velocity east

WVD

Wind velocity down

IMU

Inertial Measurement Unit data

TimeUS

μs

Time since system startup

I

instance

IMU sensor instance number

GyrX

rad/s

measured rotation rate about X axis

GyrY

rad/s

measured rotation rate about Y axis

GyrZ

rad/s

measured rotation rate about Z axis

AccX

m/s/s

acceleration along X axis

AccY

m/s/s

acceleration along Y axis

AccZ

m/s/s

acceleration along Z axis

EG

gyroscope error count

EA

accelerometer error count

T

degC

IMU temperature

GH

gyroscope health

AH

accelerometer health

GHz

Hz

gyroscope measurement rate

AHz

Hz

accelerometer measurement rate

IOMC

IOMCU diagnostic information

TimeUS

Time since system startup

RSErr

Status Read error count (zeroed on successful read)

Mem

Free memory

TS

IOMCU uptime

NPkt

Number of packets received by IOMCU

Nerr

Protocol failures on MCU side

Nerr2

Reported number of failures on IOMCU side

NDel

Number of delayed packets received by MCU

JSN1

Log data received from JSON simulator

TimeUS

μs

Time since system startup (us)

TStamp

s

Simulation’s timestamp (s)

R

rad

Simulation’s roll (rad)

P

rad

Simulation’s pitch (rad)

Y

rad

Simulation’s yaw (rad)

GX

rad/s

Simulated gyroscope, X-axis (rad/sec)

GY

rad/s

Simulated gyroscope, Y-axis (rad/sec)

GZ

rad/s

Simulated gyroscope, Z-axis (rad/sec)

JSN2

Log data received from JSON simulator

TimeUS

μs

Time since system startup (us)

VN

m/s

simulation’s velocity, North-axis (m/s)

VE

m/s

simulation’s velocity, East-axis (m/s)

VD

m/s

simulation’s velocity, Down-axis (m/s)

AX

m/s/s

simulation’s acceleration, X-axis (m/s^2)

AY

m/s/s

simulation’s acceleration, Y-axis (m/s^2)

AZ

m/s/s

simulation’s acceleration, Z-axis (m/s^2)

AN

m/s/s

simulation’s acceleration, North (m/s^2)

AE

m/s/s

simulation’s acceleration, East (m/s^2)

AD

m/s/s

simulation’s acceleration, Down (m/s^2)

LAND

Slope Landing data

TimeUS

Time since system startup

stage

progress through landing sequence

f1

Landing flags

f2

Slope-specific landing flags

slope

Slope to landing point

slopeInit

Initial slope to landing point

altO

Rangefinder correction

fh

Height for flare timing.

LGR

Landing gear information

TimeUS

Time since system startup

LandingGear

enum

Current landing gear state Values:

LG_UNKNOWN

-1

LG_RETRACTED

0

LG_DEPLOYED

1

LG_RETRACTING

2

LG_DEPLOYING

3

WeightOnWheels

enum

Weight on wheels state Values:

LG_WOW_UNKNOWN

-1

LG_NO_WOW

0

LG_WOW

1

MAG

Information received from compasses

TimeUS

μs

Time since system startup

I

instance

magnetometer sensor instance number

MagX

mGauss

magnetic field strength in body frame

MagY

mGauss

magnetic field strength in body frame

MagZ

mGauss

magnetic field strength in body frame

OfsX

mGauss

magnetic field offset in body frame

OfsY

mGauss

magnetic field offset in body frame

OfsZ

mGauss

magnetic field offset in body frame

MOX

mGauss

motor interference magnetic field offset in body frame

MOY

mGauss

motor interference magnetic field offset in body frame

MOZ

mGauss

motor interference magnetic field offset in body frame

Health

true if the compass is considered healthy

S

μs

time measurement was taken

MAGH

Magnetometer high resolution data

TimeUS

Time since system startup

Node

CAN node

Sensor

sensor ID on node

Bus

CAN bus

Mx

X axis field

My

y axis field

Mz

z axis field

MAV

GCS MAVLink link statistics

TimeUS

μs

Time since system startup

chan

instance

mavlink channel number

txp

transmitted packet count

rxp

received packet count

rxdp

perceived number of packets we never received

flags

bitmask

compact representation of some stage of the channel Bitmask values:

USING_SIGNING

1

ACTIVE

2

STREAMING

4

PRIVATE

8

LOCKED

16

ss

ms

stream slowdown is the number of ms being added to each message to fit within bandwidth

tf

times buffer was full when a message was going to be sent

MAVC

MAVLink command we have just executed

TimeUS

μs

Time since system startup

TS

target system for command

TC

target component for command

SS

source system for command

SC

source component for command

Fr

command frame

Cmd

mavlink command enum value

P1

first parameter from mavlink packet

P2

second parameter from mavlink packet

P3

third parameter from mavlink packet

P4

fourth parameter from mavlink packet

X

X coordinate from mavlink packet

Y

Y coordinate from mavlink packet

Z

Z coordinate from mavlink packet

Res

command result being returned from autopilot

WL

true if this command arrived via a COMMAND_LONG rather than COMMAND_INT

MCU

MCU voltage and temprature monitering

TimeUS

μs

Time since system startup

MTemp

degC

Temperature

MVolt

V

Voltage

MVmin

V

Voltage min

MVmax

V

Voltage max

MMO

MMC3416 compass data

TimeUS

Time since system startup

Nx

new measurement X axis

Ny

new measurement Y axis

Nz

new measurement Z axis

Ox

new offset X axis

Oy

new offset Y axis

Oz

new offset Z axis

MNT

Mount’s desired and actual roll, pitch and yaw angles

TimeUS

μs

Time since system startup

I

instance

Instance number

DRoll

deg

Desired roll

Roll

deg

Actual roll

DPitch

deg

Desired pitch

Pitch

deg

Actual pitch

DYawB

deg

Desired yaw in body frame

YawB

deg

Actual yaw in body frame

DYawE

deg

Desired yaw in earth frame

YawE

deg

Actual yaw in earth frame

Dist

m

Rangefinder distance

MODE

vehicle control mode information

TimeUS

μs

Time since system startup

Mode

vehicle-specific mode number

ModeNum

alias for Mode

Rsn

enum

reason for entering this mode; enumeration value Values:

UNKNOWN

0

RC_COMMAND

1

GCS_COMMAND

2

RADIO_FAILSAFE

3

BATTERY_FAILSAFE

4

GCS_FAILSAFE

5

EKF_FAILSAFE

6

GPS_GLITCH

7

MISSION_END

8

THROTTLE_LAND_ESCAPE

9

FENCE_BREACHED

10

TERRAIN_FAILSAFE

11

BRAKE_TIMEOUT

12

FLIP_COMPLETE

13

AVOIDANCE

14

AVOIDANCE_RECOVERY

15

THROW_COMPLETE

16

TERMINATE

17

TOY_MODE

18

CRASH_FAILSAFE

19

SOARING_FBW_B_WITH_MOTOR_RUNNING

20

SOARING_THERMAL_DETECTED

21

SOARING_THERMAL_ESTIMATE_DETERIORATED

22

VTOL_FAILED_TRANSITION

23

VTOL_FAILED_TAKEOFF

24

FAILSAFE

25

general failsafes, prefer specific failsafes over this as much as possible

INITIALISED

26

SURFACE_COMPLETE

27

BAD_DEPTH

28

LEAK_FAILSAFE

29

SERVOTEST

30

STARTUP

31

SCRIPTING

32

UNAVAILABLE

33

AUTOROTATION_START

34

AUTOROTATION_BAILOUT

35

SOARING_ALT_TOO_HIGH

36

SOARING_ALT_TOO_LOW

37

SOARING_DRIFT_EXCEEDED

38

RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL

39

RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND

40

MISSION_CMD

41

FRSKY_COMMAND

42

FENCE_RETURN_PREVIOUS_MODE

43

QRTL_INSTEAD_OF_RTL

44

AUTO_RTL_EXIT

45

LOITER_ALT_REACHED_QLAND

46

LOITER_ALT_IN_VTOL

47

RADIO_FAILSAFE_RECOVERY

48

QLAND_INSTEAD_OF_RTL

49

DEADRECKON_FAILSAFE

50

MODE_TAKEOFF_FAILSAFE

51

DDS_COMMAND

52

MON

Main loop performance monitoring message.

TimeUS

μs

Time since system startup

Dly

Loop delay so far

Tsk

Current task

IErr

Internal error mask

IErrCnt

Count of internal error occurances

IErrLn

Internal Error line

MM

MAVLink message currently being processed

MC

MAVLink command currently being processed

SmLn

If semaphore taken, line of semaphore take call

SPICnt

count of SPI transactions

I2CCnt

count of i2c transactions

MOTB

Motor mixer information

TimeUS

μs

Time since system startup

LiftMax

Maximum motor compensation gain

BatVolt

Ratio between detected battery voltage and maximum battery voltage

ThLimit

Throttle limit set due to battery current limitations

ThrAvMx

Maximum average throttle that can be used to maintain attitude control, derived from throttle mix params

ThrOut

Throttle output

FailFlags

bit 0 motor failed, bit 1 motors balanced, should be 2 in normal flight

MSG

Textual messages

TimeUS

μs

Time since system startup

Message

char[64]

message text

MULT

Message mapping from single character to numeric multiplier

TimeUS

μs

Time since system startup

Id

character referenced by FMTU

Mult

numeric multiplier

NKF0

EKF2 beacon sensor diagnostics

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

ID

Beacon sensor ID

rng

m

Beacon range

innov

Beacon range innovation

SIV

sqrt of beacon range innovation variance

TR

Beacon range innovation consistency test ratio

BPN

m

Beacon north position

BPE

m

Beacon east position

BPD

m

Beacon down position

OFH

m

High estimate of vertical position offset of beacons rel to EKF origin

OFL

m

Low estimate of vertical position offset of beacons rel to EKF origin

OFN

m

always zero

OFE

m

always zero

OFD

m

always zero

NKF1

EKF2 estimator outputs

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

Roll

deg

Estimated roll

Pitch

deg

Estimated pitch

Yaw

degheading

Estimated yaw

VN

m/s

Estimated velocity (North component)

VE

m/s

Estimated velocity (East component)

VD

m/s

Estimated velocity (Down component)

dPD

m/s

Filtered derivative of vertical position (down)

PN

m

Estimated distance from origin (North component)

PE

m

Estimated distance from origin (East component)

PD

m

Estimated distance from origin (Down component)

GX

deg/s

Estimated gyro bias, X axis

GY

deg/s

Estimated gyro bias, Y axis

GZ

deg/s

Estimated gyro bias, Z axis

OH

m

Height of origin above WGS-84

NKF2

EKF2 estimator secondary outputs

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

AZbias

Estimated accelerometer Z bias

GSX

Gyro Scale Factor (X-axis)

GSY

Gyro Scale Factor (Y-axis)

GSZ

Gyro Scale Factor (Z-axis)

VWN

m/s

Estimated wind velocity (North component)

VWE

m/s

Estimated wind velocity (East component)

MN

mGauss

Magnetic field strength (North component)

ME

mGauss

Magnetic field strength (East component)

MD

mGauss

Magnetic field strength (Down component)

MX

mGauss

Magnetic field strength (body X-axis)

MY

mGauss

Magnetic field strength (body Y-axis)

MZ

mGauss

Magnetic field strength (body Z-axis)

MI

Magnetometer used for data

NKF3

EKF2 innovations

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

IVN

m/s

Innovation in velocity (North component)

IVE

m/s

Innovation in velocity (East component)

IVD

m/s

Innovation in velocity (Down component)

IPN

m

Innovation in position (North component)

IPE

m

Innovation in position (East component)

IPD

m

Innovation in position (Down component)

IMX

mGauss

Innovation in magnetic field strength (X-axis component)

IMY

mGauss

Innovation in magnetic field strength (Y-axis component)

IMZ

mGauss

Innovation in magnetic field strength (Z-axis component)

IYAW

deg

Innovation in vehicle yaw

IVT

UNKNOWN

Innovation in true-airspeed

RErr

Accumulated relative error of this core with respect to active primary core

ErSc

A consolidated error score where higher numbers are less healthy

NKF4

EKF2 variances SV, SP, SH and SM are probably best described as ‘Squared Innovation Test Ratios’ where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK2_MAG_I_GATE, EK2_HGT_I_GATE, etc

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

SV

Square root of the velocity variance

SP

Square root of the position variance

SH

Square root of the height variance

SM

Magnetic field variance

SVT

tilt error convergence metric

errRP

Filtered error in roll/pitch estimate

OFN

m

Most recent position reset (North component)

OFE

m

Most recent position reset (East component)

FS

Filter fault status

TS

Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement)

SS

Filter solution status

GPS

Filter GPS status

PI

Primary core index

NKF5

EKF2 Sensor innovations (primary core) and general dumping ground

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

NI

Normalised flow variance

FIX

Optical flow LOS rate vector innovations from the main nav filter (X-axis)

FIY

Optical flow LOS rate vector innovations from the main nav filter (Y-axis)

AFI

Optical flow LOS rate innovation from terrain offset estimator

HAGL

m

Height above ground level

offset

UNKNOWN

Estimated vertical position of the terrain relative to the nav filter zero datum

RI

UNKNOWN

Range finder innovations

rng

UNKNOWN

Measured range

Herr

m

Filter ground offset state error

eAng

rad

Magnitude of angular error

eVel

m/s

Magnitude of velocity error

ePos

m

Magnitude of position error

NKQ

EKF2 quaternion defining the rotation from NED to XYZ (autopilot) axes

TimeUS

μs

Time since system startup

C

instance

EKF2 core this data is for

Q1

Quaternion a term

Q2

Quaternion b term

Q3

Quaternion c term

Q4

Quaternion d term

NKT

EKF2 timing information

TimeUS

μs

Time since system startup

C

instance

EKF core this message instance applies to

Cnt

s

count of samples used to create this message

IMUMin

s

smallest IMU sample interval

IMUMax

s

largest IMU sample interval

EKFMin

s

low-passed achieved average time step rate for the EKF (minimum)

EKFMax

s

low-passed achieved average time step rate for the EKF (maximum)

AngMin

s

accumulated measurement time interval for the delta angle (minimum)

AngMax

s

accumulated measurement time interval for the delta angle (maximum)

VMin

s

accumulated measurement time interval for the delta velocity (minimum)

VMax

s

accumulated measurement time interval for the delta velocity (maximum)

NKY0

EKF Yaw Estimator States

TimeUS

μs

Time since system startup

C

instance

EKF core this data is for

YC

degheading

GSF yaw estimate (deg)

YCS

deg

GSF yaw estimate 1-Sigma uncertainty (deg)

Y0

degheading

Yaw estimate from individual EKF filter 0 (deg)

Y1

degheading

Yaw estimate from individual EKF filter 1 (deg)

Y2

degheading

Yaw estimate from individual EKF filter 2 (deg)

Y3

degheading

Yaw estimate from individual EKF filter 3 (deg)

Y4

degheading

Yaw estimate from individual EKF filter 4 (deg)

W0

Weighting applied to yaw estimate from individual EKF filter 0

W1

Weighting applied to yaw estimate from individual EKF filter 1

W2

Weighting applied to yaw estimate from individual EKF filter 2

W3

Weighting applied to yaw estimate from individual EKF filter 3

W4

Weighting applied to yaw estimate from individual EKF filter 4

NKY1

EKF Yaw Estimator Innovations

TimeUS

μs

Time since system startup

C

instance

EKF core this data is for

IVN0

m/s

North velocity innovation from individual EKF filter 0 (m/s)

IVN1

m/s

North velocity innovation from individual EKF filter 1 (m/s)

IVN2

m/s

North velocity innovation from individual EKF filter 2 (m/s)

IVN3

m/s

North velocity innovation from individual EKF filter 3 (m/s)

IVN4

m/s

North velocity innovation from individual EKF filter 4 (m/s)

IVE0

m/s

East velocity innovation from individual EKF filter 0 (m/s)

IVE1

m/s

East velocity innovation from individual EKF filter 1 (m/s)

IVE2

m/s

East velocity innovation from individual EKF filter 2 (m/s)

IVE3

m/s

East velocity innovation from individual EKF filter 3 (m/s)

IVE4

m/s

East velocity innovation from individual EKF filter 4 (m/s)

NTUN

Navigation Tuning information - e.g. vehicle destination

TimeUS

μs

Time since system startup

WpDist

m

distance to the current navigation waypoint

WpBrg

degheading

bearing to the current navigation waypoint

DesYaw

degheading

the vehicle’s desired heading

Yaw

cdegheading

the vehicle’s current heading

XTrack

m

the vehicle’s current distance from the current travel segment

OABR

Object avoidance (Bendy Ruler) diagnostics

TimeUS

μs

Time since system startup

Type

Type of BendyRuler currently active

Act

True if Bendy Ruler avoidance is being used

DYaw

deg

Best yaw chosen to avoid obstacle

Yaw

deg

Current vehicle yaw

DP

deg

Desired pitch chosen to avoid obstacle

RChg

True if BendyRuler resisted changing bearing and continued in last calculated bearing

Mar

m

Margin from path to obstacle on best yaw chosen

DLt

deglatitude

Destination latitude

DLg

deglongitude

Destination longitude

DAlt

cm

Desired alt above EKF Origin

OLt

deglatitude

Intermediate location chosen for avoidance

OLg

deglongitude

Intermediate location chosen for avoidance

OAlt

cm

Intermediate alt chosen for avoidance above EKF origin

OADJ

Object avoidance (Dijkstra) diagnostics

TimeUS

μs

Time since system startup

State

Dijkstra avoidance library state

Err

Dijkstra library error condition

CurrPoint

Destination point in calculated path to destination

TotPoints

Number of points in path to destination

DLat

deglatitude

Destination latitude

DLng

deglongitude

Destination longitude

OALat

deglatitude

Object Avoidance chosen destination point latitude

OALng

deglongitude

Object Avoidance chosen destination point longitude

OAVG

Object avoidance path planning visgraph points

TimeUS

μs

Time since system startup

version

Visgraph version, increments each time the visgraph is re-generated

point_num

point number in visgraph

Lat

deglatitude

Latitude

Lon

deglongitude

longitude

OF

Optical flow sensor data

TimeUS

μs

Time since system startup

Qual

Estimated sensor data quality

flowX

rad/s

Sensor flow rate, X-axis

flowY

rad/s

Sensor flow rate,Y-axis

bodyX

m/s

derived rotational velocity, X-axis

bodyY

m/s

derived rotational velocity, Y-axis

OFCA

Optical Flow Calibration sample

TimeUS

μs

Time since system startup

Axis

instance

Axis (X=0 Y=1)

Num

Sample number

FRate

rad/s

Flow rate

BRate

rad/s

Body rate

LPred

rad/s

Los pred

ORGN

Vehicle navigation origin or other notable position

TimeUS

μs

Time since system startup

Type

instance

Position type Values:

ekf_origin

0

ahrs_home

1

Lat

deglatitude

Position latitude

Lng

deglongitude

Position longitude

Alt

m

Position altitude

PARM

parameter value

TimeUS

μs

Time since system startup

Name

char[16]

parameter name

Value

parameter value

Default

default parameter value for this board and config

PIDA

Proportional/Integral/Derivative gain values for vertical acceleration

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PIDE

Proportional/Integral/Derivative gain values for East/West velocity

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PIDN

Proportional/Integral/Derivative gain values for North/South velocity

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PIDP

Proportional/Integral/Derivative gain values for Pitch rate

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PIDR

Proportional/Integral/Derivative gain values for Roll rate

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PIDS

Proportional/Integral/Derivative gain values for ground steering yaw rate

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PIDY

Proportional/Integral/Derivative gain values for Yaw rate

TimeUS

μs

Time since system startup

Tar

desired value

Act

achieved value

Err

error between target and achieved

P

proportional part of PID

I

integral part of PID

D

derivative part of PID

FF

controller feed-forward portion of response

DFF

controller derivative feed-forward portion of response

Dmod

scaler applied to D gain to reduce limit cycling

SRate

slew rate used in slew limiter

Flags

bitmask

bitmask of PID state flags Bitmask values:

LIMIT

1

true if the output is saturated, I term anti windup is active

PD_SUM_LIMIT

2

true if the PD sum limit is active

RESET

4

true if the controller was reset

I_TERM_SET

8

true if the I term has been set externally including reseting to 0

PL

Precision Landing messages

TimeUS

μs

Time since system startup

Heal

True if Precision Landing is healthy

TAcq

True if landing target is detected

pX

cm

Target position relative to vehicle, X-Axis (0 if target not found)

pY

cm

Target position relative to vehicle, Y-Axis (0 if target not found)

vX

cm/s

Target velocity relative to vehicle, X-Axis (0 if target not found)

vY

cm/s

Target velocity relative to vehicle, Y-Axis (0 if target not found)

mX

cm

Target’s relative to origin position as 3-D Vector, X-Axis

mY

cm

Target’s relative to origin position as 3-D Vector, Y-Axis

mZ

cm

Target’s relative to origin position as 3-D Vector, Z-Axis

LastMeasMS

ms

Time when target was last detected

EKFOutl

EKF’s outlier count

Est

Type of estimator used

PM

autopilot system performance and general data dumping ground

TimeUS

μs

Time since system startup

LR

Hz

Main loop rate

NLon

Number of long loops detected

NL

Number of measurement loops for this message

MaxT

Maximum loop time

Mem

B

Free memory available

Load

d%

System processor load

IntE

bitmask

Internal error mask; which internal errors have been detected Bitmask values:

logger_mapfailure

1

logger_missing_logstructure

2

logger_logwrite_missingfmt

4

logger_too_many_deletions

8

logger_bad_getfilename

16

panic

32

logger_flushing_without_sem

64

logger_bad_current_block

128

logger_blockcount_mismatch

256

logger_dequeue_failure

512

constraining_nan

1024

watchdog_reset

2048

iomcu_reset

4096

iomcu_fail

8192

spi_fail

16384

main_loop_stuck

32768

gcs_bad_missionprotocol_link

65536

bitmask_range

131072

gcs_offset

262144

i2c_isr

524288

flow_of_control

1048576

switch_full_sector_recursion

2097152

bad_rotation

4194304

stack_overflow

8388608

imu_reset

16777216

gpio_isr

33554432

mem_guard

67108864

dma_fail

134217728

params_restored

268435456

invalid_arg_or_result

536870912

__LAST__

1073741824

ErrL

Internal error line number; last line number on which a internal error was detected

ErrC

Internal error count; how many internal errors have been detected

SPIC

Number of SPI transactions processed

I2CC

Number of i2c transactions processed

I2CI

Number of i2c interrupts serviced

Ex

μs

number of microseconds being added to each loop to address scheduler overruns

POS

Canonical vehicle position

TimeUS

μs

Time since system startup

Lat

deglatitude

Canonical vehicle latitude

Lng

deglongitude

Canonical vehicle longitude

Alt

m

Canonical vehicle altitude

RelHomeAlt

m

Canonical vehicle altitude relative to home

RelOriginAlt

m

Canonical vehicle altitude relative to navigation origin

POWR

System power information

TimeUS

μs

Time since system startup

Vcc

V

Flight board voltage

VServo

V

Servo rail voltage

Flags

bitmask

System power flags Bitmask values:

BRICK_VALID

1

main brick power supply valid

SERVO_VALID

2

main servo power supply valid for FMU

USB_CONNECTED

4

USB power is connected

PERIPH_OVERCURRENT

8

peripheral supply is in over-current state

PERIPH_HIPOWER_OVERCURRENT

16

hi-power peripheral supply is in over-current state

CHANGED

32

Power status has changed since boot

AccFlags

bitmask

Accumulated System power flags; all flags which have ever been set Bitmask values:

BRICK_VALID

1

main brick power supply valid

SERVO_VALID

2

main servo power supply valid for FMU

USB_CONNECTED

4

USB power is connected

PERIPH_OVERCURRENT

8

peripheral supply is in over-current state

PERIPH_HIPOWER_OVERCURRENT

16

hi-power peripheral supply is in over-current state

CHANGED

32

Power status has changed since boot

Safety

Hardware Safety Switch status

PRTN

Plane Parameter Tuning data

TimeUS

Time since system startup

Set

Parameter set being tuned

Parm

Parameter being tuned

Value

Current parameter value

CenterValue

Center value (startpoint of current modifications) of parameter being tuned

PRX

Proximity Filtered sensor data

TimeUS

μs

Time since system startup

Layer

instance

Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged.

He

True if proximity sensor is healthy

D0

m

Nearest object in sector surrounding 0-degrees

D45

m

Nearest object in sector surrounding 45-degrees

D90

m

Nearest object in sector surrounding 90-degrees

D135

m

Nearest object in sector surrounding 135-degrees

D180

m

Nearest object in sector surrounding 180-degrees

D225

m

Nearest object in sector surrounding 225-degrees

D270

m

Nearest object in sector surrounding 270-degrees

D315

m

Nearest object in sector surrounding 315-degrees

DUp

m

Nearest object in upwards direction

CAn

degheading

Angle to closest object

CDis

m

Distance to closest object

PRXR

Proximity Raw sensor data

TimeUS

μs

Time since system startup

Layer

instance

Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged.

D0

m

Nearest object in sector surrounding 0-degrees

D45

m

Nearest object in sector surrounding 45-degrees

D90

m

Nearest object in sector surrounding 90-degrees

D135

m

Nearest object in sector surrounding 135-degrees

D180

m

Nearest object in sector surrounding 180-degrees

D225

m

Nearest object in sector surrounding 225-degrees

D270

m

Nearest object in sector surrounding 270-degrees

D315

m

Nearest object in sector surrounding 315-degrees

PSCD

Position Control Down

TimeUS

μs

Time since system startup

TPD

m

Target position relative to EKF origin

PD

m

Position relative to EKF origin

DVD

m/s

Desired velocity Down

TVD

m/s

Target velocity Down

VD

m/s

Velocity Down

DAD

m/s/s

Desired acceleration Down

TAD

m/s/s

Target acceleration Down

AD

m/s/s

Acceleration Down

PSCE

Position Control East

TimeUS

μs

Time since system startup

TPE

m

Target position relative to EKF origin

PE

m

Position relative to EKF origin

DVE

m/s

Desired velocity East

TVE

m/s

Target velocity East

VE

m/s

Velocity East

DAE

m/s/s

Desired acceleration East

TAE

m/s/s

Target acceleration East

AE

m/s/s

Acceleration East

PSCN

Position Control North

TimeUS

μs

Time since system startup

TPN

m

Target position relative to EKF origin

PN

m

Position relative to EKF origin

DVN

m/s

Desired velocity North

TVN

m/s

Target velocity North

VN

m/s

Velocity North

DAN

m/s/s

Desired acceleration North

TAN

m/s/s

Target acceleration North

AN

m/s/s

Acceleration North

RAD

Telemetry radio statistics

TimeUS

μs

Time since system startup

RSSI

RSSI

RemRSSI

RSSI reported from remote radio

TxBuf

number of bytes in radio ready to be sent

Noise

local noise floor

RemNoise

local noise floor reported from remote radio

RxErrors

damaged packet count

Fixed

fixed damaged packet count

RALY

Rally point information

TimeUS

μs

Time since system startup

Tot

total number of rally points onboard

Seq

this rally point’s sequence number

Lat

deglatitude

latitude of rally point

Lng

deglongitude

longitude of rally point

Alt

cm

altitude of rally point

Flags

altitude frame flags

RATE

Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes.

TimeUS

μs

Time since system startup

RDes

deg/s

vehicle desired roll rate

R

deg/s

achieved vehicle roll rate

ROut

normalized output for Roll

PDes

deg/s

vehicle desired pitch rate

P

deg/s

vehicle pitch rate

POut

normalized output for Pitch

Y

deg/s

achieved vehicle yaw rate

YOut

deg/s

normalized output for Yaw

YDes

vehicle desired yaw rate

ADes

cm/s/s

desired vehicle vertical acceleration

A

cm/s/s

achieved vehicle vertical acceleration

AOut

percentage of vertical thrust output current being used

AOutSlew

vertical thrust output slew rate

RBCH

Replay Data Beacon Header

RBCI

Replay Data Beacon Instance

RBOH

Replay body odometry data

RBRH

Replay Data Barometer Header

RBRI

Replay Data Barometer Instance

RCDA

Raw RC data

TimeUS

Time since system startup

TS

data arrival timestamp

Prot

Protocol currently being decoded

Len

Number of valid bytes in message

U0

first quartet of bytes

U1

second quartet of bytes

U2

third quartet of bytes

U3

fourth quartet of bytes

U4

fifth quartet of bytes

U5

sixth quartet of bytes

U6

seventh quartet of bytes

U7

eight quartet of bytes

U8

ninth quartet of bytes

U9

tenth quartet of bytes

RCI2

(More) RC input channels to vehicle

TimeUS

μs

Time since system startup

C15

us

channel 15 input

C16

us

channel 16 input

OMask

bitmask of RC channels being overridden by mavlink input

Flags

bitmask

bitmask of RC state flags Bitmask values:

HAS_VALID_INPUT

1

true if the system is receiving good RC values

IN_RC_FAILSAFE

2

true if the system is current in RC failsafe

RCIN

RC input channels to vehicle

TimeUS

μs

Time since system startup

C1

us

channel 1 input

C2

us

channel 2 input

C3

us

channel 3 input

C4

us

channel 4 input

C5

us

channel 5 input

C6

us

channel 6 input

C7

us

channel 7 input

C8

us

channel 8 input

C9

us

channel 9 input

C10

us

channel 10 input

C11

us

channel 11 input

C12

us

channel 12 input

C13

us

channel 13 input

C14

us

channel 14 input

RCO2

Servo channel output values 15 to 18

TimeUS

μs

Time since system startup

C15

us

channel 15 output

C16

us

channel 16 output

C17

us

channel 17 output

C18

us

channel 18 output

RCO3

Servo channel output values 19 to 32

TimeUS

μs

Time since system startup

C19

us

channel 19 output

C20

us

channel 20 output

C21

us

channel 21 output

C22

us

channel 22 output

C23

us

channel 23 output

C24

us

channel 24 output

C25

us

channel 25 output

C26

us

channel 26 output

C27

us

channel 27 output

C28

us

channel 28 output

C29

us

channel 29 output

C30

us

channel 30 output

C31

us

channel 31 output

C32

us

channel 32 output

RCOU

Servo channel output values 1 to 14

TimeUS

μs

Time since system startup

C1

us

channel 1 output

C2

us

channel 2 output

C3

us

channel 3 output

C4

us

channel 4 output

C5

us

channel 5 output

C6

us

channel 6 output

C7

us

channel 7 output

C8

us

channel 8 output

C9

us

channel 9 output

C10

us

channel 10 output

C11

us

channel 11 output

C12

us

channel 12 output

C13

us

channel 13 output

C14

us

channel 14 output

REPH

Replay external position data

REV2

Replay Event

REVH

Replay external position data

REY3

Replay Euler Yaw event

RFND

Rangefinder sensor information

TimeUS

μs

Time since system startup

Instance

instance

rangefinder instance number this data is from

Dist

m

Reported distance from sensor

Stat

enum

Sensor state Values:

NotConnected

0

NoData

1

OutOfRangeLow

2

OutOfRangeHigh

3

Good

4

Orient

Sensor orientation

Quality

%

Signal quality. -1 means invalid, 0 is no signal, 100 is perfect signal

RGPH

Replay Data GPS Header

RGPI

Replay Data GPS Instance, infrequently changing data

RGPJ

Replay Data GPS Instance - rapidly changing data

RMGH

Replay Data Magnetometer Header

RMGI

Replay Data Magnetometer Instance

ROFH

Replay optical flow data

RPM

Data from RPM sensors

TimeUS

μs

Time since system startup

rpm1

rpm

First sensor’s data

rpm2

rpm

Second sensor’s data

RRNH

Replay Data Rangefinder Header

RRNI

Replay Data Rangefinder Instance

RSLL

Replay Set Lat Lng event

RSO2

Replay Set Origin event

RSSI

Received Signal Strength Indicator for RC receiver

TimeUS

μs

Time since system startup

RXRSSI

RSSI

RXLQ

%

RX Link Quality

RVOH

Replay Data Visual Odometry data

RWA2

Replay set-default-airspeed event

RWOH

Replay wheel odometry data

SA

Simple Avoidance messages

TimeUS

μs

Time since system startup

State

True if Simple Avoidance is active

DVelX

m/s

Desired velocity, X-Axis (Velocity before Avoidance)

DVelY

m/s

Desired velocity, Y-Axis (Velocity before Avoidance)

DVelZ

m/s

Desired velocity, Z-Axis (Velocity before Avoidance)

MVelX

m/s

Modified velocity, X-Axis (Velocity after Avoidance)

MVelY

m/s

Modified velocity, Y-Axis (Velocity after Avoidance)

MVelZ

m/s

Modified velocity, Z-Axis (Velocity after Avoidance)

Back

True if vehicle is backing away

SAIL

Sailboat information

TimeUS

μs

Time since system startup

Tack

Current tack, 0 = port, 1 = starboard

TackThr

deg

Apparent wind angle used for tack threshold

MainOut

%

Normalized mainsail output

WingOut

%

Normalized wingsail output

MastRotOut

%

Normalized direct-rotation mast output

VMG

m/s

Velocity made good (speed at which vehicle is making progress directly towards destination)

SBPH

Swift Health Data

TimeUS

μs

Time since system startup

CrcError

Number of packet CRC errors on serial connection

LastInject

Timestamp of last raw data injection to GPS

IARhyp

Current number of integer ambiguity hypotheses

SBRH

Swift Raw Message Data

TimeUS

μs

Time since system startup

msg_flag

Swift message type

1

Sender ID

2

index; always 1

3

pages; number of pages received

4

msg length; number of bytes received

5

unused; always zero

6

data received from device

SCR

Scripting runtime stats

TimeUS

μs

Time since system startup

Name

instance

script name

Runtime

μs

run time

Total_mem

B

total memory usage of all scripts

Run_mem

B

run memory usage

SCVE

Debug message for SCurve internal error

TimeUS

μs

Time since system startup

Sm

duration of the raised cosine jerk profile

Jm

maximum value of the raised cosine jerk profile

V0

initial velocity magnitude

Am

maximum constant acceleration

Vm

maximum constant velocity

L

Length of the path

Jm_out

maximum value of the raised cosine jerk profile

tj_out

segment duration

t2_out

segment duration

t4_out

segment duration

t6_out

segment duration

SIM

SITL simulator state

TimeUS

μs

Time since system startup

Roll

deg

Simulated roll

Pitch

deg

Simulated pitch

Yaw

degheading

Simulated yaw

Alt

m

Simulated altitude

Lat

deglatitude

Simulated latitude

Lng

deglongitude

Simulated longitude

Q1

Attitude quaternion component 1

Q2

Attitude quaternion component 2

Q3

Attitude quaternion component 3

Q4

Attitude quaternion component 4

SIM2

Additional simulator state

TimeUS

Time since system startup

PN

North position from home

PE

East position from home

PD

Down position from home

VN

Velocity north

VE

Velocity east

VD

Velocity down

As

Airspeed

ASpdU

Achieved simulation speedup value

SITL

Simulation data

TimeUS

Time since system startup

VN

Velocity - North component

VE

Velocity - East component

VD

Velocity - Down component

AN

Acceleration - North component

AE

Acceleration - East component

AD

Acceleration - Down component

PN

Position - North component

PE

Position - East component

PD

Position - Down component

SLV1

Log data received from JSON simulator 1

TimeUS

μs

Time since system startup (us)

Instance

instance

Slave instance

magic

magic JSON protocol key

frame_rate

Slave instance’s desired frame rate

frame_count

Slave instance’s current frame count

active

1 if the servo outputs are being used from this instance

SLV2

Log data received from JSON simulator 2

TimeUS

μs

Time since system startup

Instance

instance

Slave instance

C1

us

channel 1 output

C2

us

channel 2 output

C3

us

channel 3 output

C4

us

channel 4 output

C5

us

channel 5 output

C6

us

channel 6 output

C7

us

channel 7 output

C8

us

channel 8 output

C9

us

channel 9 output

C10

us

channel 10 output

C11

us

channel 11 output

C12

us

channel 12 output

C13

us

channel 13 output

C14

us

channel 14 output

SMOO

Smoothed sensor data fed to EKF to avoid inconsistencies

TimeUS

Time since system startup

AEx

Angular Velocity (around x-axis)

AEy

Angular Velocity (around y-axis)

AEz

Angular Velocity (around z-axis)

DPx

Velocity (along x-axis)

DPy

Velocity (along y-axis)

DPz

Velocity (along z-axis)

R

Roll

P

Pitch

Y

Yaw

R2

DCM Roll

P2

DCM Pitch

Y2

DCM Yaw

SRTL

SmartRTL statistics

TimeUS

μs

Time since system startup

Active

true if SmartRTL could be used right now

NumPts

number of points currently in use

MaxPts

maximum number of points that could be used

Action

enum

most recent internal action taken by SRTL library Values:

SRTL_POINT_ADD

0

SRTL_POINT_PRUNE

1

SRTL_POINT_SIMPLIFY

2

SRTL_ADD_FAILED_NO_SEMAPHORE

3

SRTL_ADD_FAILED_PATH_FULL

4

SRTL_POP_FAILED_NO_SEMAPHORE

5

SRTL_PEEK_FAILED_NO_SEMAPHORE

6

SRTL_DEACTIVATED_INIT_FAILED

7

SRTL_DEACTIVATED_BAD_POSITION

8

SRTL_DEACTIVATED_BAD_POSITION_TIMEOUT

9

SRTL_DEACTIVATED_PATH_FULL_TIMEOUT

10

SRTL_DEACTIVATED_PROGRAM_ERROR

11

N

m

point associated with most recent action (North component)

E

m

point associated with most recent action (East component)

D

m

point associated with most recent action (Down component)

STAK

Stack information

TimeUS

μs

Time since system startup

Id

instance

thread ID

Pri

thread priority

Total

total stack

Free

free stack

Name

char[16]

thread name

STER

Steering related messages

TimeUS

μs

Time since system startup

SteerIn

Steering input

SteerOut

Normalized steering output

DesLatAcc

m/s/s

Desired lateral acceleration

LatAcc

m/s/s

Actual lateral acceleration

DesTurnRate

deg/s

Desired turn rate

TurnRate

deg/s

Actual turn rate

TERR

Terrain database information

TimeUS

μs

Time since system startup

Status

enum

Terrain database status Values:

TerrainStatusDisabled

0

not enabled

TerrainStatusUnhealthy

1

no terrain data for current location

TerrainStatusOK

2

terrain data available

Lat

deglatitude

Current vehicle latitude

Lng

deglongitude

Current vehicle longitude

Spacing

terrain Tile spacing

TerrH

m

current Terrain height

CHeight

m

Vehicle height above terrain

Pending

Number of tile requests outstanding

Loaded

Number of tiles in memory

ROfs

m

terrain reference offset for arming altitude

THR

Throttle related messages

TimeUS

μs

Time since system startup

ThrIn

Throttle Input

ThrOut

Throttle Output

DesSpeed

m/s

Desired speed

Speed

m/s

Actual speed

AccX

m/s/s

Acceleration

TRIG

Camera shutter information

TimeUS

μs

Time since system startup

I

instance

Instance number

Img

Image number

GPSTime

milliseconds since start of GPS week

GPSWeek

weeks since 5 Jan 1980

Lat

deglatitude

current latitude

Lng

deglongitude

current longitude

Alt

m

current altitude

RelAlt

m

current altitude relative to home

GPSAlt

m

altitude as reported by GPS

R

deg

current vehicle roll

P

deg

current vehicle pitch

Y

deg

current vehicle yaw

TRMP

Torqeedo Motor Param

TimeUS

Time since system startup

RPM

Motor RPM

Pow

Motor power

Volt

Motor voltage

Cur

Motor current

ETemp

ESC Temp

MTemp

Motor Temp

TRMS

Torqeedo Motor Status

TimeUS

Time since system startup

State

Motor status flags

Err

Motor error flags

TRQD

Torqeedo Status

TimeUS

Time since system startup

Health

Health

DesMotSpeed

Desired Motor Speed (-1000 to 1000)

MotSpeed

Motor Speed (-1000 to 1000)

SuccCnt

Success Count

ErrCnt

Error Count

TRSE

Torqeedo System Setup

TimeUS

Time since system startup

Flag

Flags

MotType

Motor type

MotVer

Motor software version

BattCap

Battery capacity

BattPct

Battery charge percentage

BattType

Battery type

SwVer

Master software version

TRST

Torqeedo System State

TimeUS

Time since system startup

F

Flags bitmask

Err

Master error code

MVolt

Motor voltage

MCur

Motor current

Pow

Motor power

RPM

Motor RPM

MTemp

Motor Temp (higher of pcb or stator)

BPct

Battery charge percentage

BVolt

Battery voltage

BCur

Battery current

TSYN

Time synchronisation response information

TimeUS

μs

Time since system startup

SysID

system ID this data is for

RTT

μs

round trip time for this system

UART

UART stats

TimeUS

μs

Time since system startup

I

instance

instance

Tx

B/s

transmitted data rate bytes per second

Rx

B/s

received data rate bytes per second

UBX1

uBlox-specific GPS information (part 1)

TimeUS

μs

Time since system startup

Instance

instance

GPS instance number

noisePerMS

noise level as measured by GPS

jamInd

jamming indicator; higher is more likely jammed

aPower

antenna power indicator; 2 is don’t know

agcCnt

automatic gain control monitor

config

bitmask for messages which haven’t been seen

UBX2

uBlox-specific GPS information (part 2)

TimeUS

μs

Time since system startup

Instance

instance

GPS instance number

ofsI

imbalance of I part of complex signal

magI

magnitude of I part of complex signal

ofsQ

imbalance of Q part of complex signal

magQ

magnitude of Q part of complex signal

UBXT

uBlox specific UBX-TIM-TM2 logging, see uBlox interface description

TimeUS

μs

Time since system startup

I

instance

GPS instance number

ch

Channel (i.e. EXTINT) upon which the pulse was measured

flags

Bitmask

count

Rising edge counter

wnR

Week number of last rising edge

MsR

ms

Tow of rising edge

SubMsR

ns

Millisecond fraction of tow of rising edge in nanoseconds

wnF

Week number of last falling edge

MsF

ms

Tow of falling edge

SubMsF

ns

Millisecond fraction of tow of falling edge in nanoseconds

accEst

ns

Accuracy estimate

UNIT

Message mapping from single character to SI unit

TimeUS

μs

Time since system startup

Id

character referenced by FMTU

Label

char[64]

Unit - SI where available

VER

Ardupilot version

TimeUS

μs

Time since system startup

BT

Board type

BST

Board subtype

Maj

Major version number

Min

Minor version number

Pat

Patch number

FWT

Firmware type

GH

Github commit

FWS

char[64]

Firmware version string

APJ

Board ID

BU

Build vehicle type

FV

Filter version

VIBE

Processed (acceleration) vibration information

TimeUS

μs

Time since system startup

IMU

instance

Vibration instance number

VibeX

m/s/s

Primary accelerometer filtered vibration, x-axis

VibeY

m/s/s

Primary accelerometer filtered vibration, y-axis

VibeZ

m/s/s

Primary accelerometer filtered vibration, z-axis

Clip

Number of clipping events on 1st accelerometer

VISO

Visual Odometry

TimeUS

μs

System time

dt

μs

Time period this data covers

AngDX

rad

Angular change for body-frame roll axis

AngDY

rad

Angular change for body-frame pitch axis

AngDZ

rad

Angular change for body-frame z axis

PosDX

m

Position change for body-frame X axis (Forward-Back)

PosDY

m

Position change for body-frame Y axis (Right-Left)

PosDZ

m

Position change for body-frame Z axis (Down-Up)

conf

Confidence

VISP

Vision Position

TimeUS

μs

System time

RTimeUS

μs

Remote system time

CTimeMS

ms

Corrected system time

PX

m

Position X-axis (North-South)

PY

m

Position Y-axis (East-West)

PZ

m

Position Z-axis (Down-Up)

R

deg

Roll lean angle

P

deg

Pitch lean angle

Y

degheading

Yaw angle

PErr

m

Position estimate error

AErr

deg

Attitude estimate error

Rst

Position reset counter

Ign

Ignored

Q

%

Quality

VISV

Vision Velocity

TimeUS

μs

System time

RTimeUS

μs

Remote system time

CTimeMS

ms

Corrected system time

VX

m/s

Velocity X-axis (North-South)

VY

m/s

Velocity Y-axis (East-West)

VZ

m/s

Velocity Z-axis (Down-Up)

VErr

m/s

Velocity estimate error

Rst

Velocity reset counter

Ign

Ignored

Q

%

Quality

VSTB

Log message for video stabilisation software such as Gyroflow

TimeUS

μs

Time since system startup

GyrX

rad/s

measured rotation rate about X axis

GyrY

rad/s

measured rotation rate about Y axis

GyrZ

rad/s

measured rotation rate about Z axis

AccX

m/s/s

acceleration along X axis

AccY

m/s/s

acceleration along Y axis

AccZ

m/s/s

acceleration along Z axis

Q1

Estimated attitude quaternion component 1

Q2

Estimated attitude quaternion component 2

Q3

Estimated attitude quaternion component 3

Q4

Estimated attitude quaternion component 4

WDOG

Watchdog diagnostics

TimeUS

μs

Time since system startup

Tsk

current task number

IE

internal error mast

IEC

internal error count

IEL

line internal error was raised on

MvMsg

mavlink message being acted on

MvCmd

mavlink command being acted on

SmLn

line semaphore was taken on

FL

fault_line

FT

fault_type

FA

fault address

FP

fault thread priority

ICSR

ICS regiuster

LR

long return address

TN

char[4]

Thread name

WENC

Wheel encoder measurements

TimeUS

μs

Time since system startup

Dist0

m

First wheel distance travelled

Qual0

Quality measurement of Dist0

Dist1

m

Second wheel distance travelled

Qual1

Quality measurement of Dist1

WINC

Winch

TimeUS

μs

Time since system startup

Heal

Healthy

ThEnd

Reached end of thread

Mov

Motor is moving

Clut

Clutch is engaged (motor can move freely)

Mode

0 is Relaxed, 1 is Position Control, 2 is Rate Control

DLen

m

Desired Length

Len

m

Estimated Length

DRate

m/s

Desired Rate

Tens

UNKNOWN

Tension on line

Vcc

V

Voltage to Motor

Temp

degC

Motor temperature

WIND

Windvane readings

TimeUS

μs

Time since system startup

DrRaw

deg

raw apparent wind direction direct from sensor, in body-frame

DrApp

deg

Apparent wind direction, in body-frame

DrTru

degheading

True wind direction

SpdRaw

m/s

raw wind speed direct from sensor

SpdApp

m/s

Apparent wind Speed

SpdTru

m/s

True wind speed

XKF0

EKF3 beacon sensor diagnostics

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

ID

Beacon sensor ID

rng

m

Beacon range

innov

Beacon range innovation

SIV

sqrt of beacon range innovation variance

TR

Beacon range innovation consistency test ratio

BPN

m

Beacon north position

BPE

m

Beacon east position

BPD

m

Beacon down position

OFH

m

High estimate of vertical position offset of beacons rel to EKF origin

OFL

m

Low estimate of vertical position offset of beacons rel to EKF origin

OFN

m

North position of receiver rel to EKF origin

OFE

m

East position of receiver rel to EKF origin

OFD

m

Down position of receiver rel to EKF origin

XKF1

EKF3 estimator outputs

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

Roll

deg

Estimated roll

Pitch

deg

Estimated pitch

Yaw

degheading

Estimated yaw

VN

m/s

Estimated velocity (North component)

VE

m/s

Estimated velocity (East component)

VD

m/s

Estimated velocity (Down component)

dPD

m/s

Filtered derivative of vertical position (down)

PN

m

Estimated distance from origin (North component)

PE

m

Estimated distance from origin (East component)

PD

m

Estimated distance from origin (Down component)

GX

deg/s

Estimated gyro bias, X axis

GY

deg/s

Estimated gyro bias, Y axis

GZ

deg/s

Estimated gyro bias, Z axis

OH

m

Height of origin above WGS-84

XKF2

EKF3 estimator secondary outputs

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

AX

Estimated accelerometer X bias

AY

Estimated accelerometer Y bias

AZ

Estimated accelerometer Z bias

VWN

m/s

Estimated wind velocity (North component)

VWE

m/s

Estimated wind velocity (East component)

MN

mGauss

Magnetic field strength (North component)

ME

mGauss

Magnetic field strength (East component)

MD

mGauss

Magnetic field strength (Down component)

MX

mGauss

Magnetic field strength (body X-axis)

MY

mGauss

Magnetic field strength (body Y-axis)

MZ

mGauss

Magnetic field strength (body Z-axis)

IDX

m/s/s

Innovation in vehicle drag acceleration (X-axis component)

IDY

m/s/s

Innovation in vehicle drag acceleration (Y-axis component)

IS

rad

Innovation in vehicle sideslip

XKF3

EKF3 innovations

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

IVN

m/s

Innovation in velocity (North component)

IVE

m/s

Innovation in velocity (East component)

IVD

m/s

Innovation in velocity (Down component)

IPN

m

Innovation in position (North component)

IPE

m

Innovation in position (East component)

IPD

m

Innovation in position (Down component)

IMX

mGauss

Innovation in magnetic field strength (X-axis component)

IMY

mGauss

Innovation in magnetic field strength (Y-axis component)

IMZ

mGauss

Innovation in magnetic field strength (Z-axis component)

IYAW

deg

Innovation in vehicle yaw

IVT

UNKNOWN

Innovation in true-airspeed

RErr

Accumulated relative error of this core with respect to active primary core

ErSc

A consolidated error score where higher numbers are less healthy

XKF4

EKF3 variances. SV, SP, SH and SM are probably best described as ‘Squared Innovation Test Ratios’ where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK3_MAG_I_GATE, EK3_HGT_I_GATE, etc

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

SV

Square root of the velocity variance

SP

Square root of the position variance

SH

Square root of the height variance

SM

Magnetic field variance

SVT

Square root of the total airspeed variance

errRP

Filtered error in roll/pitch estimate

OFN

m

Most recent position reset (North component)

OFE

m

Most recent position reset (East component)

FS

Filter fault status

TS

Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement, 5:drag measurement)

SS

Filter solution status

GPS

Filter GPS status

PI

Primary core index

XKF5

EKF3 Sensor innovations (primary core) and general dumping ground

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

NI

Normalised flow variance

FIX

Optical flow LOS rate vector innovations from the main nav filter (X-axis)

FIY

Optical flow LOS rate vector innovations from the main nav filter (Y-axis)

AFI

Optical flow LOS rate innovation from terrain offset estimator

HAGL

m

Height above ground level

offset

UNKNOWN

Estimated vertical position of the terrain relative to the nav filter zero datum

RI

UNKNOWN

Range finder innovations

rng

UNKNOWN

Measured range

Herr

m

Filter ground offset state error

eAng

rad

Magnitude of angular error

eVel

m/s

Magnitude of velocity error

ePos

m

Magnitude of position error

XKFD

EKF3 Body Frame Odometry errors

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

IX

Innovation in velocity (X-axis)

IY

Innovation in velocity (Y-axis)

IZ

Innovation in velocity (Z-axis)

IVX

Variance in velocity (X-axis)

IVY

Variance in velocity (Y-axis)

IVZ

Variance in velocity (Z-axis)

XKFM

EKF3 diagnostic data for on-ground-and-not-moving check

TimeUS

μs

Time since system startup

C

instance

EKF core this message instance applies to

OGNM

True of on ground and not moving

GLR

Gyroscope length ratio

ALR

Accelerometer length ratio

GDR

Gyroscope rate of change ratio

ADR

Accelerometer rate of change ratio

XKFS

EKF3 sensor selection

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

MI

compass selection index

BI

barometer selection index

GI

GPS selection index

AI

airspeed selection index

SS

Source Set (primary=0/secondary=1/tertiary=2)

XKQ

EKF3 quaternion defining the rotation from NED to XYZ (autopilot) axes

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

Q1

Quaternion a term

Q2

Quaternion b term

Q3

Quaternion c term

Q4

Quaternion d term

XKT

EKF3 timing information

TimeUS

μs

Time since system startup

C

instance

EKF core this message instance applies to

Cnt

s

count of samples used to create this message

IMUMin

s

smallest IMU sample interval

IMUMax

s

largest IMU sample interval

EKFMin

s

low-passed achieved average time step rate for the EKF (minimum)

EKFMax

s

low-passed achieved average time step rate for the EKF (maximum)

AngMin

s

accumulated measurement time interval for the delta angle (minimum)

AngMax

s

accumulated measurement time interval for the delta angle (maximum)

VMin

s

accumulated measurement time interval for the delta velocity (minimum)

VMax

s

accumulated measurement time interval for the delta velocity (maximum)

XKTV

EKF3 Yaw Estimator States

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

TVS

rad

Tilt Error Variance from symbolic equations (rad^2)

TVD

rad

Tilt Error Variance from difference method (rad^2)

XKV1

EKF3 State variances (primary core)

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

V00

Variance for state 0

V01

Variance for state 1

V02

Variance for state 2

V03

Variance for state 3

V04

Variance for state 4

V05

Variance for state 5

V06

Variance for state 6

V07

Variance for state 7

V08

Variance for state 8

V09

Variance for state 9

V10

Variance for state 10

V11

Variance for state 11

XKV2

more EKF3 State Variances (primary core)

TimeUS

μs

Time since system startup

C

instance

EKF3 core this data is for

V12

Variance for state 12

V13

Variance for state 13

V14

Variance for state 14

V15

Variance for state 15

V16

Variance for state 16

V17

Variance for state 17

V18

Variance for state 18

V19

Variance for state 19

V20

Variance for state 20

V21

Variance for state 21

V22

Variance for state 22

V23

Variance for state 23

XKY0

EKF Yaw Estimator States

TimeUS

μs

Time since system startup

C

instance

EKF core this data is for

YC

degheading

GSF yaw estimate (deg)

YCS

deg

GSF yaw estimate 1-Sigma uncertainty (deg)

Y0

degheading

Yaw estimate from individual EKF filter 0 (deg)

Y1

degheading

Yaw estimate from individual EKF filter 1 (deg)

Y2

degheading

Yaw estimate from individual EKF filter 2 (deg)

Y3

degheading

Yaw estimate from individual EKF filter 3 (deg)

Y4

degheading

Yaw estimate from individual EKF filter 4 (deg)

W0

Weighting applied to yaw estimate from individual EKF filter 0

W1

Weighting applied to yaw estimate from individual EKF filter 1

W2

Weighting applied to yaw estimate from individual EKF filter 2

W3

Weighting applied to yaw estimate from individual EKF filter 3

W4

Weighting applied to yaw estimate from individual EKF filter 4

XKY1

EKF Yaw Estimator Innovations

TimeUS

μs

Time since system startup

C

instance

EKF core this data is for

IVN0

m/s

North velocity innovation from individual EKF filter 0 (m/s)

IVN1

m/s

North velocity innovation from individual EKF filter 1 (m/s)

IVN2

m/s

North velocity innovation from individual EKF filter 2 (m/s)

IVN3

m/s

North velocity innovation from individual EKF filter 3 (m/s)

IVN4

m/s

North velocity innovation from individual EKF filter 4 (m/s)

IVE0

m/s

East velocity innovation from individual EKF filter 0 (m/s)

IVE1

m/s

East velocity innovation from individual EKF filter 1 (m/s)

IVE2

m/s

East velocity innovation from individual EKF filter 2 (m/s)

IVE3

m/s

East velocity innovation from individual EKF filter 3 (m/s)

IVE4

m/s

East velocity innovation from individual EKF filter 4 (m/s)