Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Paparazzi Messages

Table of Contents

These are the common messages. Also see http://wiki.paparazziuav.org/wiki/Telemetry and http://wiki.paparazziuav.org/wiki/Messages_Format

Telemetry Messages

AUTOPILOT_VERSION (ID 1)

Field name Type Unit/Values Description
version uint32 version encoded as: MAJOR * 10000 + MINOR * 100 + PATCH
desc char[] version description as string from paparazzi_version

ALIVE (ID 2)

alive/heartbeat message containing the MD5sum of the aircraft configuration

Field name Type Unit/Values Description
md5sum uint8[]

PONG (ID 3)

Answer to PING datalink message, to measure latencies

message has no fields

TAKEOFF (ID 4)

Field name Type Unit/Values Description
cpu_time uint16 s

ARDRONE_NAVDATA (ID 5)

Field name Type Unit/Values Description
taille uint16
nu_trame uint16
ax uint16
ay uint16
az uint16
vx int16
vy int16
vz int16
temperature_acc uint16
temperature_gyro uint16
ultrasound uint16
us_debut_echo uint16
us_fin_echo uint16
us_association_echo uint16
us_distance_echo uint16
us_curve_time uint16
us_curve_value uint16
us_curve_ref uint16
nb_echo uint16
sum_echo uint32
gradient int16
flag_echo_ini uint16
pressure int32
temperature_pressure uint16
mx int16
my int16
mz int16
chksum uint16
checksum_errors uint32

ATTITUDE (ID 6)

Field name Type Unit/Values Description
phi float rad
psi float rad
theta float rad

GPS (ID 8)

Field name Type Unit/Values Description
mode uint8 byte_mask
utm_east int32 cm
utm_north int32 cm
course int16 decideg
alt int32 mm Altitude above geoid (MSL)
speed uint16 cm/s norm of 2d ground speed in cm/s
climb int16 cm/s
week uint16 weeks
itow uint32 ms
utm_zone uint8
gps_nb_err uint8

NAVIGATION_REF (ID 9)

Field name Type Unit/Values Description
utm_east int32 m
utm_north int32 m
utm_zone uint8
ground_alt float m

NAVIGATION (ID 10)

Field name Type Unit/Values Description
cur_block uint8
cur_stage uint8
pos_x float m
pos_y float m
dist_wp float m
dist_home float m
flight_time uint16 s
block_time uint16 s
stage_time uint16 s
kill_auto_throttle uint8 bool
circle_count uint8
oval_count uint8

PPRZ_MODE (ID 11)

Field name Type Unit/Values Description
ap_mode uint8 MANUAL, AUTO1, AUTO2, HOME, NOGPS, FAILSAFE
ap_gaz uint8 MANUAL, AUTO_THROTTLE, AUTO_CLIMB, AUTO_ALT
ap_lateral uint8 MANUAL, ROLL_RATE, ROLL, COURSE
ap_horizontal uint8 WAYPOINT, ROUTE, CIRCLE
if_calib_mode uint8 NONE, DOWN, UP
mcu1_status uint8 LOST, OK, REALLY_LOST

ENERGY (ID 12)

Field name Type Unit/Values Description
throttle uint8 % Throttle setting
voltage float V Input battery voltage
current float A Current consumption
power float W Electrical power
avg_power float W Average electrical power
charge float Ah Accumulated consumed charge
energy float Wh Accumulated consumed energy

CALIBRATION (ID 14)

Field name Type Unit/Values Description
climb_sum_err float
climb_gaz_submode uint8

SETTINGS (ID 15)

Field name Type Unit/Values Description
slider_1_val float
slider_2_val float

DESIRED (ID 16)

Field name Type Unit/Values Description
roll float rad
pitch float rad
course float rad
x float m
y float m
altitude float m
climb float m/s
airspeed float m/s

GPS_SOL (ID 17)

Field name Type Unit/Values Description
Pacc uint32 cm
Sacc uint32 cm/s
PDOP uint16
numSV uint8

ADC_GENERIC (ID 18)

Field name Type Unit/Values Description
val1 uint16
val2 uint16

CAM (ID 20)

Field name Type Unit/Values Description
pan int16 deg
tilt int16 deg
target_x int16 m
target_y int16 m

CIRCLE (ID 21)

Field name Type Unit/Values Description
center_east float m
center_north float m
radius float m

SEGMENT (ID 22)

Field name Type Unit/Values Description
segment_east_1 float m
segment_north_1 float m
segment_east_2 float m
segment_north_2 float m

VECTORNAV_INFO (ID 23)

Field name Type Unit/Values Description
timestamp float s
chksm_error uint32
hdr_error uint32
rate uint16 packets/s
ins_status uint8 NoTracking, OutOfSpecs, OK
ins_err uint8
YprU1 float deg
YprU2 float deg
YprU3 float deg

HYBRID_GUIDANCE (ID 24)

Field name Type Unit/Values Description
pos_x int32
pos_y int32
speed_x int32
speed_y int32
wind_x int32
wind_y int32
pos_err_x int32
pos_err_y int32
speed_sp_x int32
speed_sp_y int32
norm_ref_speed int32
heading_diff int32
phi int32
theta int32
psi int32

SVINFO (ID 25)

Field name Type Unit/Values Description
chn uint8
SVID uint8
Flags uint8
QI uint8
CNO uint8 dbHz
Elev int8 deg
Azim int16 deg

DEBUG (ID 26)

Field name Type Unit/Values Description
msg uint8[]

SURVEY (ID 27)

Field name Type Unit/Values Description
east float m
north float m
west float m
south float m

RSSI (ID 28)

Field name Type Unit/Values Description
rssi uint8 dB
tx_power uint8 dB

RANGEFINDER (ID 29)

Field name Type Unit/Values Description
range uint16 cm
z_dot float m/s
z_dot_sum_err float m/s
z_dot_setpoint float m/s
z_sum_err float m/s
z_setpoint float m
flying uint8 bool

DATALINK_REPORT (ID 30)

Datalink status reported by an aircraft for the ground

Field name Type Unit/Values Description
uplink_lost_time uint16 s
uplink_nb_msgs uint16
downlink_nb_msgs uint16
downlink_rate uint16 bytes/s
uplink_rate uint16 msgs/s
downlink_ovrn uint8

DL_VALUE (ID 31)

Field name Type Unit/Values Description
index uint8
value float

MARK (ID 32)

Field name Type Unit/Values Description
ac_id uint8
lat float deg
long float deg

SYS_MON (ID 33)

Field name Type Unit/Values Description
periodic_time uint16 usec
periodic_time_min uint16 usec
periodic_time_max uint16 usec
periodic_cycle uint16 usec
periodic_cycle_min uint16 usec
periodic_cycle_max uint16 usec
event_number uint16
cpu_load uint8 %
cpu_time float s

MOTOR (ID 34)

Field name Type Unit/Values Description
rpm uint16 Hz
current float A

WP_MOVED (ID 35)

Waypoint with id wp_id has been updated/moved to the specified UTM coordinates.

Field name Type Unit/Values Description
wp_id uint8
utm_east float m
utm_north float m
alt float m Height above Mean Sea Level (geoid)
utm_zone uint8

MKK (ID 36)

Field name Type Unit/Values Description
nr uint8
rpm uint8 Poles/s
current uint8 mA
temp int8 deg

GUIDANCE_INDI_HYBRID (ID 37)

Field name Type Unit/Values Description
sp_accel_x float
sp_accel_y float
sp_accel_z float
euler_cmd_x float
euler_cmd_y float
euler_cmd_z float
accelned_filt_x float
accelned_filt_y float
accelned_filt_z float
speed_sp_x float
speed_sp_y float
speed_sp_z float

DRAGSPEED (ID 38)

Velocities in body axes (assuming small pitch/roll angles) as measured by the dragspeed module and by the INS.

Field name Type Unit/Values Description
u_est float m/s Estimated velocity along body +x axis
v_est float m/s Estimated velocity along body +y axis
u_ins float m/s INS velocity along body +x axis
v_ins float m/s INS velocity along body +y axis

RSSI_COMBINED (ID 39)

Field name Type Unit/Values Description
remote_rssi uint8
tx_power uint8
local_rssi uint8
local_noise uint8
remote_noise uint8

DCF (ID 40)

Telemetry message for monitoring the status of the Distributed Circular Formation.

Field name Type Unit/Values Description
table int16[] The size of the array is 4 x (maximum number of possible neighbors). The elements per each neighbor are: 1. ID of the neighbor, 2. Theta of the neighbor (degrees x 100), 3. Desired inter-vehicle angle (degrees x 100), 4. Last time in ms we received a msg from the neighbor
errors int16[] The size of the array is the maximum number of possible neighbors. Errors w.r.t. desired inter-vehicle angles (degrees x 100)

ALT_KALMAN (ID 41)

Field name Type Unit/Values Description
p00 float
p01 float
p10 float
p11 float

ESTIMATOR (ID 42)

Field name Type Unit/Values Description
z float m
z_dot float m/s

TUNE_ROLL (ID 43)

Field name Type Unit/Values Description
p float
phi float
phi_sp float

BARO_MS5534A (ID 44)

Field name Type Unit/Values Description
pressure uint32 P
temp uint16 dC
alt float m

CHIRP (ID 45)

Field name Type Unit/Values Description
active uint8 Chirp is active
percentage_done float Percentage done
current_frequency float Current frequency
axis uint8 Current chirp axis
amplitude int16 Amplitude
fstart float Start frequency
fstop float Stop frequency
noise_onaxis_ratio float Noise ratio onaxis
noise_offaxis float Noise offaxis
current_value int16 Current chirp value
fade_in uint8 bool Fade in feature active
exponential uint8 bool Exponential chirp active

EXTERNAL_POSE_DOWN (ID 46)

Position, speed and orientation in local frame from a remote vision system

Field name Type Unit/Values Description
timestamp float mus Timestamp from the measurement
ned_x float m NED x position in vision frame
ned_y float m NED y position in vision frame
ned_z float m NED z position in vision frame
ned_xd float m/s NED x speed in vision frame
ned_yd float m/s NED y speed in vision frame
ned_zd float m/s NED z speed in vision frame
body_qi float Body quaternion i in NED to body
body_qx float Body quaternion x in NED to body
body_qy float Body quaternion y in NED to body
body_qz float Body quaternion z in NED to body

WP_MOVED_LLA (ID 47)

Field name Type Unit/Values Description
wp_id uint8
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm Height above Mean Sea Level (geoid)

RLFILTER (ID 48)

Relative localization data for other tracked MAVs in terms of x y and z in the body axis

Field name Type Unit/Values Description
trackedID int32
rangearray float dB
x_tracked float m/s
y_tracked float m/s
vx_own float m/s
vy_own float m/s
vx_tracked float m/s
vy_tracked float m/s
z_pos float m

WP_MOVED_ENU (ID 49)

Field name Type Unit/Values Description
wp_id uint8
east int32 2^8m
north int32 2^8m
up int32 2^8m

WINDTURBINE_STATUS_ (ID 50)

Field name Type Unit/Values Description
ac_id uint8
tb_id uint8
sync_itow uint32 ms
cycle_time uint32 ms

RC_3CH_ (ID 51)

Field name Type Unit/Values Description
throttle_mode uint8 byte_mask
roll int8
pitch int8

MPPT (ID 52)

Field name Type Unit/Values Description
values int16[]

DEBUG_VECT (ID 53)

Field name Type Unit/Values Description
name char[]
vector float[]

AIRSPEED (ID 54)

Field name Type Unit/Values Description
airspeed float m/s Fused airspeed from all sources
airspeed_sp float m/s Airspeed setpoint
airspeed_cnt float m/s
groundspeed_sp float m/s

METEO_STICK (ID 55)

Data from the MeteoSitck sensor board

Field name Type Unit/Values Description
lat int32 1e7deg
lon int32 1e7deg
hmsl int32 mm Height above Mean Sea Level (geoid)
itow uint32 ms GPS time of week
pressure float Pa absolute static pressure
temperature float deg C temperature
humidity float % relative humidity
airspeed float m/s calibrated airspeed

BARO_ETS (ID 56)

Field name Type Unit/Values Description
adc uint16
offset uint16
scaled float

VISION_OUTBACK (ID 58)

Field name Type Unit/Values Description
status uint8
het_moment uint8
timeoutcount uint8
vision_timeout uint8
height float
out_of_range float
marker_enu_x float
marker_enu_y float
flow_x float
flow_y float

GPS_LLA (ID 59)

Field name Type Unit/Values Description
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm altitude above WGS84 reference ellipsoid
hmsl int32 mm Height above Mean Sea Level (geoid)
course int16 decideg
speed uint16 cm/s
climb int16 cm/s
week uint16 weeks
itow uint32 ms
mode uint8 byte_mask
gps_nb_err uint8

H_CTL_A (ID 60)

Field name Type Unit/Values Description
roll_sum_err float
roll_sp float rad
roll_ref float rad
phi float rad
aileron_sp int16 pprz
pitch_sum_err float
pitch_sp float rad
pitch_ref float rad
theta float rad
elevator_sp int16 pprz

CLOUD_SENSOR (ID 61)

Geolocalized and timestamped data from the meteo cloud sensor module

Field name Type Unit/Values Description
lat int32 1e7deg
lon int32 1e7deg
hmsl int32 mm Height above Mean Sea Level (geoid)
itow uint32 ms GPS time of week
coef float Angstrom coefficient computed on board
raw float[] Raw values and extra measurements data

TURB_PRESSURE_VOLTAGE (ID 62)

Field name Type Unit/Values Description
ch_1_p float
ch_1_t float
ch_2_p float
ch_2_t float
ch_3_p float
ch_3_t float
ch_4_p float
ch_4_t float
ch_5_p float
ch_5_t float
ch_6_p float
ch_6_t float
ch_7_p float
ch_7_t float
gnd1 float
gnd2 float

CAM_POINT (ID 63)

Field name Type Unit/Values Description
cam_point_distance_from_home uint16 m
cam_point_lat float deg
cam_point_lon float deg

DC_INFO (ID 64)

Field name Type Unit/Values Description
mode int16
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm altitude above WGS84 reference ellipsoid
course float deg
photo_nr uint16
dist float m
next_dist float m
start_x float m
start_y float m
start_angle float deg
angle float deg
last_block float
count uint16
shutter uint8 decisec

AMSYS_BARO (ID 65)

Field name Type Unit/Values Description
pBaroRaw uint16
pBaro float Pa
pHomePressure float Pa
AltOffset float m
aktuell float m
Over_Ground float m
tempBaro float °C

AMSYS_AIRSPEED (ID 66)

Field name Type Unit/Values Description
asRaw uint16
asPresure float Pa
asAirspeed float m/s
asAirsFilt float m/s
asTemp float °C

FLIGHT_BENCHMARK (ID 67)

Field name Type Unit/Values Description
SE_As float
SE_Alt float
SE_Pos float
Err_As float
Err_Alt float
Err_Pos float

MPL3115_BARO (ID 68)

Field name Type Unit/Values Description
pressure uint32
temp int16
alt float m

AOA (ID 69)

Field name Type Unit/Values Description
raw uint32
angle float rad

XTEND_RSSI (ID 70)

Field name Type Unit/Values Description
datalink_time uint16 s
rssi_fade_margin uint8 dB
duty uint8 %

GVF (ID 71)

Information about the trajectory followed by the Guidance Vector Field algorithm.

Field name Type Unit/Values Description
error float Error index e, i.e. 'distance' to the trajectory
traj uint8 Kind of trajectory
s int8 1, -1 Direction to be followed
ke float Gain for the vector field convergence
p float[] Parameters describing the trajectory

SUPERBITRF (ID 72)

Field name Type Unit/Values Description
status uint8 UNINIT, INIT_BINDING, INIT_TRANSFER, BINDING, SYNCING_A, SYNCING_B, TRANSFER
cyrf_status uint8 UNINIT, IDLE, GET_MFG_ID, MULTIWRITE, DATA_CODE, CHAN_SOP_DATA_CRC, RX_IRQ_STATUS_PACKET, SEND
irq_count uint32
rx_packet_count uint32
tx_packet_count uint32
transfer_timeouts uint32
resync_count uint32
uplink_count uint32
rc_count uint32
timing1 uint32
timing2 uint32
bind_mfg_id uint32
mfg_id uint8[]

GX3_INFO (ID 73)

Field name Type Unit/Values Description
GX3_freq float hz
chksm_error uint32
hdr_error uint32
GX3_chksm uint16

UBLOX_INFO (ID 74)

Field name Type Unit/Values Description
baud uint32
ver_sw_h uint8
ver_sw_l uint8
ver_hw_h uint16
ver_hw_l uint16
sbas uint8
gnss uint8 NONE, GPS, GLONAS, GPS+GLONAS, BEIDOU, GPS+BEIDOU, GLONAS+BEIDOU, GPS+GLONAS+BEIDOU, GALILEO

GVF_PARAMETRIC (ID 75)

Information about the parametric trajectory followed by the Guidance Vector Field algorithm.

Field name Type Unit/Values Description
traj uint8 Kind of trajectory
s int8 1, -1 Direction to be followed
w float Virtual coordinate of the algorithm
p float[] Parameters describing the trajectory
phi float[] m Error signals

BODY_RATES_ACCEL (ID 76)

Rates and Acceleration in the body frame

Field name Type Unit/Values Description
p float rad/s
q float rad/s
r float rad/s
ax int32
ay int32
az int32

SWARM_FISH (ID 77)

State of the swarm fish navigation

Field name Type Unit/Values Description
heading float rad Current Heading
step_size float m Current step size
rw float m Distance to wall
fw float Wall interaction coef
theta_w float rad Angle to wall
f_fluct float Fluctation effect
f_wall float Wall effect
f_ali float Alignement effect
f_att float Attraction effect

INV_FILTER (ID 78)

Field name Type Unit/Values Description
quat float
phi_inv float rad
theta_inv float rad
psi_inv float rad
Vx_inv float m/s
Vy_inv float m/s
Vz_inv float m/s
Px_inv float m
Py_inv float m
Pz_inv float m
bias_phi float rad/s
bias_theta float rad/s
bias_psi float rad/s
bias_as float
bias_hb float
meas_baro float m
meas_gps float m

MISSION_STATUS (ID 79)

Field name Type Unit/Values Description
remaining_time float
index_list uint8[]

JEVOIS (ID 80)

Debug message for the JeVois smart camera corresponding to the standardized messages

Field name | Type | Unit/Values | Description | --------—|---—|----------—|----------—| type | uint8 | | Standardized message type JEVOIS_MSG_[T1|N1|D1|T2|N2|D2|F2|T3|N3|D3|F3] | id | char[] | | Text string describing the reported object | nb | uint8 | | Number of elements in the coordinates array | coord | int16[] | | List of coordinates corresponding to 1D, 2D or 3D messages | dim | uint16[3] | | 1, 2 or 3D dimension | quat | float[4] | | Quaternion that relates the object's frame to the camera's frame, if appropriate |

GENERIC_COM (ID 81)

Field name Type Unit/Values Description
lat int32 1e7deg
lon int32 1e7deg
alt int16 m
gspeed uint16 cm/s
course int16 decideg
airspeed uint16 cm/s
vsupply uint8 deciV
charge uint8 deciAh
throttle uint8 %
ap_mode uint8
nav_block uint8
flight_time uint16 s

FORMATION_SLOT_TM (ID 82)

Field name Type Unit/Values Description
ac_id uint8
mode uint8
slot_east float m
slot_north float m
slot_alt float m

FORMATION_STATUS_TM (ID 83)

Field name Type Unit/Values Description
ac_id uint8
leader_id uint8
status uint8

BMP_STATUS (ID 84)

Field name Type Unit/Values Description
UP int32
UT int32
press int32 Pa
temp int32 10x_deg_celsius

MLX_STATUS (ID 85)

Field name Type Unit/Values Description
itemp_case uint16
temp_case float deg_celsius
itemp_obj uint16
temp_obj float deg_celsius

TMP_STATUS (ID 86)

Field name Type Unit/Values Description
itemp uint16
temp float deg_celsius

WIND_INFO_RET (ID 87)

Wind information returned to the ground station. The wind is reported as a vector, it gives the direction the wind is blowing to. This can be used to acknowledge data comming from the ground wind estimator or from an embedded algorithm. Flags field definition:

  • bit 0: horizontal wind is valid (east and north fields)
  • bit 1: vertical wind is valid (up field)
  • bit 2: airspeed is valid
Field name Type Unit/Values Description
flags uint8 bit 0: horizontal wind, bit 1: vertical wind: bit 2: airspeed
east float m/s east component of the wind
north float m/s north component of the wind
up float m/s vertical component of the wind
airspeed float m/s local airspeed norm

SCP_STATUS (ID 88)

Field name Type Unit/Values Description
press uint32 Pa
temp int16 100x_deg_celsius

SHT_STATUS (ID 89)

Field name Type Unit/Values Description
ihumid uint16
itemp uint16
humid float rel_hum
temp float deg_celsius

VISION_POSITION_ESTIMATE (ID 90)

Generic message to send position measurement from computer vision

Field name Type Unit/Values Description
cnt uint16 Counter
x float X
y float Y
z float Z
quality float Detection Quality or Uncertainty
extra float In case the default message does not suit you

DPICCO_STATUS (ID 91)

Field name Type Unit/Values Description
humid uint16
temp uint16
fhumid float rel_hum
ftemp float deg_celsius

LOGGER_STATUS (ID 92)

Logger status and error id (dependent of the logging system)

Field name Type Unit/Values Description
status uint8 STOPPED, RUNNING, ERROR General status of the logger
errno uint8 Error number, depend of the logging system, provides detailed information
used uint32 bytes Accumulated number of bytes written by the logger
filenames char[] The filenames currently in use by the logger (First sdlog, second Flight recorder for chibios)

MINIMAL_COM (ID 93)

Minimal information for correct display in the GCS, in particular the Strip

Field name Type Unit/Values Description
lat float deg Lattitude
lon float deg Longitude
hmsl float m Altitude above mean sea level
gspeed float m/s Ground speed norm
course float rad Ground speed direction
climb float m/s Vertical speed
vsupply float V Battery voltage
throttle uint8 % Throttle level
ap_mode uint8 Current autopilot mode
nav_block uint8 Current navigation block
gps_mode uint8 GPS fix flag
flight_time uint16 Flight time

MOTOR_BENCH_STATUS (ID 94)

Field name Type Unit/Values Description
time_ticks uint32
throttle float
rpm float
current float
thrust float
torque float
time_s uint16
mode uint8

TARGET_POS_INFO (ID 95)

Global position, speed and ID of a target for functions like 'Follow Me'

Field name Type Unit/Values Description
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm Height above Mean Sea Level (geoid)
speed float m/s Ground speed
climb float m/s Climb speed
course float deg
heading float deg
off_heading float deg Offset heading
off_distance float m Offset distance
off_height float m Offset height

HIH_STATUS (ID 96)

Field name Type Unit/Values Description
humid uint16
fhumid float rel_hum
ftemp float deg_celsius

TEMT_STATUS (ID 97)

Field name Type Unit/Values Description
light uint16
f_light float percent

GP2Y_STATUS (ID 98)

Field name Type Unit/Values Description
idensity uint16
density float mg/m3

SHT_I2C_SERIAL (ID 99)

Field name Type Unit/Values Description
serial0 uint32
serial1 uint32

PPM (ID 100)

Field name Type Unit/Values Description
ppm_rate uint8
values uint16[] usec

RC (ID 101)

Field name Type Unit/Values Description
values int16[] pprz

COMMANDS (ID 102)

Field name Type Unit/Values Description
values int16[] ticks

FBW_STATUS (ID 103)

Field name Type Unit/Values Description
rc_status uint8 OK, LOST, REALLY_LOST
frame_rate uint8 Hz
mode uint8 MANUAL, AUTO, FAILSAFE
vsupply float V
current float A

ADC (ID 104)

Field name Type Unit/Values Description
mcu uint8 FBW, AP
values uint16[] none

ACTUATORS (ID 105)

Field name Type Unit/Values Description
values int16[] none

BLUEGIGA (ID 106)

Field name Type Unit/Values Description
data_rate uint32 bytes/s
A2A_msg_rate uint32

THROTTLE_CURVE (ID 107)

Field name Type Unit/Values Description
curve uint8
throttle uint16
collective int16
rpm_sp uint16
rpm_meas uint16
rpm_err_sum float

PIKSI_HEARTBEAT (ID 108)

Field name Type Unit/Values Description
heartbeat uint32

MULTIGAZE_METERS (ID 109)

Field name Type Unit/Values Description
multigaze_meters float[]

DC_SHOT (ID 110)

Field name Type Unit/Values Description
photo_nr int16
lat int32 1e7deg Gedetic latitude
lon int32 1e7deg Longitude
alt int32 mm altitude above WGS84 reference ellipsoid
hmsl int32 mm Height above Mean Sea Level (geoid)
phi int16 decideg Euler angle around x-axis (roll)
theta int16 decideg Euler angle around y-axis (pitch)
psi int16 decideg Euler angle around z-axis (yaw)
course int16 decideg Course over ground (CW/north)
speed uint16 cm/s horizontal ground speed
itow uint32 ms GPS time of week

CAMERA_PAYLOAD (ID 111)

Field name Type Unit/Values Description
timestamp float s Payload computer seconds since startup
used_memory uint8 % Percentage of used memory (RAM) of the payload computer rounded up to whole percent
used_disk uint8 % Percentage of used disk of the payload computer rounded up to whole percent
door_status uint8 UNKNOWN, CLOSE, OPEN Payload door open/close
error_code uint8 NONE, CAMERA_ERR, DOOR_ERR Error codes of the payload

MOTOR_MIXING (ID 112)

Field name Type Unit/Values Description
values int16[] none

MLX_SERIAL (ID 113)

Field name Type Unit/Values Description
serial0 uint32
serial1 uint32

PAYLOAD (ID 114)

Field name Type Unit/Values Description
values uint8[] none

HTM_STATUS (ID 115)

Field name Type Unit/Values Description
ihumid uint16
itemp uint16
humid float rel_hum
temp float deg_celsius

BARO_MS5611 (ID 116)

Field name Type Unit/Values Description
d1 uint32
d2 uint32
pressure float hPa
temp float deg_celsius

MS5611_COEFF (ID 117)

Field name Type Unit/Values Description
c0 uint16
c1 uint16
c2 uint16
c3 uint16
c4 uint16
c5 uint16
c6 uint16
c7 uint16

ATMOSPHERE_CHARGE (ID 118)

Field name Type Unit/Values Description
t0 uint16
t1 uint16
t2 uint16
t3 uint16
t4 uint16
t5 uint16
t6 uint16
t7 uint16
t8 uint16
t9 uint16

SOLAR_RADIATION (ID 119)

Field name Type Unit/Values Description
up_t0 uint16
dn_t0 uint16
up_t1 uint16
dn_t1 uint16
up_t2 uint16
dn_t2 uint16
up_t3 uint16
dn_t3 uint16
up_t4 uint16
dn_t4 uint16
up_t5 uint16
dn_t5 uint16
up_t6 uint16
dn_t6 uint16
up_t7 uint16
dn_t7 uint16
up_t8 uint16
dn_t8 uint16
up_t9 uint16
dn_t9 uint16

TCAS_TA (ID 120)

Field name Type Unit/Values Description
ac_id uint8

TCAS_RA (ID 121)

Field name Type Unit/Values Description
ac_id uint8
resolve uint8 NONE, LEVEL, CLIMB, DESCEND

TCAS_RESOLVED (ID 122)

Field name Type Unit/Values Description
ac_id uint8

TCAS_DEBUG (ID 123)

Field name Type Unit/Values Description
ac_id uint8
tau float

POTENTIAL (ID 124)

Field name Type Unit/Values Description
east float
north float
alt float
speed float
climb float

COPILOT_STATUS (ID 125)

Field name Type Unit/Values Description
timestamp float s Mission computer seconds since startup
used_memory uint8 % Percentage of used memory (RAM) of the mission computer rounded up to whole percent
used_disk uint8 % Percentage of used disk of the mission computer rounded up to whole percent
status uint8 UNKNOWN, INIT, LOGGING, FAULT Mission computer status
error_code uint8 NONE, IO_ERROR Error codes of the mission computer

TEMP_TCOUPLE (ID 126)

Field name Type Unit/Values Description
fval0 float
fval1 float
fval2 float
fval3 float
fref0 float
fref1 float
fref2 float
fref3 float
val0 uint16
val1 uint16
val2 uint16
val3 uint16
ref0 uint16
ref1 uint16
ref2 uint16
ref3 uint16

SHT_I2C_STATUS (ID 127)

Field name Type Unit/Values Description
ihumid uint16
itemp uint16
humid float rel_hum
temp float deg_celsius

CAMERA_SNAPSHOT (ID 128)

Field name Type Unit/Values Description
camera_id uint16 Unique camera ID - consists of make,model and camera index
camera_state uint8 UNKNOWN, OK, ERROR State of the given camera
snapshot_image_number uint16 Snapshot number in sequence
snapshot_valid uint8 bool Flag checking whether the last snapshot was valid
lens_temp float deg_celsius Lens temperature, NaN if not measured
array_temp float deg_celsius Imager sensor temperature, NaN if not measured

TIMESTAMP (ID 129)

Field name Type Unit/Values Description
timestamp uint32

STAB_ATTITUDE_FLOAT (ID 130)

Field name Type Unit/Values Description
est_p float
est_q float
est_r float
est_phi float
est_theta float
est_psi float
ref_phi float
ref_theta float
ref_psi float
sum_err_phi float
sum_err_theta float
sum_err_psi float
delta_a_fb float
delta_e_fb float
delta_r_fb float
delta_a_ff float
delta_e_ff float
delta_r_ff float
delta_a int32
delta_e int32
delta_r int32
est_p_d float
est_q_d float
est_r_d float

IMU_GYRO_SCALED (ID 131)

Field name Type Unit/Values Description
id uint8
gp int32
gq int32
gr int32

IMU_ACCEL_SCALED (ID 132)

Field name Type Unit/Values Description
id uint8
ax int32
ay int32
az int32

IMU_MAG_SCALED (ID 133)

Field name Type Unit/Values Description
id uint8
mx int32
my int32
mz int32

FILTER (ID 134)

Field name Type Unit/Values Description
phi int32
theta int32
psi int32
measure_phi int32
measure_theta int32
measure_psi int32
corrected_phi int32
corrected_theta int32
corrected_psi int32
correction_phi int32
correction_theta int32
correction_psi int32
bp int32
bq int32
br int32
comp_id uint8 NONE, GENERIC, IR, ICQ, ICE, FC, DCM, FINV, MLKF, GX3, CHIMU, VN

IMU_HEATER (ID 135)

Field name Type Unit/Values Description
meas_temp float Celcius
target_temp float Celcius
heat_cmd uint8 %

RATE_LOOP (ID 136)

Rotorcraft rate control loop.

Field name Type Unit/Values Description
sp_p float rad/s rate setpoint
sp_q float rad/s rate setpoint
sp_r float rad/s rate setpoint
sumerr_p float integrated quaternion error
sumerr_q float integrated quaternion error
sumerr_r float integrated quaternion error
fb_p float feedback command on pitch (pprz scale)
fb_q float feedback command on roll (pprz scale)
fb_r float feedback command on yaw (pprz scale)
delta_t int32 thrust command

FILTER_ALIGNER (ID 137)

Field name Type Unit/Values Description
lp_gp int32
lp_gq int32
lp_gr int32
gp int32
gq int32
gr int32
noise int32
cnt int32
status uint8 UNINIT, RUNNING, LOCKED

AIRSPEED_RAW (ID 138)

Field name Type Unit/Values Description
sensor_id uint8
raw uint16
offset float Pa
diffPress float Pa
temperature float deg_celcius
airspeed float m/s

APPROACH_MOVING_TARGET (ID 139)

Field name Type Unit/Values Description
ref_pos_x float m
ref_pos_y float m
ref_pos_z float m
ref_vel_x float m/s
ref_vel_y float m/s
ref_vel_z float m/s
distance float m

STAB_ATTITUDE_INT (ID 140)

Field name Type Unit/Values Description
est_p int32
est_q int32
est_r int32
est_phi int32
est_theta int32
est_psi int32
sp_phi int32
sp_theta int32
sp_psi int32
sum_err_phi int32
sum_err_theta int32
sum_err_psi int32
delta_a_fb int32
delta_e_fb int32
delta_r_fb int32
delta_a_ff int32
delta_e_ff int32
delta_r_ff int32
delta_a int32
delta_e int32
delta_r int32

STAB_ATTITUDE_REF_INT (ID 141)

Field name Type Unit/Values Description
sp_phi int32
sp_theta int32
sp_psi int32
ref_phi int32
ref_theta int32
ref_psi int32
ref_p int32
ref_q int32
ref_r int32
ref_pd int32
ref_qd int32
ref_rd int32

STAB_ATTITUDE_REF_FLOAT (ID 142)

Field name Type Unit/Values Description
sp_phi float
sp_theta float
sp_psi float
ref_phi float
ref_theta float
ref_psi float
ref_p float
ref_q float
ref_r float
ref_pd float
ref_qd float
ref_rd float

ROTORCRAFT_CMD (ID 143)

Field name Type Unit/Values Description
cmd_roll int32
cmd_pitch int32
cmd_yaw int32
cmd_thrust int32

GUIDANCE_H_INT (ID 144)

Field name Type Unit/Values Description
sp_x int32
sp_y int32
ref_x int32
ref_y int32
est_x int32
est_y int32

VERT_LOOP (ID 145)

Field name Type Unit/Values Description
z_sp int32
zd_sp int32
est_z int32
est_zd int32
est_zdd int32
ref_z int32
ref_zd int32
ref_zdd int32
adp_inv_m int32
adp_cov int32
adp_meas int32
sum_err int32
ff_cmd int32
fb_cmd int32
delta_t int32

HOVER_LOOP (ID 146)

Field name Type Unit/Values Description
sp_x int32
sp_y int32
est_x int32
est_y int32
est_xd int32
est_yd int32
est_xdd int32
est_ydd int32
err_x int32
err_y int32
err_xd int32
err_yd int32
err_sum_x int32
err_sum_y int32
cmd_x int32
cmd_y int32
cmd_heading float rad

ROTORCRAFT_FP (ID 147)

Field name Type Unit/Values Description
east int32
north int32
up int32
veast int32
vnorth int32
vup int32
phi int32
theta int32
psi int32
carrot_east int32
carrot_north int32
carrot_up int32
carrot_psi int32
thrust int32
flight_time uint16 s

TEMP_ADC (ID 148)

Field name Type Unit/Values Description
temp1 float deg_celsius
temp2 float deg_celsius
temp3 float deg_celsius

GUIDANCE_H_REF_INT (ID 149)

Field name Type Unit/Values Description
sp_x int32
ref_x int32
sp_xd int32
ref_xd int32
ref_xdd int32
sp_y int32
ref_y int32
sp_yd int32
ref_yd int32
ref_ydd int32

ROTORCRAFT_TUNE_HOVER (ID 150)

Field name Type Unit/Values Description
rc_roll int16
rc_pitch int16
rc_yaw int16
cmd_roll int32
cmd_pitch int32
cmd_yaw int32
cmd_thrust int32
body_phi int32
body_theta int32
body_psi int32

INS_Z (ID 151)

Field name Type Unit/Values Description
baro_z float m
ins_z int32
ins_zd int32
ins_zdd int32

PCAP01_STATUS (ID 152)

Field name Type Unit/Values Description
ihumid uint32
itemp uint32
humid float rel_hum
temp float deg_celsius

GEIGER_COUNTER (ID 153)

Field name Type Unit/Values Description
tube1 uint32 events
tube2 uint32 events
vsupply uint16 volts

INS_REF (ID 154)

Field name Type Unit/Values Description
ecef_x0 int32
ecef_y0 int32
ecef_z0 int32
lat0 int32 1e7deg
lon0 int32 1e7deg
alt0 int32
hmsl0 int32
baro_qfe float pascal

GPS_INT (ID 155)

Field name Type Unit/Values Description
ecef_x int32 cm
ecef_y int32 cm
ecef_z int32 cm
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm altitude above WGS84 reference ellipsoid
hmsl int32 mm height above mean sea level (geoid)
ecef_xd int32 cm/s
ecef_yd int32 cm/s
ecef_zd int32 cm/s
pacc uint32 cm
sacc uint32 cm/s
tow uint32
pdop uint16
numsv uint8
fix uint8 NONE, NA, 2D, 3D, DGPS, RTK
comp_id uint8 NONE, UBX, NMEA, SIRF, SKYTRAQ, MTK, PIKSI, XSENS, DATALINK, UDP, ARDRONE2, SIM, MULTI, VECTORNAV, IMCU

AHRS_EULER_INT (ID 156)

Field name Type Unit/Values Description
imu_phi int32
imu_theta int32
imu_psi int32
body_phi int32
body_theta int32
body_psi int32
comp_id uint8 NONE, GENERIC, IR, ICQ, ICE, FC, DCM, FINV, MLKF, GX3, CHIMU, VN

AHRS_QUAT_INT (ID 157)

Field name Type Unit/Values Description
weight float
imu_qi int32
imu_qx int32
imu_qy int32
imu_qz int32
body_qi int32
body_qx int32
body_qy int32
body_qz int32
comp_id uint8 NONE, GENERIC, IR, ICQ, ICE, FC, DCM, FINV, MLKF, GX3, CHIMU, VN

INS_FLOW_INFO (ID 158)

Field name Type Unit/Values Description
vy float m/s
phi float deg
p float deg/s
vx float m/s
theta float deg
q float deg/s
z float m
vz float m/s
vy_GT float m/s
phi_GT float deg
p_GT float deg/s
vx_GT float m/s
theta_GT float deg
q_GT float deg/s
z_GT float m
vz_GT float m/s
thrust_bias float N
use_filter int32 -

ROTORCRAFT_NAV_STATUS (ID 159)

Field name Type Unit/Values Description
block_time uint16 s
stage_time uint16 s
dist_home float m
dist_wp float m
cur_block uint8
cur_stage uint8
horizontal_mode uint8

ROTORCRAFT_RADIO_CONTROL (ID 160)

Field name Type Unit/Values Description
roll int16 pprz
pitch int16 pprz
yaw int16 pprz
throttle int16 pprz
mode int16 pprz
kill int16 pprz
status uint8 OK, LOST, REALLY_LOST

VFF_EXTENDED (ID 161)

Field name Type Unit/Values Description
meas_baro float
meas_alt float
z float
zd float
zdd float
bias float
offset float
obs_height float
Pzz float
Pzdzd float
Pbb float
Poffsetoffset float
Pobsobs float

VFF (ID 162)

Field name Type Unit/Values Description
measure float
z float
zd float
bias float
Pzz float
Pzdzd float
Pbb float

GEO_MAG (ID 163)

Field name Type Unit/Values Description
Hx float
Hy float
Hz float
comp_id uint8 NONE, GENERIC, GEOM, ICQ, ICE, FC, DCM, FINV, MLKF, GX3

HFF (ID 164)

Field name Type Unit/Values Description
x float
y float
xd float
yd float
xdd float
ydd float
xbias float
ybias float

HFF_DBG (ID 165)

Field name Type Unit/Values Description
x_measure float
y_measure float
xd_measure float
yd_measure float
Pxx float
Pyy float
Pxdxd float
Pydyd float
Pxbiasxbias float
Pybiasybias float

HFF_GPS (ID 166)

Field name Type Unit/Values Description
lag_cnt uint16
lag_cnt_err int16
save_cnt int16

INS_EKF2 (ID 167)

Extended Kalman Filter 2 status message which gives feedback about the input- and output states of the filter.

Field name Type Unit/Values Description
control_mode uint32 description of the control status (bitfields from common.h)
filter_fault_status uint16 numerical errors in output states (bitfields from common.h)
gps_check_status uint16 quality check of the GPS feedback (bitfields from common.h)
soln_status uint16 which output states are valid or has an error (bitfields from common.h)
innov_test_status uint16 which inputs exceed the innovation test
innov_mag float
innov_vel float
innov_pos float
innov_hgt float
innov_tas float
innov_hagl float
innov_flow float
innov_beta float
mag_decl float deg Magnetic declination
terrain_status uint8 INVALID, VALID terrain detection for valid for ground sensors
dead_reckoning uint8 INACTIVE, ACTIVE active if all positioning sensors fail

ROTORCRAFT_CAM (ID 168)

Field name Type Unit/Values Description
tilt int16 2^12rad
pan int16 2^12rad

AHRS_REF_QUAT (ID 169)

Field name Type Unit/Values Description
ref_qi int32
ref_qx int32
ref_qy int32
ref_qz int32
body_qi int32
body_qx int32
body_qy int32
body_qz int32

INS_EKF2_EXT (ID 170)

Field name Type Unit/Values Description
gps_drift_h float m/s Horizontal position drift rate (m/s)
gps_drift_v float m/s Vertical position drift rate (m/s)
gps_drift_h_filt float m/s Filtered horizontal velocity (m/s)
gps_drift_blocked uint8 The GPS drift calculation is blocked
gyro_vibe_coning float Gyro delta angle coning metric = filtered length of (delta_angle x prev_delta_angle)
gyro_vibe_hf float Gyro high frequency vibe = filtered length of (delta_angle - prev_delta_angle)
accel_vibe_hf float Accel high frequency vibe = filtered length of (delta_velocity - prev_delta_velocity)

AHRS_BIAS (ID 171)

Field name Type Unit/Values Description
accel_x float m/s^2 Accelerometer bias x-axis
accel_y float m/s^2 Accelerometer bias y-axis
accel_z float m/s^2 Accelerometer bias z-axis
gyro_p float rad/sec Gyrometer bias roll rate
gyro_q float rad/sec Gyrometer bias pitch rate
gyro_r float rad/sec Gyrometer bias yaw rate
mag_x float mGauss Magnetometer x-bias in mGauss
mag_y float mGauss Magnetometer y-bias in mGauss
mag_z float mGauss Magnetometer z-bias in mGauss

AHRS_EULER (ID 173)

Field name Type Unit/Values Description
phi float rad
theta float rad
psi float rad
comp_id uint8 NONE, GENERIC, IR, ICQ, ICE, FC, DCM, FINV, MLKF, GX3, CHIMU, VN

AHRS_MEASUREMENT_EULER (ID 174)

Field name Type Unit/Values Description
phi float rad
theta float rad
psi float rad

WT (ID 175)

Field name Type Unit/Values Description
rpm float

CSC_CAN_DEBUG (ID 176)

Field name Type Unit/Values Description
err_nb uint32
err_code uint32

CSC_CAN_MSG (ID 177)

Field name Type Unit/Values Description
frame uint32
id uint32
data_a uint32
data_b uint32

AHRS_GYRO_BIAS_INT (ID 178)

Field name Type Unit/Values Description
bp int32
bq int32
br int32
comp_id uint8 NONE, GENERIC, IR, ICQ, ICE, FC, DCM, FINV, MLKF, GX3, CHIMU, VN

AEROPROBE (ID 179)

Airflow data returned by OTF and uADC 3D probes from Aeroprobe.

Field name Type Unit/Values Description
counter uint32
velocity int16 cm/s
a_attack int16 centideg
a_sideslip int16 centideg
altitude int32 cm
dynamic_p int32 Pa
static_p int32 Pa
checksum uint8

FMS_TIME (ID 180)

Field name Type Unit/Values Description
tv_sec uint32
tv_nsec uint32
delay_ns uint32

ROTATING_WING_STATE (ID 181)

Field name Type Unit/Values Description
current_state uint8 QUAD, SKEW, FW_THRUST, FW_IDLE, FW, FREE
desired_state uint8 QUAD, SKEW, FW_THRUST, FW_IDLE, FW, FREE
wing_angle_deg float
wing_angle_deg_sp float
ADC_position uint16
pprz_cmd int32

DOUBLET (ID 183)

Field name Type Unit/Values Description
active uint8 Doublet is active
axis uint8 Current doublet axis
amplitude int16 Amplitude
current_value int16 Current doublet value
doublet_mode_3211 uint8 Mode 3211 enabled

GUIDANCE (ID 184)

Field name Type Unit/Values Description
pos_N_ref float m
pos_E_ref float m
pos_D_ref float m
pos_N float m
pos_E float m
pos_D float m
vel_N_ref float m/s
vel_E_ref float m/s
vel_D_ref float m/s
vel_N float m/s
vel_E float m/s
vel_D float m/s
acc_N_ref float m/s^2
acc_E_ref float m/s^2
acc_D_ref float m/s^2
acc_N float m/s^2
acc_E float m/s^2
acc_D float m/s^2
jerk_N float m/s^3
jerk_E float m/s^3
jerk_D float m/s^3

AHRS_LKF (ID 193)

Field name Type Unit/Values Description
phi float rad
theta float rad
psi float rad
qi float
qx float
qy float
qz float
p float rad/s
q float rad/s
r float rad/s
ax float
ay float
az float
mx float
my float
mz float

AIRSPEED_WIND_ESTIMATOR_EKF (ID 196)

Field name Type Unit/Values Description
u_est float m/s
v_est float m/s
w_est float m/s
mu_N float m/s
mu_E float m/s
mu_D float m/s
offset_x float -
offset_y float -
offset_z float -
healthy uint8 bool
crashes_n uint16 -
innov_V_gnd_x float -
innov_V_gnd_y float -
innov_V_gnd_z float -
innov_acc_x float -
innov_acc_y float -
innov_acc_z float -
innov_V_pitot float -
debug_1 float -
debug_2 float -
debug_3 float -

NPS_SENSORS_SCALED (ID 197)

Field name Type Unit/Values Description
acc_x float
acc_y float
acc_z float
mag_x float
mag_y float
mag_z float

INS (ID 198)

Field name Type Unit/Values Description
ins_x int32
ins_y int32
ins_z int32
ins_xd int32
ins_yd int32
ins_zd int32
ins_xdd int32
ins_ydd int32
ins_zdd int32

IMU_GYRO (ID 200)

Field name Type Unit/Values Description
id uint8
gp float rad/s
gq float rad/s
gr float rad/s

IMU_MAG (ID 201)

Field name Type Unit/Values Description
id uint8
mx float
my float
mz float

IMU_ACCEL (ID 202)

Field name Type Unit/Values Description
id uint8
ax float m/s-2
ay float m/s-2
az float m/s-2

IMU_GYRO_RAW (ID 203)

Field name Type Unit/Values Description
id uint8
temp float Celcius
gp int32 adc
gq int32 adc
gr int32 adc

IMU_ACCEL_RAW (ID 204)

Field name Type Unit/Values Description
id uint8
temp float Celcius
ax int32 adc
ay int32 adc
az int32 adc

IMU_MAG_RAW (ID 205)

Field name Type Unit/Values Description
id uint8
mx int32 adc
my int32 adc
mz int32 adc

IMU_MAG_SETTINGS (ID 206)

Field name Type Unit/Values Description
inclination float
declination float
hardiron_x float
hardiron_y float
hardiron_z float

IMU_MAG_CURRENT_CALIBRATION (ID 207)

Field name Type Unit/Values Description
id uint8
mx int32 adc
my int32 adc
mz int32 adc
electrical_current float A

UART_ERRORS (ID 208)

Field name Type Unit/Values Description
overrun_cnt uint16
noise_err_cnt uint16
framing_err_cnt uint16
bus_number uint8

IMU_GYRO_LP (ID 209)

Field name Type Unit/Values Description
gp float rad/s
gq float rad/s
gr float rad/s

IMU_PRESSURE (ID 210)

Field name Type Unit/Values Description
p float pascal

WINDTUNNEL_MEAS (ID 211)

Field name Type Unit/Values Description
aoa float deg Angle of attack
airspeed float m/s Airspeed measured
voltage float V Voltage measured
current float A Current measured
power float W Calculated power (Voltage * Current)
commands int32[] Commands send to actuators

TUNE_VERT (ID 213)

Field name Type Unit/Values Description
z_sp int32
est_z int32
ref_z int32
ref_zd int32

MF_DAQ_STATE (ID 214)

Field name Type Unit/Values Description
flight_time uint16 s
p float
q float
r float
phi float
theta float
psi float
ax float
ay float
az float
ve float
vn float
vu float
lat float
lon float
alt float
we float
wn float

INFO_MSG (ID 215)

Field name Type Unit/Values Description
msg char[]

STAB_ATTITUDE (ID 216)

Field name Type Unit/Values Description
phi float rad
theta float rad
psi float rad
phi_ref float rad
theta_ref float rad
psi_ref float rad
angular_rate_p float rad/s
angular_rate_q float rad/s
angular_rate_r float rad/s
angular_rate_ref_p float rad/s
angular_rate_ref_q float rad/s
angular_rate_ref_r float rad/s
angular_accel_p float rad/s2
angular_accel_q float rad/s2
angular_accel_r float rad/s2
angular_accel_ref_p float rad/s2
angular_accel_ref_q float rad/s2
angular_accel_ref_r float rad/s2
nu float[] none Input of control allocation
u float[] none Output of control allocation

ROTORCRAFT_FP_MIN (ID 217)

Minimalistic message to track Rotorcraft over very low bandwidth links

Field name Type Unit/Values Description
east int32
north int32
up int32
gspeed uint16 cm/s

BEBOP_ACTUATORS (ID 218)

Field name Type Unit/Values Description
cmd_thrust int32
cmd_roll int32
cmd_pitch int32
cmd_yaw int32
rpm_ref_lf uint16 rpm
rpm_ref_rf uint16 rpm
rpm_ref_rb uint16 rpm
rpm_ref_lb uint16 rpm
rpm_obs_lf uint16 rpm
rpm_obs_rf uint16 rpm
rpm_obs_rb uint16 rpm
rpm_obs_lb uint16 rpm

WEATHER (ID 219)

Field name Type Unit/Values Description
p_amb float Pa
t_amb float deg C
windspeed float m/s
wind_from float deg
humidity float %

IMU_TURNTABLE (ID 220)

Field name Type Unit/Values Description
omega float rad/s

BARO_RAW (ID 221)

Field name Type Unit/Values Description
abs float
diff float

AIR_DATA (ID 222)

Field name Type Unit/Values Description
pressure float Pa static pressure
diff_p float Pa differential pressure
temp float deg celcius air temperature
qnh float hPa barometric pressure adjusted to sea level
amsl_baro float m barometric altitude above mean sea level
airspeed float m/s Equivalent Air Speed (or Calibrated Air Speed at low speed/altitude)
tas float True Air Speed (when P, T and P_diff are available)

AMSL (ID 223)

Field name Type Unit/Values Description
AMSL_BARO float ft
AMSL_GPS float ft

DIVERGENCE (ID 224)

Field name Type Unit/Values Description
divergence float vertical velocity / height from optitrack (unit = 1/sec)
divergence_vision float vertical velocity / height from vision (unit = 1/sec)
normalized_thrust float thrust / max thrust paparazzi (-)
cov_div float covariance of divergence and thrust, or past divergence depending on the mode (-)
pstate float gain state in adaptive gain control: indicative of height (-)
pused float gain used for control, includes the effect of the p-gain of adaptive control (-)
sonar float measurement from the sonar (mm)
front_divergence float divergence from front cam

VIDEO_SYNC (ID 225)

Field name Type Unit/Values Description
id uint8

PERIODIC_TELEMETRY_ERR (ID 226)

Field name Type Unit/Values Description
process uint8
mode uint8
id uint8

TIME (ID 227)

Field name Type Unit/Values Description
t uint32 an integral value representing the number of seconds elapsed since 00:00 hours, Jan 1, 1970 UTC

OPTIC_FLOW_EST (ID 228)

Field name Type Unit/Values Description
fps float
corner_cnt uint16
tracked_cnt uint16
flow_x int16 subpixels
flow_y int16 subpixels
flow_der_x int16 subpixels
flow_der_y int16 subpixels
vel_x float m/s
vel_y float m/s
vel_z float m/s
div_size float 1/s
surface_roughness float 1/s
divergence float 1/s
camera_id uint8

STEREO_IMG (ID 229)

Field name Type Unit/Values Description
type uint8 DIST_MATRIX, HISTOGRAM, DISPARITY_MAP, RAW
width uint8
height uint8
package_nb uint8
image_data uint8[]

ROVER_STATUS (ID 230)

Rover status message

Field name Type Unit/Values Description
rc_status uint8 OK, LOST, REALLY_LOST
frame_rate uint8 Hz
gps_status uint8 NO_FIX, NA, 2D, 3D, DGPS, RTK
ap_mode uint8 Rover AP modes are generated from XML file
ap_motors_on uint8 MOTORS_OFF, MOTORS_ON
cpu_time uint16 s
vsupply float V

ROTORCRAFT_STATUS (ID 231)

Field name Type Unit/Values Description
link_imu_nb_err uint32
motor_nb_err uint8
rc_status uint8 OK, LOST, REALLY_LOST
frame_rate uint8 Hz
gps_status uint8 NO_FIX, NA, 2D, 3D, DGPS, RTK
ap_mode uint8 KILL, FAILSAFE, HOME, RATE_DIRECT, ATTITUDE_DIRECT, RATE_RC_CLIMB, ATTITUDE_RC_CLIMB, ATTITUDE_CLIMB, RATE_Z_HOLD, ATTITUDE_Z_HOLD, HOVER_DIRECT, HOVER_CLIMB, HOVER_Z_HOLD, NAV, RC_DIRECT, CARE_FREE, FORWARD, MODULE, FLIP, GUIDED
ap_in_flight uint8 ON_GROUND, IN_FLIGHT
ap_motors_on uint8 MOTORS_OFF, MOTORS_ON
arming_status uint8 NO_RC, WAITING, ARMING, ARMED, DISARMING, KILLED, YAW_CENTERED, THROTTLE_DOWN, NOT_MODE_MANUAL, UNARMED_IN_AUTO, THROTTLE_NOT_DOWN, STICKS_NOT_CENTERED, PITCH_NOT_CENTERED, ROLL_NOT_CENTERED, YAW_NOT_CENTERED, AHRS_NOT_ALLIGNED, OUT_OF_GEOFENCE, LOW_BATTERY
ap_h_mode uint8 KILL, RATE, ATTITUDE, HOVER, NAV, RC_DIRECT, CF, FORWARD, MODULE, FLIP, GUIDED
ap_v_mode uint8 KILL, RC_DIRECT, RC_CLIMB, CLIMB, HOVER, NAV, MODULE, FLIP, GUIDED
cpu_time uint16 s
vsupply float V Main supply voltage
vboard float V AP Board voltage

STATE_FILTER_STATUS (ID 232)

Field name Type Unit/Values Description
id uint8
state_filter_mode uint8 UNKNOWN, INIT, ALIGN, OK, GPS_LOST, IMU_LOST, COV_ERR, IR_CONTRAST, ERROR
value uint16

OPTICAL_FLOW (ID 233)

Field name Type Unit/Values Description
time_sec float s
sensor_id uint8
flow_x int32
flow_y int32
flow_comp_m_x float m
flow_comp_m_y float m
flow_quality uint8
ground_distance float m
distance_compensated float mm
distance_quality uint8

LIDAR (ID 234)

Field name Type Unit/Values Description
distance float m
status uint8 INIT, REQ, READ, PARSE
trans_status uint8 Pending, Running, Success, Failed, Done

VISUALTARGET (ID 235)

Generic message with pixel coordinates of detected targets

Field name Type Unit/Values Description
cnt uint16 Counter
x int16 Center pixel X
y int16 Center pixel X
w int16 Width in pixels
h int16 height in pixels
source uint16 In case many detectors run, which one did find this target

SONAR (ID 236)

Field name Type Unit/Values Description
sonar_meas uint16
sonar_distance float m

PAYLOAD_FLOAT (ID 237)

Field name Type Unit/Values Description
values float[]

NPS_POS_LLH (ID 238)

Field name Type Unit/Values Description
pprz_lat float rad
lat_geod float rad
lat_geoc float rad
pprz_lon float rad
lon float rad
pprz_alt float m
alt_geod float m
agl float m
asl float m

KEY_EXCHANGE_UAV (ID 239)

Message for key exchange during crypto initialization

Field name Type Unit/Values Description
msg_type uint8 P_AE, P_BE, SIG
msg_data uint8[]

NPS_SPEED_POS (ID 240)

Field name Type Unit/Values Description
ltpp_xdd float m/s2
ltpp_ydd float m/s2
ltpp_zdd float m/s2
ltpp_xd float m/s
ltpp_yd float m/s
ltpp_zd float m/s
ltpp_x float m
ltpp_y float m
ltpp_z float m

NPS_RATE_ATTITUDE (ID 241)

Field name Type Unit/Values Description
p float deg/s
q float deg/s
r float deg/s
phi float deg
theta float deg
psi float deg

NPS_GYRO_BIAS (ID 242)

Field name Type Unit/Values Description
bp float deg/s
bq float deg/s
br float deg/s

OPTICAL_FLOW_HOVER (ID 243)

This messages includes the messages send by the Optical Flow Hover module, providing data for all three axes.

Field name Type Unit/Values Description
flowX float Filtered Horizontal velocity in X / height used in Optical Flow Hover
flowY float Filtered Horizontal velocity in X / height used in Optical Flow Hover
Divergence float Filtered vertical velocity / height used in Optical Flow Hover
cov_flowX float covariance of Ventral flow in X and past ventral flow in X
cov_flowY float covariance of Ventral flow in Y and past ventral flow in Y
cov_divZ float covariance of divergence and past divergence or thrust history
pusedX float Gain used in the X feedback
pusedY float Gain used in the Y feedback
pusedZ float Gain used in the Z feedback
sum_errX float Sum of errors in X
sum_errY float Sum of errors in Y
sum_errZ float Sum of errors in Z
thrust int32 The thrust
phi_des float The desired phi angle in degrees
theta_des float The desired theta angle in degrees

NPS_WIND (ID 244)

Field name Type Unit/Values Description
vx float m/s
vy float m/s
vz float m/s

ESC (ID 245)

Electronic Speed Controller data

Field name Type Unit/Values Description
amps float A Current consumption
bat_volts float V Input battery voltage
power float W Electrical power
rpm float rpm Motor rotation speed
motor_volts float V Motor voltage
energy float Wh Accumulated consumed energy
temperature float C Temperature
temperature_dev float C Device temperature
node_id uint8 Node ID
motor_id uint8 Motor ID

RTOS_MON (ID 246)

RTOS monitoring

Field name Type Unit/Values Description
nb_threads uint8 Number of running threads
cpu_load uint8 % Global CPU load
core_free uint32 Bytes Core free memory
heap_free uint32 Bytes Total fragmented free memory in the heap
heap_frags uint32 Fragments Number of fragments in the heap
heap_largest uint32 Bytes Largest free block in the heap
cpu_time float s

PPRZ_DEBUG (ID 247)

Field name Type Unit/Values Description
module uint8
errno uint8

BATTERY_MONITOR (ID 248)

Field name Type Unit/Values Description
version uint8 v3, v4, v5 Battery monitor version
bus_dev_stat uint8 CURRENT, VOLTAGE, TEMP Bus monitor status
bus_trans_stat uint8 Pending, Running, Success, Failed, Done Bus monitor i2c transaction status
current_raw uint16 mV Raw bus current reading
current float A Bus current
bus_voltage uint16 mV Bus voltage
bus_temp_raw uint16[] mV Raw temperature reading
bus_temp float[] C Battery temperatures
bal1_trans_stat uint8 Pending, Running, Success, Failed, Done Cell bank 1 monitor i2c transaction status
bal1_cells uint16[] mV Cell bank 1 voltage
bal2_trans_stat uint8 Pending, Running, Success, Failed, Done Cell bank 2 monitor i2c transaction status
bal2_cells uint16[] mV Cell bank 2 voltage
safety_plug uint16 mV Safety plug voltage

GPS_RXMRTCM (ID 249)

Field name Type Unit/Values Description
Msg1005 uint32
Msg1077 uint32
Msg1087 uint32
Crc1005 uint32
Crc1077 uint32
Crc1087 uint32

EFF_MAT_G (ID 250)

Field name Type Unit/Values Description
G1_aN float[] none
G1_aE float[] none
G1_aZ float[] none
G1_roll float[] none
G1_pitch float[] none
G1_yaw float[] none
G1_thrust float[] none
G2 float[] none

GPS_RTK (ID 251)

Field name Type Unit/Values Description
iTOW uint32 ms
refStationId uint16
relPosN int32 cm
relPosE int32 cm
relPosD int32 cm
relPosHPN int8 mm
relPosHPE int8 mm
relPosHPD int8 mm
accN uint32 mm
accE uint32 mm
accD uint32 mm
carrSoln uint8 NONE, RTK FLOAT, RTK FIX
relPosValid uint8 FALSE, TRUE
diffSoln uint8 NONE, DGPS
gnssFixOK uint8 NONE, 3D

GPS_SMALL (ID 252)

Field name Type Unit/Values Description
multiplex_speed uint32 bits 31-21 course in decideg : bits 20-10 ground speed in cm/s : bits 9-0 climb speed in cm/s
lat int32 1e7deg
lon int32 1e7deg
alt int16 cm height above the ellipsoid

I2C_ERRORS (ID 253)

Field name Type Unit/Values Description
wd_reset_cnt uint16
queue_full_cnt uint16
acknowledge_failure_cnt uint16
misplaced_start_or_stop_cnt uint16
arbitration_lost_cnt uint16
overrun_or_underrun_cnt uint16
pec_error_in_reception_cnt uint16
timeout_or_tlow_error_cnt uint16
smbus_alert_cnt uint16
unexpected_event_cnt uint16
last_unexpected_event uint32
bus_number uint8

DCF_THETA (ID 254)

Air-to-air message for the Distributed Circular Formation algorithm. It transmits the ac's theta to its neighbor

Field name Type Unit/Values Description
theta float

SECURE_LINK_STATUS (ID 255)

Message for monitoring key exchange status

Field name Type Unit/Values Description
sts_stage uint8 INIT, WAIT_MSG1, WAIT_MSG2, WAIT_MSG3, CRYPTO_OK
sts_error uint8 NONE, MSG1_TIMEOUT, MSG1_ENCRYPT, MSG3_TIMEOUT, MSG3_DECRYPT, MSG3_SIGNVERIFY, MSG2_TIMEOUT, MSG2_DECRYPT, MSG2_SIGNVERIFY, MSG3_ENCRYPT, UNEXPECTED_TYPE, UNEXPECTED_STAGE, UNEXPECTED_MSG
counter_err uint32
decrypt_err uint32
encrypt_err uint32

Datalink Messages

ACINFO (ID 1)

Field name Type Unit/Values Description
course int16 decideg
utm_east int32 cm
utm_north int32 cm
utm_zone uint8
alt int32 cm Height above Mean Sea Level (geoid)
itow uint32 ms
speed uint16 cm/s ground speed
climb int16 cm/s
ac_id uint8

MOVE_WP (ID 2)

Field name Type Unit/Values Description
wp_id uint8
ac_id uint8
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm Height above Mean Sea Level (geoid)

WIND_INFO (ID 3)

Wind information. The wind is reported as a vector, it gives the direction the wind is blowing to. This can be comming from the ground wind estimator or from an embedded algorithm. Flags field definition:

  • bit 0: horizontal wind is valid (east and north fields)
  • bit 1: vertical wind is valid (up field)
  • bit 2: airspeed is valid
Field name Type Unit/Values Description
ac_id uint8
flags uint8 bit 0: horizontal wind, bit 1: vertical wind: bit 2: airspeed
east float m/s east component of the wind
north float m/s north component of the wind
up float m/s vertical component of the wind
airspeed float m/s local airspeed norm

SETTING (ID 4)

Field name Type Unit/Values Description
index uint8
ac_id uint8
value float

BLOCK (ID 5)

Field name Type Unit/Values Description
block_id uint8
ac_id uint8

PING (ID 8)

message has no fields

FORMATION_SLOT (ID 9)

Field name Type Unit/Values Description
ac_id uint8
mode uint8
slot_east float m
slot_north float m
slot_alt float m

FORMATION_STATUS (ID 10)

Field name Type Unit/Values Description
ac_id uint8
leader_id uint8
status uint8

JOYSTICK_RAW (ID 11)

This message is used to send joystick input that can be used in any mode for control of the vehicle or the payload depending of the 'joystick_handler' function implementation. The scale of the inputs should be between -PPRZ_MAX (or 0) and PPRZ_MAX.

Field name Type Unit/Values Description
roll int16
pitch int16
yaw int16
throttle int16
ac_id uint8

COMMANDS_RAW (ID 12)

Field name Type Unit/Values Description
ac_id uint8
commands int8[]

DGPS_RAW (ID 13)

Field name Type Unit/Values Description
ac_id uint8
length uint8
rtcm uint8[]

ACINFO_LLA (ID 14)

Field name Type Unit/Values Description
course int16 decideg
lat int32 1e7deg
lon int32 1e7deg
alt int32 cm Height above ellipsoid
itow uint32 ms
speed uint16 cm/s ground speed
climb int16 cm/s
ac_id uint8

DESIRED_SETPOINT (ID 15)

This message is used to set 3D desired vehicle's states such as accelerations or velocities. The 'flag' field can be used at the user convenience to provide indication about the type of value to track (like position, speed, acceleration, ...) or the reference frame (ENU / NED, LTP / body frame, ...)

Field name Type Unit/Values Description
ac_id uint8 AC_ID of the vehicle
flag uint8 Up to the user, for example to distinguish between ENU or NED
ux float Quantity to be tracked in the X axis
uy float Quantity to be tracked in the Y axis
uz float Quantity to be tracked in the Z axis

GET_SETTING (ID 16)

Field name Type Unit/Values Description
index uint8
ac_id uint8

TCAS_RESOLVE (ID 17)

Field name Type Unit/Values Description
ac_id uint8
ac_id_conflict uint8
resolve uint8 NONE, LEVEL, CLIMB, DESCEND

MISSION_GOTO_WP (ID 20)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
wp_east float m
wp_north float m
wp_alt float m altitude above geoid (MSL)
duration float s
index uint8

MISSION_GOTO_WP_LLA (ID 21)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
wp_lat int32 1e7deg
wp_lon int32 1e7deg
wp_alt int32 mm altitude above geoid (MSL)
duration float s
index uint8

MISSION_CIRCLE (ID 22)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
center_east float m
center_north float m
center_alt float m altitude above geoid (MSL)
radius float m
duration float s
index uint8

MISSION_CIRCLE_LLA (ID 23)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
center_lat int32 1e7deg
center_lon int32 1e7deg
center_alt int32 mm altitude above geoid (MSL)
radius float m
duration float s
index uint8

MISSION_SEGMENT (ID 24)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
segment_east_1 float m
segment_north_1 float m
segment_east_2 float m
segment_north_2 float m
segment_alt float m altitude above geoid (MSL)
duration float s
index uint8

MISSION_SEGMENT_LLA (ID 25)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
segment_lat_1 int32 1e7deg
segment_lon_1 int32 1e7deg
segment_lat_2 int32 1e7deg
segment_lon_2 int32 1e7deg
segment_alt int32 mm altitude above geoid (MSL)
duration float s
index uint8

MISSION_PATH (ID 26)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
point_east_1 float m
point_north_1 float m
point_east_2 float m
point_north_2 float m
point_east_3 float m
point_north_3 float m
point_east_4 float m
point_north_4 float m
point_east_5 float m
point_north_5 float m
path_alt float m altitude above geoid (MSL)
duration float s
nb uint8
index uint8

MISSION_PATH_LLA (ID 27)

Field name Type Unit/Values Description
ac_id uint8
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL
point_lat_1 int32 1e7deg
point_lon_1 int32 1e7deg
point_lat_2 int32 1e7deg
point_lon_2 int32 1e7deg
point_lat_3 int32 1e7deg
point_lon_3 int32 1e7deg
point_lat_4 int32 1e7deg
point_lon_4 int32 1e7deg
point_lat_5 int32 1e7deg
point_lon_5 int32 1e7deg
path_alt int32 mm altitude above geoid (MSL)
duration float s
nb uint8
index uint8

MISSION_CUSTOM (ID 28)

Custom navigation pattern or action for mission controller. This will add the mission element correspond to the string identifier 'type' if it has been registered.

Field name Type Unit/Values Description
ac_id uint8 Aircraft ID
insert uint8 APPEND, PREPEND, REPLACE_CURRENT, REPLACE_ALL, REPLACE_NEXT Insertion mode
index uint8 Mission element index, should be unique
type char[5] String identifier of the custom pattern
duration float s Duration of the element or -1 for unlimited
params float[] List of parameters, 12 max

MISSION_UPDATE (ID 29)

Update parameters of a mission element without changing the mission element list or current execution.

Field name Type Unit/Values Description
ac_id uint8 Aircraft ID
index uint8 Index of mission element to update
duration float s Duration of the element, -1 for unlimited, -9 for no change
params float[] List of parameters, 12 max

GOTO_MISSION (ID 30)

Field name Type Unit/Values Description
ac_id uint8
mission_id uint8

NEXT_MISSION (ID 31)

Field name Type Unit/Values Description
ac_id uint8

END_MISSION (ID 32)

Field name Type Unit/Values Description
ac_id uint8

COPILOT_STATUS_DL (ID 33)

Field name Type Unit/Values Description
ac_id uint8
used_memory uint8 % Percentage of used memory (RAM) of the mission computer rounded up to whole percent
timestamp float s Mission computer seconds since startup
used_disk uint8 % Percentage of used disk of the mission computer rounded up to whole percent
status uint8 UNKNOWN, INIT, LOGGING, FAULT Mission computer status
error_code uint8 NONE, IO_ERROR Error codes of the mission computer

CAMERA_PAYLOAD_DL (ID 34)

Field name Type Unit/Values Description
ac_id uint8
error_code uint8 NONE, CAMERA_ERR, DOOR_ERR Error codes of the payload
timestamp float s Payload computer seconds sice startup
used_memory uint8 % Percentage of used memory (RAM) of the payload computer rounded up to whole percent
used_disk uint8 % Percentage of used disk of the payload computer rounded up to whole percent
door_status uint8 UNKNOWN, CLOSE, OPEN Payload door open/close

CAMERA_SNAPSHOT_DL (ID 35)

Field name Type Unit/Values Description
camera_id uint16 Unique camera ID - consists of make,model and camera index
snapshot_image_number uint16 Snapshot number in sequence
camera_state uint8 UNKNOWN, OK, ERROR State of the given camera
snapshot_valid uint8 bool Flag checking whether the last snapshot was valid
array_temp float deg_celsius Imager sensor temperature, NaN if not measured
lens_temp float deg_celsius Lens temperature, NaN if not measured
ac_id uint8

GUIDED_SETPOINT_NED (ID 40)

Set vehicle position or velocity in NED. Frame can be specified with the bits 0-3 Velocity of position setpoint can be specified with the bits 5-7 Flags field definition:

  • bit 0: x,y as offset coordinates
  • bit 1: x,y in body coordinates
  • bit 2: z as offset coordinates
  • bit 3: yaw as offset coordinates
  • bit 4: free
  • bit 5: x,y as vel
  • bit 6: z as vel
  • bit 7: yaw as rate
Field name Type Unit/Values Description
ac_id uint8
flags uint8 bits 0-3: frame, bits 5-7: use as velocity
x float m X position/velocity in NED
y float m Y position/velocity in NED
z float m Z position/velocity in NED (negative altitude)
yaw float rad yaw/rate setpoint

WINDTURBINE_STATUS (ID 50)

Field name Type Unit/Values Description
ac_id uint8
tb_id uint8
sync_itow uint32 ms
cycle_time uint32 ms

RC_3CH (ID 51)

Field name Type Unit/Values Description
throttle_mode uint8 byte_mask
roll int8
pitch int8

RC_4CH (ID 52)

Field name Type Unit/Values Description
ac_id uint8
mode uint8
throttle uint8
roll int8
pitch int8
yaw int8

RC_5CH (ID 53)

Field name Type Unit/Values Description
ac_id uint8
throttle uint8
roll int8
pitch int8
yaw int8
mode int8
kill int8

EXTERNAL_POSE (ID 54)

Position, speed and orientation in local frame from a remote vision system

Field name Type Unit/Values Description
ac_id uint8 AC id for which the data is meant
timestamp uint32 ms Timestamp from the measurement
enu_x float m ENU x position in vision frame
enu_y float m ENU y position in vision frame
enu_z float m ENU z position in vision frame
enu_xd float m/s ENU x speed in vision frame
enu_yd float m/s ENU y speed in vision frame
enu_zd float m/s ENU z speed in vision frame
body_qi float Body quaternion i in vision frame
body_qx float Body quaternion x in vision frame
body_qy float Body quaternion y in vision frame
body_qz float Body quaternion z in vision frame

EXTERNAL_POSE_SMALL (ID 55)

Position, speed and orientation in local frame from a remote vision system Smaller message where position, speed is in cm multiplied by a resolution

Field name Type Unit/Values Description
ac_id uint8 AC id for which the data is meant
timestamp uint32 ms Timestamp from the measurement
enu_pos uint32 ENU position in vision frame(bits 31-21 east position [cm*pos_res] : bits 20-10 north position [cm*pos_res] : bits 9-0 up position [cm*pos_res])
enu_speed uint32 ENU speed in vision frame(bits 31-21 east position [cm*pos_res] : bits 20-10 north position [cm*pos_res] : bits 9-0 up position [cm*pos_res])
heading int16 1e4rad Heading in ENU vision frame

REMOTE_GPS_LOCAL (ID 56)

Position and speed in local frame from a remote GPS or motion capture system Global position transformations are handled onboard if needed

Field name Type Unit/Values Description
ac_id uint8
pad uint8
enu_x float m
enu_y float m
enu_z float m
enu_xd float m/s
enu_yd float m/s
enu_zd float m/s
tow uint32
course float deg

TARGET_POS (ID 57)

Global position, speed and ID a target for functions like Follow Me

Field name Type Unit/Values Description
ac_id uint8
target_id uint8
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm Height above Mean Sea Level (geoid)
speed float m/s Ground speed
climb float m/s Climb speed
course float deg
heading float deg Ground heading

SMARTPROBE (ID 60)

Data from SmartProbe 5-hole probe sensor for wind and turbulence measurements

Field name Type Unit/Values Description
accel float[3] m/s^2 internal accelerometer
gyro float[3] rad/s internal gyrometer
attitude float[4] attitude in normalized quaternion or euler in radians (when last field is lower than -2)
tas float m/s true airspeed
eas float m/s equivalent airspeed
alpha float rad angle of attack
beta float rad angle of sideslip
pressure float Pa static absolute pressure
temperature float Celcius static temperature
rho float kg/m^3 air density
p_diff_C_raw float Pa raw differential pressure for central sensor
t_diff_C_raw float Celcius raw temperature for central sensor
p_diff_H_raw float Pa raw differential pressure for horizontal sensor
t_diff_H_raw float Celcius raw temperature for horizontal sensor
p_diff_V_raw float Pa raw differential pressure for vertical sensor
t_diff_V_raw float Celcius raw temperature for vertical sensor

HITL_IMU (ID 70)

Field name Type Unit/Values Description
gp float rad/s
gq float rad/s
gr float rad/s
ax float m/s-2
ay float m/s-2
az float m/s-2
mx float
my float
mz float
ac_id uint8

HITL_GPS (ID 71)

Field name Type Unit/Values Description
lat float deg
lon float deg
alt float m ellipsoid alt
hmsl float m geoid alt
ecef_vel_x float m/s
ecef_vel_y float m/s
ecef_vel_z float m/s
time float s
fix uint8
ac_id uint8

HITL_UBX (ID 72)

Field name Type Unit/Values Description
class uint8
id uint8
ac_id uint8
ubx_payload uint8[]

HITL_AIR_DATA (ID 73)

Field name Type Unit/Values Description
baro float Pa
airspeed float m/s
aoa float rad
sideslip float rad
update_flag uint8 bit 0: baro, bit 1: airspeed, bit 2: aoa, bit 3: sideslip
ac_id uint8

KITE_COMMAND (ID 96)

Field name Type Unit/Values Description
POWER uint16
TURN uint16

PAYLOAD_COMMAND (ID 97)

Field name Type Unit/Values Description
ac_id uint8
command uint8[]

SET_ACTUATOR (ID 100)

Field name Type Unit/Values Description
value uint16
no uint8
ac_id uint8

CSC_SERVO_CMD (ID 101)

Field name Type Unit/Values Description
servo_1 uint16
servo_2 uint16
servo_3 uint16
servo_4 uint16

BOOZ2_FMS_COMMAND (ID 149)

Field name Type Unit/Values Description
h_mode uint8 KILL, RATE, ATTITUDE, HOVER, NAV
v_mode uint8 KILL, DIRECT, CLIMB_RC, CLIMB, ALT, NAV
v_sp int32
h_sp_1 int32
h_sp_2 int32
h_sp_3 int32
ac_id uint8

BOOZ_NAV_STICK (ID 150)

Field name Type Unit/Values Description
ac_id uint8
vx_sp int8
vy_sp int8
vz_sp int8
r_sp int8

EXTERNAL_FILTER_SOLUTION (ID 151)

Field name Type Unit/Values Description
ac_id uint8
status uint8
x float m
xd float m
y float m
yd float m

ROTORCRAFT_CAM_STICK (ID 152)

Field name Type Unit/Values Description
ac_id uint8
tilt int8
pan int8

GPS_INJECT (ID 153)

Field name Type Unit/Values Description
ac_id uint8
packet_id uint8
data uint8[]

EXTERNAL_MAG_RAW (ID 154)

Field name Type Unit/Values Description
x int16
y int16
z int16

VIDEO_ROI (ID 155)

Field name Type Unit/Values Description
ac_id uint8 The aircraft in which video stream you clicked
startx int32 The x of the upper left corner of the selected area
starty int32 The y of the upper left corner of the selected area
width int32 The width of the selected area
height int32 The height of the selected area
downsized_width int32 The width of the image you received. Added because a module the receives this message does not know how big the image was that was broadcasted

EMERGENCY_CMD (ID 156)

Overcome setting ID and block ID problems in the case of multiboard autopilots like AP/FBW. With this message a KILL command can be sent to AP and FBW at the same time.

Field name Type Unit/Values Description
ac_id uint8
cmd uint8 KILL, STANDBY, LAND

RTCM_INJECT (ID 157)

Field name Type Unit/Values Description
packet_id uint8
data uint8[]

DCF_REG_TABLE (ID 158)

Init the table of an aircraft for the Distributed Circular Formation algorithm. If the nei_id is equal to zero, then you wipe out (clean) the whole table of the aircraft.

Field name Type Unit/Values Description
ac_id uint8 ID of the table's aircraft to be updated
nei_id uint8 ID of the neighbor for the table
desired_sigma int16 Desired angle to have w.r.t. the neighbor

KEY_EXCHANGE_GCS (ID 159)

Message for key exchange during crypto initialization

Field name Type Unit/Values Description
ac_id uint8 ID of the table's aircraft to be updated
msg_type uint8 P_AE, P_BE, SIG
msg_data uint8[]

INFO_MSG_UP (ID 160)

Message from ground to be logged on the drone

Field name Type Unit/Values Description
ac_id uint8
fd uint8 ALL, FLIGHT_RECORDER, PPRZLOG where the message will be logged
msg char[]

Ground Messages

NEW_AIRCRAFT (ID 1)

Field name Type Unit/Values Description
ac_id string

AIRCRAFT_DIE (ID 2)

Field name Type Unit/Values Description
ac_id string

AIRCRAFTS (ID 3)

Field name Type Unit/Values Description
ac_list string

AIRCRAFTS_REQ (ID 4)

message has no fields

SELECTED (ID 5)

Field name Type Unit/Values Description
aircraft_id string

SELECTED_REQ (ID 6)

message has no fields

WIND_CLEAR (ID 7)

Field name Type Unit/Values Description
ac_id string

WIND (ID 8)

Field name Type Unit/Values Description
ac_id string
dir float deg_wind
wspeed float m/s
mean_aspeed float m/s
stddev float m/s

CONFIG_REQ (ID 9)

Field name Type Unit/Values Description
ac_id string

CONFIG (ID 10)

Field name Type Unit/Values Description
ac_id string
flight_plan string url
airframe string url
radio string url
settings string url
default_gui_color string
ac_name string

FLIGHT_PARAM (ID 11)

Field name Type Unit/Values Description
ac_id string
roll float deg
pitch float deg
heading float deg
lat double deg
long double deg
speed float m/s
course float deg
alt float m
climb float m/s
agl float m
unix_time float s (Unix time)
itow uint32 ms
airspeed float m/s

AP_STATUS (ID 12)

Field name Type Unit/Values Description
ac_id string
ap_mode string MANUAL, AUTO1, AUTO2, HOME, FAILSAFE
lat_mode string MANUAL, ROLL_RATE, ROLL, COURSE
horiz_mode string WAYPOINT, ROUTE, CIRCLE
gaz_mode string MANUAL, THROTTLE, CLIMB, ALT
gps_mode string NOFIX, NA, 2D, 3D, DGPS, RTK
kill_mode string OFF, ON
flight_time uint32
state_filter_mode string UNKNOWN, INIT, ALIGN, OK, GPS_LOST, IMU_LOST, COV_ERR, IR_CONTRAST, ERROR

NAV_STATUS (ID 13)

Field name Type Unit/Values Description
ac_id string
cur_block uint8
cur_stage uint8
block_time uint32
stage_time uint32
target_lat double deg
target_long double deg
target_climb float m/s
target_alt float m
target_course float deg
dist_to_wp float m

CAM_STATUS (ID 14)

Field name Type Unit/Values Description
ac_id string
lats string
longs string
cam_target_lat double deg
cam_target_long double deg

ENGINE_STATUS (ID 15)

Field name Type Unit/Values Description
ac_id string
throttle float %
throttle_accu float
rpm float rpm
temp float C
bat float V
amp float A
charge float Ah

SVSINFO (ID 16)

Space Vehicle Information Mainly based on the NAV-SVINFO and NAV-SOL messages of the Ublox UBX protocol.

Field name Type Unit/Values Description
ac_id string
pacc uint16 cm 3D Position Accuracy Estimate
svid string Satellite ID
flags string "flags" field of the UBX NAV-SVINFO message
qi string IDLE, SEARCH, SEARCH, UNUSABLE, CODELOCK, CARRIERLOCK, CARRIERLOCK, RECEIVING Quality indicator
cno string dbHz Carrier to Noise Ratio (Signal Strength)
elev string deg Elevation
azim string deg Azimut
msg_age string s

FLY_BY_WIRE (ID 17)

Field name Type Unit/Values Description
ac_id string
rc_status string OK, LOST, REALLY_LOST
rc_mode string MANUAL, AUTO, FAILSAFE
rc_rate uint8 Hz

INFLIGH_CALIB (ID 19)

Field name Type Unit/Values Description
ac_id string
if_mode string OFF, DOWN, UP
if_value1 float
if_value2 float

WORLD_ENV (ID 20)

Field name Type Unit/Values Description
wind_east float m/s
wind_north float m/s
wind_up float m/s
ir_contrast float
time_scale float
gps_availability uint8 OFF, ON

WORLD_ENV_REQ (ID 21)

Field name Type Unit/Values Description
lat double deg
long double deg
alt float m
east float m
north float m
up float m

CIRCLE_STATUS (ID 22)

Field name Type Unit/Values Description
ac_id string
circle_lat double deg
circle_long double deg
radius int16 m

SEGMENT_STATUS (ID 23)

Field name Type Unit/Values Description
ac_id string
segment1_lat double deg
segment1_long double deg
segment2_lat double deg
segment2_long double deg

MOVE_WAYPOINT (ID 24)

Field name Type Unit/Values Description
ac_id string
wp_id uint8
lat double deg
long double deg
alt float m

GET_DL_SETTING (ID 25)

Field name Type Unit/Values Description
ac_id string
index uint8

DL_SETTING (ID 26)

Field name Type Unit/Values Description
ac_id string
index uint8
value float

JUMP_TO_BLOCK (ID 27)

Field name Type Unit/Values Description
ac_id string
block_id uint8

DL_VALUES (ID 28)

Field name Type Unit/Values Description
ac_id string
values string

RAW_DATALINK (ID 29)

Field name Type Unit/Values Description
ac_id string
message string

WAYPOINT_MOVED (ID 30)

Field name Type Unit/Values Description
ac_id string
wp_id uint8
lat double deg
long double deg
alt float m
ground_alt float m

SURVEY_STATUS (ID 31)

Field name Type Unit/Values Description
ac_id string
east_long double deg
north_lat double deg
west_long double deg
south_lat double deg

TELEMETRY_STATUS (ID 32)

Datalink status reported by Server for the GCS Combines DATLINK_REPORT (telemetry class) and LINK_REPORT (ground class)

Field name Type Unit/Values Description
ac_id string
link_id string
time_since_last_msg float s
rx_bytes uint32
rx_msgs uint32
rx_bytes_rate float bytes/s
tx_msgs uint32
uplink_lost_time uint32 s
uplink_msgs uint16
downlink_msgs uint16
downlink_rate uint16 bytes/s
ping_time float ms

TELEMETRY_ERROR (ID 33)

Report a telemetry error

Field name Type Unit/Values Description
ac_id string
message string

TELEMETRY_MESSAGE (ID 34)

Encapsulated a telemetry class message (when using redundant link)

Field name Type Unit/Values Description
ac_id string
link_id string
message string

DATALINK_MESSAGE (ID 35)

Encapsulated a datalink class message (when using redundant link)

Field name Type Unit/Values Description
ac_id string
link_id string
message string

LINK_REPORT (ID 36)

Datalink status reported by Link for the Server

Field name Type Unit/Values Description
ac_id string
link_id string
run_time uint32 s
rx_lost_time uint32 s
rx_bytes uint32
rx_msgs uint32
rx_err uint32
rx_bytes_rate float bytes/s
rx_msgs_rate float msgs/s
tx_msgs uint32
ping_time float ms

INTRUDER (ID 37)

Field name Type Unit/Values Description
id string
name string
lat int32 1e7deg
lon int32 1e7deg
alt int32 mm altitude above WGS84 reference ellipsoid
course float deg
speed float m/s
climb float m/s
itow uint32 ms

SHAPE (ID 38)

The SHAPE message used to draw shapes onto the Paparazzi GCS. Field name shape is used to define the type of shape i.e. Circle, Polygon, Line, or Text. This is indexed from 0-3 respectively.

Each shape drawn must have an id number associated with it. This id number in conjuction with the shapetype will be needed to update or delete the shape. A circle can be defined with the same id as a polygon but since they have different shape types they are considered unique.

linecolor and fillcolor take in a color string ie: "red", "blue"

opacity will change the level of transparency of the fill. 0 - Transparent 1 - Light Fill 2 - Medium Fill 3 - Opaque

Passing a status of 0 will create or update the shape specified by id and type. Passing a status of 1 will delete the shape specified by id and type.

latarr is an array of coordinates that contain the latitude coordinate for each point in the shape. The array is comma separated. lonarr is similar to latarr but contain the longitude coordinate for each point in the shape.

Circle and Text type will take the first coordinates given to place the shape. Polygon will take all the coordinates given. Line will take the first two coordinates given.

Radius is only used for the circle.

Text will always be populated with each message using the first set of coordinates. The text field can not be blank or have spaces. If text is not desired for a shape then pass "NULL" into the text field.

Field name Type Unit/Values Description
id uint8
linecolor string
fillcolor string
opacity uint8 Transparent, Light, Medium, Opaque
shape uint8 Circle, Polygon, Line
status uint8 create, delete
latarr int32[] 1e7deg
lonarr int32[] 1e7deg
radius float m
text string

DL_EMERGENCY_CMD (ID 39)

Field name Type Unit/Values Description
ac_id string
cmd uint8 KILL, STANDBY, LAND

GROUND_REF (ID 40)

Ground reference provided by an external positioning system for instance

Field name Type Unit/Values Description
ac_id string Aircraft ID
frame string LLA, ECEF, UTM, LTP_NED, LTP_ENU position reference frame
pos float[3] SI (m or deg) position in selected frame
speed float[3] m/s speed in selected frame (LTP_NED in case of LLA frame)
quat float[4] Unitary quaternion representing LTP to BODY orientation (qi, qx, qy, qz)
rate float[3] rad/s Rotation speeds in body frame
timestamp float s Timestamp

JOYSTICK (ID 41)

Generic 4 axis and 4 buttons joystick or joypad. This message can be provided by the 'input2ivy' tool for other ground agents. Standard joystick axis values are on 16 bits signed integers, but tools like 'input2ivy' may scale them on int8 type.

Field name Type Unit/Values Description
id uint8 Joystick ID
axis1 int16 axis 1 position
axis2 int16 axis 2 position
axis3 int16 axis 3 position
axis4 int16 axis 4 position
button1 uint8 bool button 1 status
button2 uint8 bool button 2 status
button3 uint8 bool button 3 status
button4 uint8 bool button 4 status

PLUMES (ID 100)

Field name Type Unit/Values Description
ids string
lats string
longs string
values string

INFO_MSG_GROUND (ID 101)

Message from ground to be logged on the drone or send to other ground agents

Field name | Type | Unit/Values | Description | --------—|---—|----------—|----------—| dest | string | | ac_id:file_descriptor | ground_name | 0 (ground broadcast) | 0xFF (broadcast) | source | string | | ground_name of the agent sending the message | msg | string | | |

Alert Messages

BAT_LOW (ID 1)

Field name Type Unit/Values Description
ac_id string
level string CATASTROPHIC, CRITIC, WARNING
value float

AIR_PROX (ID 2)

Field name Type Unit/Values Description
ac_id string
level string CATASTROPHIC, CRITIC, WARNING

Intermcu Messages

IMCU_COMMANDS (ID 1)

Field name Type Unit/Values Description
status uint8
values int16[]

IMCU_RADIO_COMMANDS (ID 2)

Field name Type Unit/Values Description
status uint8
values int16[]

IMCU_SPEKTRUM_SOFT_BIND (ID 3)

message has no fields

IMCU_FBW_STATUS (ID 4)

Field name Type Unit/Values Description
mode uint8 MANUAL, AUTO, FAILSAFE
rc_status uint8 OK, LOST, REALLY_LOST
frame_rate uint8 Hz
vsupply float V
current float A

IMCU_REMOTE_MAG (ID 10)

Field name Type Unit/Values Description
mag_x int16 RAW Magnetometer Data
mag_y int16
mag_z int16

IMCU_REMOTE_BARO (ID 11)

Field name Type Unit/Values Description
pitot_stat float Pa Static Barometric Pressure in Pascal
pitot_temp float C Pressure Sensor Temperature

IMCU_REMOTE_AIRSPEED (ID 12)

Field name Type Unit/Values Description
pitot_IAS float m/s Indicated Airspeed

IMCU_REMOTE_GROUND (ID 15)

Field name Type Unit/Values Description
mode uint8 SWITCH, SONAR, LASER, INFRARED
id uint8 Sensor ID
range uint16 cm

IMCU_REMOTE_GPS (ID 62)

Field name Type Unit/Values Description
ecef_x int32 cm
ecef_y int32 cm
ecef_z int32 cm
alt int32 mm altitude above WGS84 reference ellipsoid
hmsl int32 mm height above mean sea level (geoid)
ecef_xd int32 cm/s
ecef_yd int32 cm/s
ecef_zd int32 cm/s
course int32
gspeed uint16 cm/s
pacc uint32 cm
sacc uint32 cm/s
numsv uint8
fix uint8 NONE, NA, 2D, 3D, DGPS, RTK

STEREOCAM_ARRAY (ID 80)

Raw data fromt the stereocamera. Type defines what kind of data it is. This can be raw image, disparity map, obstacle histogram, ect.

Field name Type Unit/Values Description
type uint8 DIST_MATRIX, HISTOGRAM, DISPARITY_MAP, RAW
width uint8 array size parameters
height uint8
package_nb uint8 If the data being sent is too large for one message (e.g when sending a full image) this will indicate which package of the total data is contained in this message
image_data uint8[]

STEREOCAM_VELOCITY (ID 81)

Velocity measured using optical flow and stereovision. All parameters are in the camera frame

Field name Type Unit/Values Description
resolution uint8 Resolution of the vel and pos messages
dt_frame uint8 Time difference to previous frame
dt uint8 Time difference to previous message, not strictly required
velx int16 m/s Velocity estimaed using stereo edgeflow
vely int16 m/s
velz int16 m/s
dposx int16 m Distance traveled since the last message
dposy int16 m
dposz int16 m
vRMS uint8 RMS of the velocity estimate
posRMS uint8 RMS of the position
avg_dist uint16 Average distance to scene

STEREOCAM_STATE (ID 82)

Estimated state of the camera. As the stereocamera has no inertial sensors, this data should be sent to the stereocamera to enable onboard derotation of the optical flow

Field name Type Unit/Values Description
phi float rad Pitch, roll and yaw angles of the camera
theta float rad
psi float rad
agl float m Altitude above the ground. If not looking down, set to 0

STEREOCAM_FOLLOW_ME (ID 83)

Field name Type Unit/Values Description
headingToFollow uint8
heightObject uint8
distanceToObject uint8

IMCU_DATALINK (ID 113)

Forward FBW datalink to AP

Field name Type Unit/Values Description
msg uint8[]

IMCU_TELEMETRY (ID 114)

Forward AP telemetry to FBW

Field name Type Unit/Values Description
msg uint8[]

IMCU_DEBUG (ID 115)

Field name Type Unit/Values Description
msg uint8[]

IMCU_PAYLOAD (ID 116)

Field name Type Unit/Values Description
data uint8[]