Telemetry Topics

This group documents all data telemetry topics that can be subscribed to. More...

Enumerations

enum  DJI::OSDK::Telemetry::TopicName {
  DJI::OSDK::Telemetry::TOPIC_QUATERNION,
  DJI::OSDK::Telemetry::TOPIC_ACCELERATION_GROUND,
  DJI::OSDK::Telemetry::TOPIC_ACCELERATION_BODY,
  DJI::OSDK::Telemetry::TOPIC_ACCELERATION_RAW,
  DJI::OSDK::Telemetry::TOPIC_VELOCITY,
  DJI::OSDK::Telemetry::TOPIC_ANGULAR_RATE_FUSIONED,
  DJI::OSDK::Telemetry::TOPIC_ANGULAR_RATE_RAW,
  DJI::OSDK::Telemetry::TOPIC_ALTITUDE_FUSIONED,
  DJI::OSDK::Telemetry::TOPIC_ALTITUDE_BAROMETER,
  DJI::OSDK::Telemetry::TOPIC_ALTITUDE_OF_HOMEPOINT,
  DJI::OSDK::Telemetry::TOPIC_HEIGHT_FUSION,
  DJI::OSDK::Telemetry::TOPIC_GPS_FUSED,
  DJI::OSDK::Telemetry::TOPIC_GPS_DATE,
  DJI::OSDK::Telemetry::TOPIC_GPS_TIME,
  DJI::OSDK::Telemetry::TOPIC_GPS_POSITION,
  DJI::OSDK::Telemetry::TOPIC_GPS_VELOCITY,
  DJI::OSDK::Telemetry::TOPIC_GPS_DETAILS,
  DJI::OSDK::Telemetry::TOPIC_RTK_POSITION,
  DJI::OSDK::Telemetry::TOPIC_RTK_VELOCITY,
  DJI::OSDK::Telemetry::TOPIC_RTK_YAW,
  DJI::OSDK::Telemetry::TOPIC_RTK_POSITION_INFO,
  DJI::OSDK::Telemetry::TOPIC_RTK_YAW_INFO,
  DJI::OSDK::Telemetry::TOPIC_COMPASS,
  DJI::OSDK::Telemetry::TOPIC_RC,
  DJI::OSDK::Telemetry::TOPIC_GIMBAL_ANGLES,
  DJI::OSDK::Telemetry::TOPIC_GIMBAL_STATUS,
  DJI::OSDK::Telemetry::TOPIC_STATUS_FLIGHT,
  DJI::OSDK::Telemetry::TOPIC_STATUS_DISPLAYMODE,
  DJI::OSDK::Telemetry::TOPIC_STATUS_LANDINGGEAR,
  DJI::OSDK::Telemetry::TOPIC_STATUS_MOTOR_START_ERROR,
  DJI::OSDK::Telemetry::TOPIC_BATTERY_INFO,
  DJI::OSDK::Telemetry::TOPIC_CONTROL_DEVICE,
  DJI::OSDK::Telemetry::TOPIC_HARD_SYNC,
  DJI::OSDK::Telemetry::TOPIC_GPS_SIGNAL_LEVEL,
  DJI::OSDK::Telemetry::TOPIC_GPS_CONTROL_LEVEL,
  DJI::OSDK::Telemetry::TOPIC_RC_FULL_RAW_DATA,
  DJI::OSDK::Telemetry::TOPIC_RC_WITH_FLAG_DATA,
  DJI::OSDK::Telemetry::TOPIC_ESC_DATA,
  DJI::OSDK::Telemetry::TOPIC_RTK_CONNECT_STATUS,
  DJI::OSDK::Telemetry::TOPIC_GIMBAL_CONTROL_MODE,
  DJI::OSDK::Telemetry::TOPIC_FLIGHT_ANOMALY,
  DJI::OSDK::Telemetry::TOPIC_POSITION_VO,
  DJI::OSDK::Telemetry::TOPIC_AVOID_DATA,
  DJI::OSDK::Telemetry::TOPIC_HOME_POINT_SET_STATUS,
  DJI::OSDK::Telemetry::TOPIC_HOME_POINT_INFO,
  DJI::OSDK::Telemetry::TOPIC_DUAL_GIMBAL_DATA,
  DJI::OSDK::Telemetry::TOPIC_THREE_GIMBAL_DATA,
  TOTAL_TOPIC_NUMBER
}
 enum TopicName is the interface for user to create packages and access data It is also used as index for TopicDataBase. More...
 

Detailed Description

This group documents all data telemetry topics that can be subscribed to.

Note
This list does not include the data that is available through the older 'broadcast'-style telemetry

Enumeration Type Documentation

◆ TopicName

enum TopicName is the interface for user to create packages and access data It is also used as index for TopicDataBase.

Note
Please see dji_telemetry_doc.hpp (Or the API reference on the developer website) for detailed documentation.

Enum, containing all the telemetry values

Enumerator
TOPIC_QUATERNION 

Provides quaternion representing ground frame (NED) to body frame (FRD) rotation @ up to 200Hz.

The DJI quaternion follows Hamilton convention (q0 = w, q1 = x, q2 = y, q3 = z)

Performance Benchmarking Data :
Angle Unit Accuracy Notes
pitch, roll deg <1 in non-ahrs mode
yaw deg <3 in well-calibrated compass with fine aligned
yaw with rtk deg around 1.2 in RTK heading fixed mode with 1 meter baseline
Sensing Sources : IMU, Visual Odometry (M210 only)
Supported Platforms : M210V2,M300
Measurement Unit : rad (when converted to a rotation matrix or Euler angles)

Data Structure : Quaternion

TOPIC_ACCELERATION_GROUND 

Provides aircraft's acceleration w.r.t a ground-fixed NEU frame @ up to 200Hz.

Warning
Please note that this data is not in a conventional right-handed frame of reference.

This is a fusion output from the flight control system. The output is in a right-handed NED frame, but the sign of the Z-axis acceleration is flipped before publishing to this topic. So if you are looking to get acceleration in an NED frame, simply flip the sign of the z-axis value. Beyond that, you can convert using rotations to any right-handed frame of reference.

Supported Platforms : M210V2,M300
Measurement Unit : m/s2

Data Structure : Vector3f

TOPIC_ACCELERATION_BODY 

Provides aircraft's acceleration w.r.t a body-fixed FRU frame @ up to 200Hz.

Warning
Please note that this data is not in a conventional right-handed frame of reference.

This is a fusion output from the flight control system.

Supported Platforms : M210V2,M300
Measurement Unit : m/s2

Data Structure : Vector3f

TOPIC_ACCELERATION_RAW 

Provides aircraft's acceleration in an IMU-centered, body-fixed FRD frame @ up to 400Hz.

This is a filtered output from the IMU on board the flight control system.

Sensing Sources : IMU
Supported Platforms : M210V2,M300
Measurement Unit : m/s2

Data Structure : Vector3f

TOPIC_VELOCITY 

Provides aircraft's velocity in a ground-fixed NEU frame @ up to 200Hz.

Warning
Please note that this data is not in a conventional right-handed frame of reference.

This is a fusion output from the flight control system. The output is in a right-handed NED frame, but the sign of the Z-axis velocity is flipped before publishing to this topic. So if you are looking to get velocity in an NED frame, simply flip the sign of the z-axis value. Beyond that, you can convert using rotations to any right-handed frame of reference.

Performance Benchmarking Data :
Axis Unit Accuracy
vgx, vgy m/s Around 5cm/s for GNSS navigation. Around 3cm/s with VO at 1 meter height
vgz m/s 10cm/s only with barometer in steady air. 3cm/s with VO at 1 meter height with 8cm baseline
Sensing Sources : IMU, GPS, Baro, RTK (if available), Visual Odometry (M210 only), TOF (M210 Only)
Supported Platforms : M210V2,M300
Measurement Unit : m/s

Data Structure : Velocity

TOPIC_ANGULAR_RATE_FUSIONED 

Provides aircraft's angular velocity in a ground-fixed NED frame @ up to 200Hz.

This is a fusion output from the flight control system.

Supported Platforms : M210V2,M300
Measurement Unit : rad/s

Data Structure : Vector3f

TOPIC_ANGULAR_RATE_RAW 

Provides aircraft's angular velocity in an IMU-centered, body-fixed FRD frame @ up to 400Hz.

This is a filtered output from the IMU on board the flight control system.

Sensing Sources : IMU
Supported Platforms : M210V2,M300
Measurement Unit : rad/s

Data Structure : Vector3f

TOPIC_ALTITUDE_FUSIONED 

Provides aircraft's fused altitude from sea level using the ICAO model @ up to 200Hz.

This is a fusion output from the flight control system, and is the recommended source of altitude data.

The ICAO model gives an MSL altitude of 1013.25mBar at 15° C and a temperature lapse rate of -6.5° C per 1000m. In your case, it may be possible that the take off altitude of the aircraft is recording a higher pressure than 1013.25mBar. Let's take an example - a weather station shows that SFO (San Francisco International Airport) had recently recorded a pressure of 1027.1mBar. SFO is 4m above MSL, yet, if you calculate the Pressure Altitude using the ICAO model, it relates to -114m. You can use an online calculator to similarly calculate the Pressure Altitude in your area.

Another factor that may affect your altitude reading is manufacturing differences in the barometer - it is not uncommon to have a variation of ±30m readings at the same physical location with two different aircraft. For a given aircraft, these readings will be consistent, so you will need to calibrate the offset of your system if your code relies on the accuracy of the absolute value of altitude.

Sensing Sources : GPS, Barometer, IMU
Supported Platforms : M210V2,M300
Measurement Unit : m
Data Structure : float32_t
TOPIC_ALTITUDE_BAROMETER 

Provides aircraft's pressure altitude from sea level using the ICAO model @ up to 200Hz.

This is a filetered output from the barometer without any further fusion.

The ICAO model gives an MSL altitude of 1013.25mBar at 15° C and a temperature lapse rate of -6.5° C per 1000m. In your case, it may be possible that the take off altitude of the aircraft is recording a higher pressure than 1013.25mBar. Let's take an example - a weather station shows that SFO (San Francisco International Airport) had recently recorded a pressure of 1027.1mBar. SFO is 4m above MSL, yet, if you calculate the Pressure Altitude using the ICAO model, it relates to -114m. You can use an online calculator to similarly calculate the Pressure Altitude in your area.

Another factor that may affect your altitude reading is manufacturing differences in the barometer - it is not uncommon to have a variation of ±30m readings at the same physical location with two different aircraft. For a given aircraft, these readings will be consistent, so you will need to calibrate the offset of your system if your code relies on the accuracy of the absolute value of altitude.

Sensing Sources : GPS, Barometer, IMU
Supported Platforms : M210V2,M300
Measurement Unit : m
Data Structure : float32_t
TOPIC_ALTITUDE_OF_HOMEPOINT 

Provides the altitude from sea level when the aircraft last took off.

This is a fusion output from the flight control system, and also uses the ICAO model.

The ICAO model gives an MSL altitude of 1013.25mBar at 15° C and a temperature lapse rate of -6.5° C per 1000m. In your case, it may be possible that the take off altitude of the aircraft is recording a higher pressure than 1013.25mBar. Let's take an example - a weather station shows that SFO (San Francisco International Airport) had recently recorded a pressure of 1027.1mBar. SFO is 4m above MSL, yet, if you calculate the Pressure Altitude using the ICAO model, it relates to -114m. You can use an online calculator to similarly calculate the Pressure Altitude in your area.

Another factor that may affect your altitude reading is manufacturing differences in the barometer - it is not uncommon to have a variation of ±30m readings at the same physical location with two different aircraft. For a given aircraft, these readings will be consistent, so you will need to calibrate the offset of your system if your code relies on the accuracy of the absolute value of altitude.

Note
This value is updated each time the drone takes off.
Sensing Sources : Visual Odometry (M210 only), Barometer, IMU
Supported Platforms : M210V2,M300
Measurement Unit : m
Data Structure : float32_t
TOPIC_HEIGHT_FUSION 

Provides the relative height above ground at up to 100Hz.

This is a fusion output from the flight control system. The height is a direct estimate of the closest large object below the aircraft's ultrasonic sensors. A large object is something that covers the ultrasonic sensor for an extended duration of time.

Warning
This topic does not come with a 'valid' flag - so if the aircraft is too far from an object for the ultrasonic sensors/VO to provide any meaningful data, the values will latch and there is no way for user code to determine if the data is valid or not. Use with caution.
Sensing Sources : Visual Odometry, Ultrasonic
Supported Platforms : M210V2,M300
Measurement Unit : m
Data Structure : float32_t
TOPIC_GPS_FUSED 

Provides aircraft's GPS/IMU fused X-Y position and barometric altitude (put together in a single topic for convenience) @ up to 50Hz.

Warning
Please note that if GPS signal is weak (low visibleSatelliteNumber, see below), the latitude/longitude values won't be updated but the altitude might still be. There is currently no way to know if the lat/lon update is healthy.

The most important component of this topic is the visibleSatelliteNumber. Use this to track your GPS satellite coverage and build some heuristics for when you might expect to lose GPS updates.

Performance Benchmarking Data :
Axis Unit Position Sensor Accuracy
x, y m GPS <3m with open sky without multipath
z m GPS <5m with open sky without multipath
Sensing Sources : GPS/IMU (x,y), Barometer(z)
Supported Platforms : M210V2,M300
Measurement Unit : rad (Lat,Lon), m (Alt)

Data Structure : GPSFused

TOPIC_GPS_DATE 

Provides raw date information from GPS @ up to 5Hz.

Format : yyyymmdd

Sensing Sources : GPS
Supported Platforms : M210V2,M300
Data Structure : uint32_t
TOPIC_GPS_TIME 

Provides raw time information from GPS @ up to 5Hz.

Format : hhmmss

Sensing Sources : GPS
Supported Platforms : M210V2,M300
Data Structure : uint32_t
TOPIC_GPS_POSITION 

Provides aircraft's raw GPS LLA @ up to 5Hz.

Performance Benchmarking Data :
Axis Position Sensor Accuracy
x, y GPS <3m with open sky without multipath
z GPS <5m with open sky without multipath
Sensing Sources : GPS
Supported Platforms : M210V2,M300
Measurement Unit : rad*10-7 (Lat,Lon), mm (Alt)

Data Structure : Vector3d

Note
The data structure for this UID is too generic for the data itself - please note that in the vector3d struct, x = Latitude, y = Longitude, z = Altitude
TOPIC_GPS_VELOCITY 

Provides aircraft's raw GPS velocity @ up to 5Hz.

Sensing Sources : GPS
Supported Platforms : M210V2,M300
Measurement Unit : cm/s

Data Structure : Vector3f

TOPIC_GPS_DETAILS 

Provides aircraft's raw GPS status and other details @ up to 5Hz.

Sensing Sources : GPS
Supported Platforms : M210V2,M300

Data Structure : GPSDetail

TOPIC_RTK_POSITION 

Provides aircraft's raw Real-Time Kinematic (RTK) LLA @ up to 5Hz.

Performance Benchmarking Data :
Axis Position Sensor Accuracy
x, y RTK ~2cm with fine alignment and fix condition
z RTK ~3cm with fine alignment and fix condition
Sensing Sources : RTK
Supported Platforms : M210V2,M300 (in each case, if RTK is installed)
Measurement Unit : deg (x, y), m(z)

Data Structure : PositionData

TOPIC_RTK_VELOCITY 

Provides aircraft's raw Real-Time Kinematic (RTK) velocity @ up to 5Hz.

Sensing Sources : RTK
Supported Platforms : M210V2,M300 (in each case, if RTK is installed)
Measurement Unit : cm/s

Data Structure : Vector3f

TOPIC_RTK_YAW 

Provides aircraft's raw Real-Time Kinematic (RTK) yaw @ up to 5Hz.

The RTK yaw will provide the vector from ANT1 to ANT2 as configured in DJI Assistant 2. In the M210, this means that the value of RTK yaw will be 90° offset from the yaw of the aircraft. For the M600 w/D-RTK, it will depend on how you mount your antennae. In preconfigured units, the mounting will be such that the RTK yaw is 90° offset from the aircraft yaw.

Sensing Sources : RTK
Supported Platforms : M210V2,M300 (in each case, if RTK is installed)
Measurement Unit : deg
Data Structure : int16_t
TOPIC_RTK_POSITION_INFO 

Provides a status on aircraft's Real-Time Kinematic (RTK) positioning solution @ up to 5Hz.

Value Meaning
0 no solution
1 Position has been fixed by the FIX POSITION command
2 Position has been fixed by the FIX HEIGHT/AUTO command
8 Velocity computed using instantaneous Doppler
16 Single point position
17 Pseudorange differential solution
18 Solution calculated using corrections from an SBAS
19 Propagated by a Kalman filter without new observations
20 OmniSTAR VBS position (L1 sub-metre)
32 Floating L1 ambiguity solution
33 Floating ionospheric-free ambiguity solution
34 Floating narrow-lane ambiguity solution
48 Integer L1 ambiguity solution
49 Integer wide-lane ambiguity solution
50 Integer narrow-lane ambiguity solution
Sensing Sources : RTK
Supported Platforms : M210V2,M300 (in each case, if RTK is installed)
Data Structure : uint8_t
TOPIC_RTK_YAW_INFO 

Provides a status on aircraft's Real-Time Kinematic (RTK) yaw solution @ up to 5Hz.

Value Meaning
0 no solution
1 Position has been fixed by the FIX POSITION command
2 Position has been fixed by the FIX HEIGHT/AUTO command
8 Velocity computed using instantaneous Doppler
16 Single point position
17 Pseudorange differential solution
18 Solution calculated using corrections from an SBAS
19 Propagated by a Kalman filter without new observations
20 OmniSTAR VBS position (L1 sub-metre)
32 Floating L1 ambiguity solution
33 Floating ionospheric-free ambiguity solution
34 Floating narrow-lane ambiguity solution
48 Integer L1 ambiguity solution
49 Integer wide-lane ambiguity solution
50 Integer narrow-lane ambiguity solution
Sensing Sources : RTK
Supported Platforms : M210V2,M300 (in each case, if RTK is installed)
Data Structure : uint8_t
TOPIC_COMPASS 

Provides aircraft's magnetometer reading, fused with IMU and GPS @ up to 100Hz.

This reading is the magnetic field recorded by the magnetometer in x,y,z axis, calibrated such that 1000 < |m| < 2000, and fused with IMU and GPS for robustness

Sensing Sources : Magnetometer, IMU, GPS
Supported Platforms : M210V2,M300
Measurement Unit : N/A

Data Structure : Mag

TOPIC_RC 

Provides remote controller stick inputs @ up to 100Hz.

This topic will give you:

  • Stick inputs (R,P,Y,Thr)
  • Mode switch (P/A/F)
  • Landing gear switch (Up/Down)
Supported Platforms : M210V2,M300

Data Structure : RC

Also Refer To TOPIC_RC_WITH_FLAG_DATA

TOPIC_GIMBAL_ANGLES 

Provides gimbal pitch, roll, yaw @ up to 50Hz.

The reference frame for gimbal angles is a NED frame attached to the gimbal. This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :

Data Structure Element Meaning
Vector3f.x pitch
Vector3f.y roll
Vector3f.z yaw
Performance Benchmarking Data :
0.1 deg accuracy in all axes
Sensing Sources : Gimbal Encoder, IMU, Magnetometer
Supported Platforms : M210V2,M300
Measurement Unit : deg

Data Structure : Vector3f

Also Refer To TOPIC_GIMBAL_STATUS, TOPIC_GIMBAL_CONTROL_MODE

TOPIC_GIMBAL_STATUS 

Provides gimbal status and error codes @ up to 50Hz.

Please see the GimbalStatus struct for the details on what data you can receive.

Supported Platforms : M210V2,M300

Data Structure : GimbalStatus

Also Refer To TOPIC_GIMBAL_ANGLES, TOPIC_GIMBAL_CONTROL_MODE

TOPIC_STATUS_FLIGHT 

Provides the aircraft's internal flight state @ up to 50Hz.

The state machine for this topic has the following transition diagram:

state_machine.png
Supported Platforms : M210V2,M300

Data Structure : uint8_t (For detailed enumerations see FlightStatus)

Also Refer To TOPIC_STATUS_DISPLAYMODE

TOPIC_STATUS_DISPLAYMODE 

Provides a granular state representation for various tasks/flight modes @ up to 50Hz.

Typically, use this topic together with TOPIC_STATUS_FLIGHT to get a better understanding of the overall status of the aircraft.

Supported Platforms : M210V2,M300

Data Structure : uint8_t (For detailed enumerations see DisplayMode)

Also Refer To TOPIC_STATUS_FLIGHT

TOPIC_STATUS_LANDINGGEAR 

Provides status for the landing gear state @ up to 50Hz.

Supported Platforms : M300

Data Structure : uint8_t (For detailed enumerations see LandingGearMode)

TOPIC_STATUS_MOTOR_START_ERROR 

If motors failed to start, this topic provides reasons why. Available @ up to 50Hz.

Supported Platforms : M210V2,M300

Data Structure : uint8_t (For detailed enumerations see CommonACK, starting from the 6th element)

Note
These enumerations show up in the ErrorCode class because they can also be returned as acknowledgements for APIs that start the motors, such as Takeoff or Arm
TOPIC_BATTERY_INFO 

Provides various data about the battery @ up to 50Hz.

Note
Most of these details need a DJI Intelligent battery to work correctly (this is usually not the case with A3/N3 based setups)

Please be aware that some of the data elements in this topic may not be able to update at high rates due to the limitations of the sensing for that data. e.g. current can only update @ 1 Hz.

Supported Platforms : M210V2,M300
Measurement Unit :
|voltage | mV | |current | mA |

Data Structure : Battery

TOPIC_CONTROL_DEVICE 

Provides states of the aircraft related to SDK/RC control.

The following information is available in this topic:

Data Structure Element Meaning
controlMode The modes in which the aircraft is being controlled (control loops being applied on horizontal, vertical and yaw axes of the aircraft)
deviceStatus Which device is controlling the motion of the aircraft: RC (Manual control), MSDK (Missions kicked off through mobile), OSDK (Missions kicked off through onboard/ low-level flight control)
flightStatus Has the OSDK been granted control authority? Since MSDK and RC have precedence, it is possible that deviceStatus shows RC or MSDK actually controlling the aircraft but this value is 1.
vrcStatus Deprecated
Supported Platforms : M210V2,M300

Data Structure : SDKInfo

TOPIC_HARD_SYNC 

Provides IMU and quaternion data time-synced with a hardware clock signal @ up to 400Hz.

This is the only data which can be synchronized with external software or hardware systems. If you want to fuse an external sensor's data with the aircraft's IMU, this data along with a hardware trigger from the A3/N3's expansion ports is how you would do it. You can see detailed documentation on how this process works in the Hardware Sync Guide.

Sensing Sources : IMU, sensor fusion output
Supported Platforms : N3
Measurement Unit :
Data Structure Element Units
Timestamp 2.5ms, 1ns (See SyncTimestamp)
Quaternion rad (after converting to rotation matrix)
Acceleration g
Gyroscope rad/sec

Data Structure : HardSyncData

TOPIC_GPS_SIGNAL_LEVEL 

Provides a measure of the quality of GPS signal @ up to 50Hz.

The level varies from 0 to 5, with 0 being the worst and 5 the best GPS signal. Closely related to TOPIC_GPS_CONTROL_LEVEL

Sensing Sources : GPS
Supported Platforms : M210V2,M300
Data Structure : uint8_t

Also Refer To TOPIC_GPS_CONTROL_LEVEL

TOPIC_GPS_CONTROL_LEVEL 

Provides a measure of the quality of GPS signal, with a mechanism for guarding against unset homepoint @ up to 50Hz.

The level varies from 0 to 5, with 0 being the worst and 5 the best GPS signal. The key difference between this and TOPIC_GPS_SIGNAL_LEVEL is that this topic always returns 0 if the homepoint is not set. Once the home point is set, the behavior is exactly the same as TOPIC_GPS_SIGNAL_LEVEL.

Sensing Sources : GPS
Supported Platforms : M210V2,M300
Data Structure : uint8_t

Also Refer To TOPIC_GPS_SIGNAL_LEVEL

TOPIC_RC_FULL_RAW_DATA 

Provides raw remote controller stick, buttons and switch data @ up to 50Hz.

Note
This topic was added in August 2018. Your aircraft may require a FW update to enable this feature.

For LB2 and SBUS RCs, this topic will give you:

Also Refer To TOPIC_RC_WITH_FLAG_DATA, TOPIC_RC

TOPIC_RC_WITH_FLAG_DATA 

Provides normalized remote controller stick input data, along with connection status @ up to 50Hz.

Note
This topic was added in August 2018. Your aircraft may require a FW update to enable this feature.

This topic will give you:

  • Stick inputs (R,P,Y,Thr)
  • Mode switch (P/A/F)
  • Landing gear switch (Up/Down)
  • Connection status for air system, ground system and MSDK apps. The connection status also includes a logicConnected element, which will change to false if either the air system or the ground system radios are disconnected for >3s.
  • Deadzones near the center of the stick positions are also handled in this topic.
Supported Platforms : M210V2,M300

Data Structure : RCWithFlagData

Also Refer To TOPIC_RC_FULL_RAW_DATA, TOPIC_RC

TOPIC_ESC_DATA 

Provides raw data from the ESCs @ up to 50Hz.

Note
This topic was added in August 2018. Your aircraft may require a FW update to enable this feature.

This topic supports reporting data for up to 8 ESCs; note that only DJI Intelligent ESCs are supported for this reporting feature. Use this topic to get data on elements close to the hardware - e.g. motor speeds, ESC current and voltage, error flags at the ESC level etc.

Supported Platforms : M210V2,M300

Data Structure : ESCStatusIndividual, EscData

TOPIC_RTK_CONNECT_STATUS 

Provides RTK connection status @ up to 50Hz.

Note
This topic was added in August 2018. Your aircraft may require a FW update to enable this feature.

This topic will update in real time whether the RTK GPS system is connected or not; typical uses include app-level logic to switch between GPS and RTK sources of positioning based on this flag.

Supported Platforms : M210V2,M300

Data Structure : RTKConnectStatus

TOPIC_GIMBAL_CONTROL_MODE 

Provides the mode in which the gimbal will interpret control commands @ up to 50Hz.

Note
This topic was added in August 2018. Your aircraft may require a FW update to enable this feature.

This topic will report the current control mode which can be set in the DJI Go app, MSDK apps, or through Onboard SDK gimbal control APIs (see AngleData struct for more information)

Supported Platforms : M210V2,M300

Data Structure : GimbalControlMode

TOPIC_FLIGHT_ANOMALY 

Provides a number of flags which report different errors the aircraft may encounter in flight @ up to 50Hz.

Note
This topic was added in August 2018. Your aircraft may require a FW update to enable this feature.
Warning
Most of the errors reported by this topic are cases where immediate action is required; you can use these as a baseline for implementing safety-related error-handling routines.
Supported Platforms : M210V2,M300

Data Structure : FlightAnomaly

TOPIC_POSITION_VO 

Provides aircraft's position in a Cartesian frame @ up to 50Hz, without the need for GPS.

Warning
This topic does not follow a standard co-ordinate convention. Please read the details below for usage.

This is the only topic which can provide positioning information without having a GPS fix; though this can be a big enabler please note the caveats of using this topic:

  • The topic will use an origin that does not have a global reference, and is not published to the SDK.
  • The topic uses a combination of VO and compass heading to identify the X-Y axes of its reference frame. This means that if your compass performance is not good in an environment, there is no guarantee the X-Y axes will point to North and East.
  • The actual directions of the X-Y axes are currently not published to the SDK.
  • If during a flight the compass performance were to change dramatically, the orientation of the X-Y axes may change to re-align with North-East. The aircraft's position in X and Y may exhibit discontinuities in these cases.
  • The reference frame is referred to as the Navigation Frame - Cartesian X,Y axes aligned with N,E directions on a best-effort basis, and Z aligned to D (down) direction.
  • A health flag for each axis provides some granularity on whether this data is valid or not.

The key takeaway from these details is that this topic provides a best-effort attempt at providing position information in the absence of absolute references (GPS, compass etc.), without guarantees of consistency if environmental conditions change. So if your application is confined to a stable environment, or if you will have GPS and compass available at all times, this topic can still provide useful data that cannot be otherwise had. If using for control, make sure to have guards checking for the continuity of data.

Note
Since this topic relies on visual features and/or GPS, if your environment does not provide any of these sources of data, the quality of this topic will reduce significantly. VO data quality will reduce if you are too high above the ground. Make sure that the Vision Positioning System is enabled in DJI Go 4 before using this topic (by default it is enabled).
Sensing Sources : IMU, VO, GPS(if available), RTK (if available), ultrasonic, magnetometer, barometer
Supported Platforms : M210V2,M300
Measurement Unit : m
TOPIC_AVOID_DATA 

Provides obstacle info around the vehicle @ up to 100Hz.

Supported Platforms : M210V2,M300

Data Structure : LocalPositionVO

TOPIC_HOME_POINT_SET_STATUS 

Provides status of whether the home point was set or not.

Supported Platforms : M210V2,M300

Data Structure : HomeLocationSetStatus

TOPIC_HOME_POINT_INFO 

Provides homepoint information, the valid of the home point infomation can ref to the topic DJI_DATA_SUBSCRIPTION_TOPIC_HOME_POINT_SET_STATUS.

Supported Platforms : M210V2,M300

Data Structure : HomeLocationData

TOPIC_DUAL_GIMBAL_DATA 

Provides double gimbal information, used for M210V2.

Supported Platforms : M210V2

Data Structure : GimbalDualData

TOPIC_THREE_GIMBAL_DATA 

Provides three gimbal information, used for M300.

Supported Platforms : M300

Data Structure : GimbalThreeData