Telemetry list#

  • Flight sensors data: barometer, battery, GPS, IMU, magnetometer, motors, TOF

  • Flight data: altitude, angles, position, velocity

  • Camera stabilization data: angles, position

  • Camera settings

Telemetry data are available in shared memory for all processes. Data are separated in sections. Each section contains a circular buffer of timestamped samples provided by a producer. Consumers can query data at a specific timestamp. The updating rates depend on the producer. Timestamps are given in seconds and nanoseconds according to the monotonic clock.

Flight#

Drone#

section drone_controller

This section runs at 200Hz.

float32 position_global.x
float32 position_global.y
float32 position_global.z

position_global is the estimated position of the drone in the Global frame (m), computed by fusing flight sensors.

The x,y position is initialized at {0, 0}m either at the location of the first GPS fix or at the location of the first take-off, whichever happens first. The z position is initialized at 0m at each ground take-off and -1m on hand launch take-off.

During the flight, the fusion algorithm uses GPS measures of position/velocity only when magnetometer measures are valid (calibrated, no magnetic interference). Otherwise the x,y position estimation continues in odometry using IMU/Cameras/TOF estimations.

Long running times without GPS may result in a position drift. When GPS/magnetometer signal becomes valid, this position jumps to it.

When landed, the position x,y is updated from raw GPS positions under the same GPS/magnetometer acceptance rules. IMU/Cameras/TOF odometry does not run when the drone is landed.

float64 position_geo.latitude_north_deg
float64 position_geo.longitude_east_deg

The drone position in Geographic coordinates: latitude (North) and longitude (East) are in degrees.

Before the first GPS fix (as the estimation algorithm has no knowledge of its location on Earth), both values are set to {500, 500}°.

Once there is a GPS fix, the same logic as position_global is followed. When landed, the position values are updated from raw GPS positions even if the magnetometer is invalid.

float32 position_local.x
float32 position_local.y
float32 position_local.z

position_local is the estimated position of the drone in the Local frame (m).

float32 position_offset_local_to_global.x
float32 position_offset_local_to_global.y

The difference between position_local and position_global is: position_local is not updated by the GPS fix. It is a continuous estimate. position_global is updated by the GPS fix and may be discontinuous.

The x,y position is initialized at {0, 0}m at power-on and at the first take-off.

During the flight, when the fusion algorithm switches from one sensor to another, like from IMU/Cameras/TOF estimation to GPS/magnetometer, it absorbs any discontinuity. It is intended as input for position control loops, since they require smooth continuous position estimates. Value of discontinuities is cumulated over time during flight. This cumulated value is the difference between position_local and position_global.

When landed, the position fusion algorithm does not run. Hence position_local is maintained constant. There is no reset to {0, 0}m between successive flights while the drone is powered on.

float32 altitude_ato

Altitude of the drone above take-off (m), positive upward.

float32 altitude_agl

Altitude of the drone above ground level (m), positive upward.

float32 takeoff_altitude_amsl

Altitude at take-off above the mean sea level (m), positive upward.

float32 attitude_ned_q.w
float32 attitude_ned_q.x
float32 attitude_ned_q.y
float32 attitude_ned_q.z

Estimated attitude quaternion of the drone in NED basis.

float32 attitude_ned_start_q.w
float32 attitude_ned_start_q.x
float32 attitude_ned_start_q.y
float32 attitude_ned_start_q.z

Estimated attitude quaternion of the drone in NED_start basis.

float32 yaw_offset_ned_start_to_ned

Yaw offset between NED basis and NED_start basis (rad).

float32 linear_velocity_global.x
float32 linear_velocity_global.y
float32 linear_velocity_global.z

Drone linear velocity relatively to the Global frame (m/s).

Pilot#

section pilot_estimation

Pilot uses mobile device GPS and barometer data, and optionally visual tracking.

float32 position_global.x
float32 position_global.y
float32 position_global.z

Pilot position in Global frame (m).

float32 linear_velocity_global.x
float32 linear_velocity_global.y
float32 linear_velocity_global.z

Pilot linear velocity in Global frame (m/s).

float64 position_geo.latitude_north_deg
float64 position_geo.longitude_east_deg

Pilot position in Geographic coordinates (°).

float32 distance_3d

3D distance between the drone and the pilot (m).

float32 course

Pilot trajectory orientation relative to the north.

Computer vision#

section cv@tracking@proposals
uint32 count

Number of valid boxes available in the array of boxes described in box right below. Value is between 0 and 10.

float32 box.x
float32 box.y
float32 box.width
float32 box.height
uint32 box.class_id
float32 box.confidence
uint32 box.track_id
  • x, y relative position [0; 1] in picture.

  • width, height dimensions [0; 1] relative to picture.

  • class_id type of tracked object:

    • 1: Animal

    • 2: Bicycle

    • 3: Boat

    • 4: Car

    • 5: Horse

    • 6: Motorbike

    • 7: Person

  • confidence tracking confidence [0; 1].

  • track_id box unique identifier (UID). Multiple BoundingBox messages. sharing the same UID refers to the same bounding box.

section cv@tracking@box

The tracking box is the box selected by the user.

uint32 status

Tracking status.

  • 0: Inactive

  • 1: Tracking

  • 2: Searching

  • 3: Abandon

float32 box.x
float32 box.y
float32 box.width
float32 box.height
uint32 box.class_id
float32 box.confidence
uint32 box.track_id
  • x, y relative position [0; 1] in picture.

  • width, height dimensions [0; 1] relative to picture.

  • class_id type of tracked object:

    • 1: Animal

    • 2: Bicycle

    • 3: Boat

    • 4: Car

    • 5: Horse

    • 6: Motorbike

    • 7: Person

  • confidence tracking confidence [0; 1].

  • track_id box unique identifier (UID). Multiple BoundingBox messages. sharing the same UID refers to the same bounding box.

uint32 tag_id

Cookie value passed by the mobile application when the tracking is started.

uint8 quality

Tracking quality ([0; 255], 0 is worst, 255 is best).

Flight sensors#

Barometer#

Barometer sensor data run at 75Hz.

section sensors_barometer
float32 pressure

Pressure value of barometer sensor (Pa).

float32 temperature

Temperature value of barometer sensor (K).

Battery#

Battery sensor data run at 1Hz.

section sensors_battery
float32 voltage

Battery voltage (V).

float32 current

Battery current (A). Negative when the battery is being discharged.

uint32 capacity

Battery capacity also referred as state of charge, as an integer percentage of full capacity. From 100 to 0.

float32 full_charge_cap

Battery full charge capacity (Ah).

float32 remaining_cap

Battery remaining capacity (Ah).

int32 time_to_empty

Estimated time to be empty (s). Based on the average current.

float32 temperature

Temperature value of battery sensor (K).

int32 soh

Battery state of health, as an integer percentage of full health. From 100 to 0.

int32 cycle_count

Battery cycle count.

float32 cell_voltage

Battery voltage per cell, [0] to [2] for each cell (V).

GPS#

GPS sensor data run at 5Hz.

section sensors_gps
float64 location.latitude
float64 location.longitude
float64 location.altitude_amsl
float64 location.altitude_wgs84

GPS data location.

  • latitude (North) and longitude (East) in degrees.

  • altitude_amsl altitude above the mean sea level (m).

  • altitude_wgs84 altitude above the WGS 84 ellipsoid (m).

int32 extra.sat_used_count
float32 extra.latitude_accuracy
float32 extra.longitude_accuracy
float32 extra.altitude_accuracy
float32 extra.east_velocity
float32 extra.north_velocity
float32 extra.up_velocity
float32 extra.velocity_accuracy
  • sat_used_count number of satellites used.

  • latitude_accuracy, longitude_accuracy and altitude_accuracy (m).

  • east_velocity, north_velocity and up_velocity (m/s).

  • velocity_accuracy (m/s).

IMU#

IMU sensor data run at 2000Hz. As the processing runs at 200Hz, 10 values are provided at every sample.

section sensors_imu
float32 gyro[10].x
float32 gyro[10].y
float32 gyro[10].z

Gyroscope data in Body basis (rad/s).

float32 acc[10].x
float32 acc[10].y
float32 acc[10].z

Accelerometer data in Body frame (m/s²).

float32 temperature[10]

Temperature value of IMU sensor (K).

uint64 timestamp[10].tv_sec;
uint64 timestamp[10].tv_nsec;

Timestamp of every value read on sensor (s,ns).

Magnetometer#

Magnetometer sensor data run at 100Hz.

section sensors_magnetometer
float32 magnetic_field_ut.x;
float32 magnetic_field_ut.y;
float32 magnetic_field_ut.z;

Magnetic field strength in Body basis (µT).

float32 temperature

Temperature value of magnetometer sensor (K).

Motors#

The first motor [0] is the front left motor. The others are numbered clockwise. Motors sensors data run at 200Hz.

section sensors_motors
int32 braking
int32 ramping
int32 spinning
int32 nominal
int32 idle

Motors state.

uint16 speeds[4].rpm;
uint8 speeds[4].pwm;
uint8 speeds[4].saturated;
  • rpm is the actual motor speed (revolutions per minute).

  • pwm represents power delivered to the motor by the ESC (pulse width modulation).

  • saturated 1 if the motor has reached speed limit.

int32 errors[4]

Motors errors code

  • 0: Nominal case, no error detected

  • 1: Reading/writing error in EEPROM

  • 2: Underspeed detection (motor stalled per example)

  • 3: Propeller block detection

  • 4: Timeout communication loss

  • 5: Power stage error (overcurrent/overtemperature/undervoltage)

  • 6: Reserved

  • 7: Reserved

  • 8: ESC temperature is too low/high

  • 9: Battery voltage is too low/high

  • 10: Number of battery cells incompatible

  • 11: Detection of defective MOSFET or motor miswired or broken

  • 12: Reserved

  • 13: Reserved

int32 status[4]

Firmware status.

  • 0: ESC begins system initialization and self-test

  • 1: ESC is waiting for the command START_PROP. Motors are at rest.

  • 2: Motors are ramping

  • 3: Reserved

  • 4: Nominal state, ESC runs motors in close loop

  • 5: Motors are stopping

  • 6: ESC has killed itself

float32 voltage

ESC voltage (V).

Time of Flight sensor (ToF)#

ToF measures downward distance. This section runs at 75Hz.

section sensors_tof_0
float32 distance

Distance to obstacle (m).

float32 magnitude

Signal magnitude decreases with distance and low IR reflectivity from the ground or the obstacle.

float32 temperature

Temperature value of ToF sensor (K).

float32 ambient

Ambient IR luminosity. The value increases with IR ambient light.

int32 qualification

Measure qualification. 0 is the nominal case, other values indicate the measure is not valid.

  • 0: Nominal case, no error detected.

  • 1: Distance is above the maximum (14.8m)sensor range.

  • 2: Distance is below the minimum (0.07m) sensor range.

  • 3: Signal magnitude is too low.

  • 4: Calibration missing.

Camera stabilization#

Front camera#

section fcam@eis@video

Sample rate matches the current video framerate (30-240Hz).

float32 hfov

Horizontal field of view of the current frame (rad), based on the current video mode and zoom level.

float32 vfov

Vertical field of view of the current frame (rad), based on the current video mode and zoom level.

float32 view_ned_start_q.w
float32 view_ned_start_q.x
float32 view_ned_start_q.y
float32 view_ned_start_q.z

Attitude quaternion of the current frame in NED_start basis.

section fcam@eis@photo

One sample is recorded each time a photo is taken.

float32 hfov

Horizontal field of view of the photo (rad), based on the current photo mode and zoom level.

float32 view_ned_start_q.w
float32 view_ned_start_q.x
float32 view_ned_start_q.y
float32 view_ned_start_q.z

Attitude quaternion of the photo in NED_start basis.

section fcam_imu

Sample rate of 8 kHz.

float32 gyro.x;
float32 gyro.y;
float32 gyro.z;

Unbiased angular velocity of the front camera IMU with respect to an inertial reference basis, expressed in the IMU-fixed reference basis (rad/s).

Front stereo camera#

section fstcam@pose

Sample rate of 30 Hz.

float32 orientation_ned_q.w
float32 orientation_ned_q.x
float32 orientation_ned_q.y
float32 orientation_ned_q.z

Orientation of the front stereo camera in Global frame.

float32 position_global.x
float32 position_global.y
float32 position_global.z
float32 position_local.x
float32 position_local.y
float32 position_local.z

position_global:and position_local are estimated positions of the center of the front right stereo image sensor in Global frame (m). The difference between global and local position is explained here.

section fstcam_imu

Sample rate of 1 kHz.

float32 gyro.x
float32 gyro.y
float32 gyro.z

Unbiased angular velocity of the front stereo IMU with respect to an inertial reference frame, expressed in the IMU-fixed reference frame (rad/s).

Camera settings#

Front camera#

section fcam@settings@photo

One sample is recorded each time a picture is taken.

Some fields have codes defined in: “Exchangeable image file format for digital still cameras: Exif Version 2.3”, available online. Some fields regarding camera models are described in the support page of Pix4D: https://support.pix4d.com/hc/en-us/articles/360016450032-Specifications-of-xmpcamera-tags

float32 exposure_time

Exposure time (s).

uint16 exposure_program

Program used for exposure, as documented by the Exif specification. The default program 2 corresponds to “normal”.

uint16 metering_mode

Metering mode used for auto exposure, as documented by the Exif specification. The default mode 2 corresponds to “center weighted average”.

int32 photographic_sensitivity

Camera ISO sensitivity.

float64 exposure_bias_value

Exposure bias value (EV).

uint16 light_source

Light source when white balance is set to manual, as documented by the Exif specification.

int32 pixel_x_dimension

Picture width (px).

int32 pixel_y_dimension

Picture height (px).

uint16 exposure_mode

Exposure mode, as documented by the Exif specification. The default mode 0 corresponds to “auto exposure”.

uint16 white_balance

White balance mode, as documented by the Exif specification. The default mode 0 corresponds to “auto white balance”.

float32 awb_r_gain

White balance red gain.

float32 awb_b_gain

White balance blue gain.

float64 focal_length

Focal length of the lens (mm).

float64 focal_length_in_35mm_film

Indicates the equivalent focal length assuming a rectilinear 35mm film camera (mm).

float32 f_number

F-number of the camera.

float64 focal_plane_x_resolution

The number of pixels per cm on the camera focal plane in the image width direction (px/cm).

float64 focal_plane_y_resolution

The number of pixels per cm on the camera focal plane in the image height direction (px/cm).

uint16 contrast

Contrast style, as documented by the Exif specification. The default style 0 corresponds to “normal”.

uint16 saturation

Saturation style, as documented by the Exif specification. The default style 0 corresponds to “normal”.

uint16 sharpness

Sharpness style, as documented by the Exif specification. The default style 0 corresponds to “normal”.

float32 principal_point_x

Coordinates of the principal point in the image width direction (mm).

float32 principal_point_y

Coordinates of the principal point in the image height direction (mm).

uint16 model_type

Camera model type. One of perspective or fisheye as described in the support page of Pix4D mapper.

  • 0: Fisheye

    float32 fisheye.c;
    float32 fisheye.d;
    float32 fisheye.e;
    float32 fisheye.f;
    float32 fisheye.p2;
    float32 fisheye.p3;
    float32 fisheye.p4;
    uint8 fisheye.affine_symmetric;
  • 1: Perspective

float32 perspective.r1
float32 perspective.r2
float32 perspective.r3
float32 perspective.t1
float32 perspective.t2
section fcam@settings@video

Sample rate matches the current video framerate (30-240Hz).

float32 exposure_time

Exposure time (s).

float32 digital_gain

Digital gain applied by the sensor.

float32 analog_gain

Analog gain applied by the sensor.

float32 isp_gain

Digital gain applied by the ISP.

float32 awb_r_gain

White balance red gain.

float32 awb_b_gain

White balance blue gain.

Vertical camera#

Vertical camera settings data run at 60 Hz.

section vcam@settings@video
float64 exposure_time

Exposure time (s).

float32 analog_gain

Analog gain applied by the sensor.

float32 digital_gain

Digital gain applied by the sensor.

uint32 luminance

Estimated gray level of the camera image, from 0 (black) to 255 (white).

int32 luminance_error

Difference between the target and estimated gray level of the camera image. The target gray level is set by the camera auto-exposure algorithm. When positive, the image is under-exposed. When negative, the image is over-exposed.

Stereo camera#

Stereo camera settings data run at 30 Hz.

section fstcam@settings@video
float64 exposure_time

Exposure time for both sensors (s).

float32 analog_gain

Analog gain applied by both sensors.

float32 digital_gain

Digital gain applied by both sensors.

uint32 luminance

Estimated gray level of the right camera image, from 0 (black) to 255 (white).

int32 luminance_error

Difference between the target and estimated gray level of the right camera image. The target gray level is set by the camera auto-exposure algorithm. When positive, the image is under-exposed. When negative, the image is over-exposed.

Wi-Fi#

section wifid
uint32 goodput

Wi-Fi link throughput estimation (Mbits/s).

uint32 link_quality

Wi-Fi link quality. The quality varies from “0” to “5”. “0” means that a disconnection is highly probable, “5” means that the link signal quality is very good.

int8 rssi

Received signal strength indication (dBm). Between -20 (very good signal level) and -90 (very bad signal level), 0 if undefined.