Back to Ardupilot

Logger Notes

libraries/AP_Logger/README.md

3.5.63.5 KB
Original Source

Logger Notes

Format Types

The format type specifies the amount of storage required for the entry and how the content should be interpreted.

CharC Type
aint16_t[32]
bint8_t
Buint8_t
hint16_t
Huint16_t
iint32_t
Iuint32_t
ffloat
ddouble
nchar[4]
Nchar[16]
Zchar[64]
Lint32_t latitude/longitude (so -35.1332423 becomes -351332423)
Muint8_t flight mode
qint64_t
Quint64_t
gfloat16_t

Legacy field types - do not use. These have been replaced by using the base C type and an appropriate multiplier column entry.

CharCType+Mult
cint16_t * 100
Cuint16_t * 100
eint32_t * 100
Euint32_t * 100

Units

All units here should be base units. This means battery capacity uses "amp * second" not "milliAmp * hours". Please keep the names consistent with Tools/autotest/param_metadata/param.py:33

CharUnit Abbrev.DescriptionNotes
'-'""no units e.g. Pi or a string
'?'"UNKNOWN"Units which haven't been worked out yet....
'A'"A"Ampere
'd'"deg"of the angular variety-180 to 180
'b'"B"bytes
'B'"B/s"bytes per second
'k'"deg/s"degrees per secondNot an SI unit, but in some situations more user-friendly than radians per second
'D'"deglatitude"degrees of latitude
'e'"deg/s/s"degrees per second per secondNot an SI unit, but in some situations more user-friendly than radians per second^2
'E'"rad/s"radians per second
'G'"Gauss"GaussNot an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
'h'"degheading"0.? to 359.?
'i'"A.s"Ampere second
'J'"W.s"Joule (Watt second)
'l'"l"litres
'L'"rad/s/s"radians per second per second
'm'"m"metres
'n'"m/s"metres per second
'N'"N"Newton
'o'"m/s/s"metres per second per second
'O'"degC"degrees CelsiusNot an SI unit, but Kelvin is too cumbersome for most users
'%'"%"percent
'S'"satellites"number of satellites
's'"s"seconds
'q'"rpm"revolutions per minuteNot an SI unit, but sometimes more intuitive than Hertz
'r'"rad"radians
't'"N.m"Newton meterstorque
'U'"deglongitude"degrees of longitude
'u'"ppm"pulses per minute
'v'"V"Volt
'P'"Pa"Pascal
'w'"Ohm"Ohm
'W'"W"watt
'X'"W.h"watt hour
'Y'"us"pulse width modulation in microseconds
'z'"Hz"Hertz
'#'"instance"(e.g.)Sensor instance number

Multipliers

This multiplier information applies to the raw value present in the log. Any adjustment implied by the format field (e.g. the "centi" in "centidegrees" is IGNORED for the purposes of scaling. Essentially "format" simply tells you the C-type, and format-type h (int16_t) is equivalent to format-type c (int16_t*100) tl;dr a GCS shouldn't/mustn't infer any scaling from the unit name

CharMultiplierDescription
'-'0no multiplier e.g. char[4]
'?'1multipliers which haven't been worked out yet
'2'1e2
'1'1e1
'0'1e0x1
'A'1e-1
'B'1e-2
'C'1e-3
'D'1e-4
'E'1e-5
'F'1e-6
'G'1e-7
'I'1e-9
'!'3.6(milliampere * hour => ampere * second) and (km/h => m/s)
'/'3600(ampere * hour => ampere * second)