dji_telemetry.hpp
Go to the documentation of this file.
1 
29 #ifndef ONBOARDSDK_DJI_Telemetry_H
30 #define ONBOARDSDK_DJI_Telemetry_H
31 
32 #include "dji_type.hpp"
33 
37 namespace DJI
38 {
42 namespace OSDK
43 {
48 namespace Telemetry
49 {
58 // clang-format off
59 typedef enum
60 {
96  TOPIC_RC_FULL_RAW_DATA, //deprecated
108  TOTAL_TOPIC_NUMBER // Always put this line in the end
109 } TopicName;
110 // clang-format on
111 
115 // clang-format off
116 typedef enum
117 {
118  UID_QUATERNION = 0xa493281f,
119  UID_ACCELERATION_GROUND = 0x8696c85b,
120  UID_ACCELERATION_BODY = 0xbb17d5fe,
121  UID_ACCELERATION_RAW = 0xc3503a6e,
122  UID_VELOCITY = 0x18fb271d,
123  UID_ANGULAR_RATE_FUSIONED = 0x3599c4be,
124  UID_ANGULAR_RATE_RAW = 0x700389ee,
125  UID_ALTITUDE_FUSIONED = 0x11e9c81a,
126  UID_ALTITUDE_BAROMETER = 0x27396a39,
127  UID_ALTITUDE_OF_HOMEPOINT = 0x252c164b,
128  UID_HEIGHT_FUSION = 0x87cf419d,
129  UID_GPS_FUSED = 0x4b19a8c7,
130  UID_GPS_DATE = 0x598f79bc,
131  UID_GPS_TIME = 0xd48912c9,
132  UID_GPS_POSITION = 0x0c949e94,
133  UID_GPS_VELOCITY = 0x7ac7eb80,
134  UID_GPS_DETAILS = 0x81fed54e,
135  UID_RTK_POSITION = 0x1df9a6b6,
136  UID_RTK_VELOCITY = 0x763d13c3,
137  UID_RTK_YAW = 0xf45d73fd,
138  UID_RTK_POSITION_INFO = 0xda4a57b5,
139  UID_RTK_YAW_INFO = 0xcb72b9e3,
140  UID_HOME_POINT_SET_STATUS = 0xb5c2211f,
141  UID_HOME_POINT_INFO = 0xbfe4b520,
142  UID_COMPASS = 0xdf3d72b7,
143  UID_RC = 0x739f7fe4,
144  UID_GIMBAL_ANGLES = 0x01f71678,
145  UID_GIMBAL_STATUS = 0x8b6cd45c,
146  UID_STATUS_FLIGHT = 0x20cfb02a,
147  UID_STATUS_DISPLAYMODE = 0x1a67d6a1,
148  UID_STATUS_LANDINGGEAR = 0x772d6e22,
149  UID_STATUS_MOTOR_START_ERROR = 0x3a41e909,
150  UID_BATTERY_INFO = 0x69779dd9,
151  UID_CONTROL_DEVICE = 0x667ba86a,
152  UID_HARD_SYNC = 0xecbef06d,
153  UID_GPS_SIGNAL_LEVEL = 0xa6a0395f,
154  UID_GPS_CONTROL_LEVEL = 0xe30b17b0,
155  UID_RC_FULL_RAW_DATA = 0x16ec4d0e,
156  UID_RC_WITH_FLAG_DATA = 0xfe04cfcd,
157  UID_ESC_DATA = 0xaaa0f589,
158  UID_RTK_CONNECT_STATUS = 0x6f349326,
159  UID_GIMBAL_CONTROL_MODE = 0x326a446d,
160  UID_FLIGHT_ANOMALY = 0x0a624b4b,
161  UID_POSITION_VO = 0xd3462697,
162  UID_AVOID_DATA = 0xf6405daa,
163  UID_DUAL_GIMBAL_FULL_DATA = 0xcfeea4fa,
164  UID_THREE_GIMBAL_FULL_DATA = 0x19d374a0,
165 } TOPIC_UID;
166 
167 // clang-format on
168 #pragma pack(1)
169 
173 typedef struct
174 {
175  const TopicName name;
176  const uint32_t uid;
177  const size_t size; /* The size of actual data for the topic */
178  const uint16_t maxFreq; /* max freq in Hz for the topic provided by FC */
179  uint16_t freq; /* Frequency at which the topic is subscribed */
180  uint8_t pkgID; /* Package ID in which the topic is subscribed */
181  /* Point to topic's address in the data buffer which stores the latest data */
182  uint8_t* latest;
183 } TopicInfo; // pack(1)
184 
188 typedef struct Quaternion
189 {
190  float32_t q0;
191  float32_t q1;
192  float32_t q2;
193  float32_t q3;
194 } Quaternion; // pack(1)
195 
199 typedef struct Vector3f
200 {
201  float32_t x;
202  float32_t y;
203  float32_t z;
204 } Vector3f; // pack(1)
205 
211 typedef struct Vector3d
212 {
213  int32_t x;
214  int32_t y;
215  int32_t z;
216 } Vector3d; // pack(1)
217 
223 typedef struct TimeStamp
224 {
225  uint32_t time_ms;
226  uint32_t time_ns;
227 } TimeStamp; // pack(1)
228 
234 typedef struct SyncStamp
235 {
236  uint32_t time_2p5ms;
237  uint16_t tag;
238  uint8_t flag;
239 } SyncStamp; // pack(1)
240 
245 typedef struct VelocityInfo
246 {
247 
248  uint8_t health : 1;
249  uint8_t reserve : 7;
250 } VelocityInfo; // pack(1)
251 
258 typedef struct Velocity
259 {
260  Vector3f data;
265 } Velocity; // pack(1)
266 
272 typedef struct GlobalPosition
273 {
274  float64_t latitude;
275  float64_t longitude;
276  float32_t altitude;
277  float32_t height;
278  uint8_t health;
280 } GlobalPosition; // pack(1)
281 
287 typedef struct GPSFused
288 {
289  float64_t longitude;
290  float64_t latitude;
291  float32_t altitude;
293 } GPSFused; // pack(1)
294 
300 typedef struct RelativePosition
301 {
302  float32_t down;
303  float32_t front;
304  float32_t right;
305  float32_t back;
306  float32_t left;
307  float32_t up;
308  uint8_t downHealth : 1;
309  uint8_t frontHealth : 1;
310  uint8_t rightHealth : 1;
311  uint8_t backHealth : 1;
312  uint8_t leftHealth : 1;
313  uint8_t upHealth : 1;
314  uint8_t reserved : 2;
315 } RelativePosition; // pack(1)
316 
322 typedef struct PositionTimeStamp
323 {
324  uint32_t date;
325  uint32_t time;
326 } PositionTimeStamp; // pack(1)
327 
331 typedef struct PositionData
332 {
333  float64_t longitude;
334  float64_t latitude;
335  float32_t HFSL;
336 } PositionData; // pack(1)
337 
338 
342 typedef struct HomeLocationData
343 {
344  float64_t latitude;
345  float64_t longitude;
346 }HomeLocationData; // pack(1)
347 
351 typedef struct HomeLocationSetStatus
352 {
353  uint8_t status;
354 }HomeLocationSetStatus;// pack(1)
361 typedef struct GPSDetail
362 {
363  float32_t hdop;
364  float32_t pdop;
365  float32_t fix;
366  float32_t gnssStatus;
367  float32_t hacc;
368  float32_t sacc;
369  uint32_t usedGPS;
370  uint32_t usedGLN;
371  uint16_t NSV;
372  uint16_t GPScounter;
373 } GPSDetail; // pack(1)
374 
380 typedef struct GPSInfo
381 {
382  PositionTimeStamp time;
383  int32_t longitude;
384  int32_t latitude;
385  int32_t HFSL;
387  GPSDetail detail;
388 } GPSInfo; // pack(1)
389 
393 typedef struct PositionFrame
394 {
395  PositionTimeStamp time;
396  PositionData data;
397 } PositionFrame; // pack(1)
398 
404 typedef struct RTK
405 {
411  int16_t yaw;
429  uint8_t posHealthFlag;
430  uint8_t yawHealthFlag;
431 } RTK; // pack(1)
432 
439 typedef struct Mag
440 {
441  int16_t x;
442  int16_t y;
443  int16_t z;
444 } Mag; // pack(1)
445 
455 typedef struct Compass
456 {
457  uint8_t compassStatus;
458 } Compass;
459 
463 typedef struct RC
464 {
465  int16_t roll;
466  int16_t pitch;
467  int16_t yaw;
468  int16_t throttle;
469  int16_t mode;
471  int16_t gear;
473 } RC; // pack(1)
474 
478 typedef struct GimbalStatus
479 {
480  uint32_t mountStatus : 1;
481  uint32_t isBusy : 1;
482  uint32_t pitchLimited : 1;
483  uint32_t rollLimited : 1;
484  uint32_t yawLimited : 1;
485  uint32_t calibrating : 1;
486  uint32_t prevCalibrationgResult : 1;
487  uint32_t installedDirection : 1;
488  uint32_t disabled_mvo : 1;
489  uint32_t gear_show_unable : 1;
490  uint32_t gyroFalut : 1;
491  uint32_t escPitchStatus : 1;
492  uint32_t escRollStatus : 1;
493  uint32_t escYawStatus : 1;
494  uint32_t droneDataRecv : 1;
495  uint32_t initUnfinished : 1;
496  uint32_t FWUpdating : 1;
497  uint32_t reserved2 : 15;
498 } GimbalStatus; // pack(1)
499 
503 typedef struct Gimbal
504 {
505 
506  float32_t roll;
507  float32_t pitch;
508  float32_t yaw;
509  uint8_t pitchLimit : 1;
510  uint8_t rollLimit : 1;
511  uint8_t yawLimit : 1;
512  uint8_t reserved : 5;
513 } Gimbal; // pack(1)
514 
518 typedef struct Status
519 {
520  uint8_t flight;
521  uint8_t mode;
522  uint8_t gear;
523  uint8_t error;
524 } Status; // pack(1)
525 
530 typedef struct Battery
531 {
532  uint32_t capacity;
533  int32_t voltage;
534  int32_t current;
535  uint8_t percentage;
536 } Battery; // pack(1)
537 
541 typedef struct SDKInfo
542 {
543  uint8_t controlMode;
544  uint8_t deviceStatus : 3;
546  uint8_t flightStatus : 1;
547  uint8_t vrcStatus : 1;
548  uint8_t reserved : 3;
549 } SDKInfo; // pack(1)
550 
554 typedef struct SyncTimestamp
555 {
556  uint32_t time2p5ms;
558  uint32_t time1ns;
559  uint32_t resetTime2p5ms;
561  uint16_t index;
568  uint8_t flag;
572 } SyncTimestamp; // pack(1)
573 
577 typedef struct HardSyncData
578 {
583 } HardSyncData; // pack(1)
584 
588 typedef struct RTKConnectStatus
589 {
590  uint16_t rtkConnected : 1;
591  uint16_t reserve : 15;
593 
597 typedef struct RCWithFlagData
598 {
599  float32_t pitch;
600  float32_t roll;
601  float32_t yaw;
602  float32_t throttle;
603  struct
604  {
605  uint8_t logicConnected :1;
606  uint8_t skyConnected :1;
607  uint8_t groundConnected :1;
608  uint8_t appConnected :1;
609  uint8_t reserved :4;
610  } flag;
612 
616 typedef struct ESCStatusIndividual
617 {
618  int16_t current;
619  int16_t speed;
620  uint16_t voltage;
621  int16_t temperature;
622  uint16_t stall : 1;
623  uint16_t empty : 1;
624  uint16_t unbalanced : 1;
625  uint16_t escDisconnected : 1;
626  uint16_t temperatureHigh : 1;
627  uint16_t reserved : 11;
629 
630 #define MAX_ESC_NUM 8
631 
634 typedef struct EscData
635 {
636  ESCStatusIndividual esc[MAX_ESC_NUM];
637 } EscData;
638 
642 typedef struct LB2RcFullRawData
643 {
644  int16_t roll;
645  int16_t pitch;
646  int16_t yaw;
647  int16_t throttle;
648  int16_t mode;
649  int16_t gear;
650  int16_t camera;
651  int16_t video;
652  int16_t videoPause;
653  int16_t goHome;
654  int16_t leftWheel;
656  int16_t rcC1;
657  int16_t rcC2;
658  int16_t rcD1;
659  int16_t rcD2;
660  int16_t rcD3;
661  int16_t rcD4;
662  int16_t rcD5;
663  int16_t rcD6;
664  int16_t rcD7;
665  int16_t rcD8;
667 
668 #define SDK_LB2_CHANNEL_NUM (sizeof(LB2RcFullRawData)/sizeof(int16_t))
669 #define SDK_SBUS_CHANNEL_NUM (16)
670 
673 typedef struct SBUSFullRawData
674 {
675  int16_t data[SDK_SBUS_CHANNEL_NUM];
676  int16_t reserved[SDK_LB2_CHANNEL_NUM - SDK_SBUS_CHANNEL_NUM];
678 
683 typedef union
684 {
685  LB2RcFullRawData lb2;
686  SBUSFullRawData sbus;
687 } RCFullRawData;
688 
689 typedef uint8_t GimbalControlMode;
690 
691 typedef struct GimbalSingleData
692 {
693  float32_t pitch;
694  float32_t roll;
695  float32_t yaw;
696  uint32_t status;
697  uint8_t mode;
698 } GimbalSingleData;
699 
700 #define SDK_M210_GIMBAL_MAX_NUM 2
701 #define SDK_M300_GIMBAL_MAX_NUM 3
702 
706 typedef struct GimbalDualData
707 {
708  GimbalSingleData gbData[SDK_M210_GIMBAL_MAX_NUM];
710 
714 typedef struct GimbalThreeData
715 {
716  GimbalSingleData gbData[SDK_M300_GIMBAL_MAX_NUM];
718 
722 typedef struct FlightAnomaly
723 {
724  uint32_t impactInAir : 1;
725  uint32_t randomFly : 1;
726  uint32_t heightCtrlFail : 1;
727  uint32_t rollPitchCtrlFail : 1;
728  uint32_t yawCtrlFail : 1;
729  uint32_t aircraftIsFalling : 1;
730  uint32_t strongWindLevel1 : 1;
731  uint32_t strongWindLevel2 : 1;
733  uint32_t imuInstallationError : 1;
734  uint32_t escTemperatureHigh : 1;
736  uint32_t gpsYawError : 1;
737  uint32_t reserved : 19;
738 } FlightAnomaly;
739 
743 typedef struct LocalPositionVO
744 {
745  float32_t x;
746  float32_t y;
747  float32_t z;
748  uint8_t xHealth : 1;
749  uint8_t yHealth : 1;
750  uint8_t zHealth : 1;
751  uint8_t reserved : 5;
753 //---------------------------------Legacy commands below-----------------------------------//
754 
759 typedef struct LegacyTimeStamp
760 {
761  uint32_t time;
762  uint32_t nanoTime;
763  uint8_t syncFlag;
764 } LegacyTimeStamp; // pack(1)
765 
772 typedef struct LegacyVelocity
773 {
774  float32_t x;
775  float32_t y;
776  float32_t z;
780  uint8_t health : 1;
781  uint8_t sensorID : 4;
782  uint8_t reserve : 3;
783 } LegacyVelocity; // pack(1)
784 
785 typedef uint16_t EnableFlag; // pack(1)
786 
791 typedef uint8_t LegacyStatus; // pack(1)
795 typedef uint8_t LegacyBattery; // pack(1)
796 
802 typedef struct LegacyGPSInfo
803 {
804  PositionTimeStamp time;
805  int32_t longitude;
806  int32_t latitude;
807  int32_t HFSL;
809 } LegacyGPSInfo; // pack(1)
810 
811 #pragma pack()
812 
813 extern TopicInfo TopicDataBase[];
814 
819 template <TopicName T>
820 struct TypeMap
821 {
822  typedef void type;
823 };
824 
825 // clang-format off
826 template <> struct TypeMap<TOPIC_QUATERNION > { typedef Quaternion type;};
827 template <> struct TypeMap<TOPIC_ACCELERATION_GROUND > { typedef Vector3f type;};
828 template <> struct TypeMap<TOPIC_ACCELERATION_BODY > { typedef Vector3f type;};
829 template <> struct TypeMap<TOPIC_ACCELERATION_RAW > { typedef Vector3f type;};
830 template <> struct TypeMap<TOPIC_VELOCITY > { typedef Velocity type;};
831 template <> struct TypeMap<TOPIC_ANGULAR_RATE_FUSIONED > { typedef Vector3f type;};
832 template <> struct TypeMap<TOPIC_ANGULAR_RATE_RAW > { typedef Vector3f type;};
833 template <> struct TypeMap<TOPIC_ALTITUDE_FUSIONED > { typedef float32_t type;};
834 template <> struct TypeMap<TOPIC_ALTITUDE_BAROMETER > { typedef float32_t type;};
835 template <> struct TypeMap<TOPIC_ALTITUDE_OF_HOMEPOINT > { typedef float32_t type;};
836 template <> struct TypeMap<TOPIC_HEIGHT_FUSION > { typedef float32_t type;};
837 template <> struct TypeMap<TOPIC_GPS_FUSED > { typedef GPSFused type;};
838 template <> struct TypeMap<TOPIC_GPS_DATE > { typedef uint32_t type;};
839 template <> struct TypeMap<TOPIC_GPS_TIME > { typedef uint32_t type;};
840 template <> struct TypeMap<TOPIC_GPS_POSITION > { typedef Vector3d type;};
841 template <> struct TypeMap<TOPIC_GPS_VELOCITY > { typedef Vector3f type;};
842 template <> struct TypeMap<TOPIC_GPS_DETAILS > { typedef GPSDetail type;};
843 template <> struct TypeMap<TOPIC_RTK_POSITION > { typedef PositionData type;};
844 template <> struct TypeMap<TOPIC_RTK_VELOCITY > { typedef Vector3f type;};
845 template <> struct TypeMap<TOPIC_RTK_YAW > { typedef int16_t type;};
846 template <> struct TypeMap<TOPIC_RTK_POSITION_INFO > { typedef uint8_t type;};
847 template <> struct TypeMap<TOPIC_RTK_YAW_INFO > { typedef uint8_t type;};
848 template <> struct TypeMap<TOPIC_COMPASS > { typedef Mag type;};
849 template <> struct TypeMap<TOPIC_RC > { typedef RC type;};
850 template <> struct TypeMap<TOPIC_GIMBAL_ANGLES > { typedef Vector3f type;};
851 template <> struct TypeMap<TOPIC_GIMBAL_STATUS > { typedef GimbalStatus type;};
852 template <> struct TypeMap<TOPIC_STATUS_FLIGHT > { typedef uint8_t type;};
853 template <> struct TypeMap<TOPIC_STATUS_DISPLAYMODE > { typedef uint8_t type;};
854 template <> struct TypeMap<TOPIC_STATUS_LANDINGGEAR > { typedef uint8_t type;};
855 template <> struct TypeMap<TOPIC_STATUS_MOTOR_START_ERROR > { typedef uint16_t type;};
856 template <> struct TypeMap<TOPIC_BATTERY_INFO > { typedef Battery type;};
857 template <> struct TypeMap<TOPIC_CONTROL_DEVICE > { typedef SDKInfo type;};
858 template <> struct TypeMap<TOPIC_HARD_SYNC > { typedef HardSyncData type;};
859 template <> struct TypeMap<TOPIC_GPS_SIGNAL_LEVEL > { typedef uint8_t type;};
860 template <> struct TypeMap<TOPIC_GPS_CONTROL_LEVEL > { typedef uint8_t type;};
861 template <> struct TypeMap<TOPIC_RC_FULL_RAW_DATA > { typedef RCFullRawData type;};
862 template <> struct TypeMap<TOPIC_RC_WITH_FLAG_DATA > { typedef RCWithFlagData type;};
863 template <> struct TypeMap<TOPIC_ESC_DATA > { typedef EscData type;};
864 template <> struct TypeMap<TOPIC_RTK_CONNECT_STATUS > { typedef RTKConnectStatus type;};
865 template <> struct TypeMap<TOPIC_GIMBAL_CONTROL_MODE > { typedef GimbalControlMode type;};
866 template <> struct TypeMap<TOPIC_FLIGHT_ANOMALY > { typedef FlightAnomaly type;};
867 template <> struct TypeMap<TOPIC_POSITION_VO > { typedef LocalPositionVO type;};
868 template <> struct TypeMap<TOPIC_AVOID_DATA > { typedef RelativePosition type;};
869 template <> struct TypeMap<TOPIC_HOME_POINT_SET_STATUS > { typedef HomeLocationSetStatus type;};
870 template <> struct TypeMap<TOPIC_HOME_POINT_INFO > { typedef HomeLocationData type;};
871 template <> struct TypeMap<TOPIC_DUAL_GIMBAL_DATA > { typedef GimbalDualData type;};
872 template <> struct TypeMap<TOPIC_THREE_GIMBAL_DATA > { typedef GimbalThreeData type;};
873 // clang-format on
874 }
875 }
876 }
877 #endif // ONBOARDSDK_DJI_Telemetry_H
uint32_t gpsYawError
Definition: dji_telemetry.hpp:736
struct for TOPIC_GPS_DETAILS and sub struct for GPSInfo of data broadcast
Definition: dji_telemetry.hpp:361
float64_t latitude
Definition: dji_telemetry.hpp:334
uint32_t mountStatus
Definition: dji_telemetry.hpp:480
uint16_t index
Definition: dji_telemetry.hpp:561
uint32_t installedDirection
Definition: dji_telemetry.hpp:487
uint32_t imuInstallationError
Definition: dji_telemetry.hpp:733
struct DJI::OSDK::Telemetry::SBUSFullRawData SBUSFullRawData
struct for the sbus part of TOPIC_RC_FULL_RAW_DATA
struct for TOPIC_ESC_DATA
Definition: dji_telemetry.hpp:634
Provides RTK connection status @ up to 50Hz.
Definition: dji_telemetry.hpp:99
uint8_t upHealth
Definition: dji_telemetry.hpp:313
struct DJI::OSDK::Telemetry::Quaternion Quaternion
struct for TOPIC_QUATERNION
float32_t x
Definition: dji_telemetry.hpp:745
int16_t mode
Definition: dji_telemetry.hpp:648
struct for TOPIC_HOME_POINT_INFO
Definition: dji_telemetry.hpp:342
int16_t rcD1
Definition: dji_telemetry.hpp:658
Provides the altitude from sea level when the aircraft last took off.
Definition: dji_telemetry.hpp:70
struct DJI::OSDK::Telemetry::GimbalStatus GimbalStatus
struct for TOPIC_GIMBAL_STATUS
uint32_t escYawStatus
Definition: dji_telemetry.hpp:493
Provides various data about the battery @ up to 50Hz.
Definition: dji_telemetry.hpp:91
uint32_t yawLimited
Definition: dji_telemetry.hpp:484
uint8_t flightStatus
Definition: dji_telemetry.hpp:546
Provides double gimbal information, used for M210V2.
Definition: dji_telemetry.hpp:106
float64_t latitude
Definition: dji_telemetry.hpp:274
float32_t q1
Definition: dji_telemetry.hpp:191
sub struct for RTK of data broadcast
Definition: dji_telemetry.hpp:393
Provides aircraft's raw Real-Time Kinematic (RTK) yaw @ up to 5Hz.
Definition: dji_telemetry.hpp:80
struct for multiple Topics
Definition: dji_telemetry.hpp:211
struct for TOPIC_HARD_SYNC
Definition: dji_telemetry.hpp:577
Provides gimbal status and error codes @ up to 50Hz.
Definition: dji_telemetry.hpp:86
VelocityInfo info
Definition: dji_telemetry.hpp:264
struct for data broadcast and subscription, return obstacle info around the vehicle
Definition: dji_telemetry.hpp:300
int32_t latitude
Definition: dji_telemetry.hpp:384
int32_t longitude
Definition: dji_telemetry.hpp:383
uint32_t droneDataRecv
Definition: dji_telemetry.hpp:494
float64_t latitude
Definition: dji_telemetry.hpp:290
uint8_t yawHealthFlag
Definition: dji_telemetry.hpp:430
struct indicates the signal level of GPS velocity info
Definition: dji_telemetry.hpp:245
Provides aircraft's GPS/IMU fused X-Y position and barometric altitude (put together in a single topi...
Definition: dji_telemetry.hpp:72
Provides a measure of the quality of GPS signal, with a mechanism for guarding against unset homepoin...
Definition: dji_telemetry.hpp:95
int16_t rcC1
Definition: dji_telemetry.hpp:656
float32_t q0
Definition: dji_telemetry.hpp:190
float64_t longitude
Definition: dji_telemetry.hpp:289
struct for TOPIC_VELOCITY
Definition: dji_telemetry.hpp:258
float32_t q2
Definition: dji_telemetry.hpp:192
uint32_t pitchLimited
Definition: dji_telemetry.hpp:482
uint8_t appConnected
Definition: dji_telemetry.hpp:608
uint8_t health
Definition: dji_telemetry.hpp:248
struct DJI::OSDK::Telemetry::Battery Battery
struct for TOPIC_BATTERY_INFO and data broadcast, return battery status
Vector3f velocityNED
Definition: dji_telemetry.hpp:409
int32_t HFSL
Definition: dji_telemetry.hpp:807
struct for TOPIC_QUATERNION
Definition: dji_telemetry.hpp:188
uint8_t deviceStatus
Definition: dji_telemetry.hpp:544
float64_t longitude
Definition: dji_telemetry.hpp:345
struct for TOPIC_RC_WITH_FLAG_DATA
Definition: dji_telemetry.hpp:597
uint8_t backHealth
Definition: dji_telemetry.hpp:311
Provides three gimbal information, used for M300.
Definition: dji_telemetry.hpp:107
Provides the aircraft's internal flight state @ up to 50Hz.
Definition: dji_telemetry.hpp:87
struct DJI::OSDK::Telemetry::GlobalPosition GlobalPosition
struct for data broadcast, return GPS data
struct for TOPIC_THREE_GIMBAL_DATA
Definition: dji_telemetry.hpp:714
uint32_t yawCtrlFail
Definition: dji_telemetry.hpp:728
int16_t roll
Definition: dji_telemetry.hpp:644
uint32_t usedGLN
Definition: dji_telemetry.hpp:370
int16_t temperature
Definition: dji_telemetry.hpp:621
float32_t fix
Definition: dji_telemetry.hpp:365
uint8_t posHealthFlag
Definition: dji_telemetry.hpp:429
struct for data broadcast, return RTK info
Definition: dji_telemetry.hpp:404
uint32_t strongWindLevel2
Definition: dji_telemetry.hpp:731
uint8_t health
Definition: dji_telemetry.hpp:780
int16_t rcC2
Definition: dji_telemetry.hpp:657
struct for data broadcast, return compass reading
Definition: dji_telemetry.hpp:455
float32_t down
Definition: dji_telemetry.hpp:302
int16_t throttle
Definition: dji_telemetry.hpp:647
Provides a status on aircraft's Real-Time Kinematic (RTK) yaw solution @ up to 5Hz.
Definition: dji_telemetry.hpp:82
struct for TOPIC_HOME_POINT_SET_STATUS
Definition: dji_telemetry.hpp:351
uint16_t empty
Definition: dji_telemetry.hpp:623
struct DJI::OSDK::Telemetry::Velocity Velocity
struct for TOPIC_VELOCITY
float64_t longitude
Definition: dji_telemetry.hpp:333
Vector3f velocityNED
Definition: dji_telemetry.hpp:808
struct DJI::OSDK::Telemetry::Compass Compass
struct for data broadcast, return compass reading
int16_t yaw
Definition: dji_telemetry.hpp:646
struct DJI::OSDK::Telemetry::FlightAnomaly FlightAnomaly
struct for TOPIC_FLIGHT_ANOMALY
float32_t front
Definition: dji_telemetry.hpp:303
struct DJI::OSDK::Telemetry::LB2RcFullRawData LB2RcFullRawData
struct for the light bridge 2 part of TOPIC_RC_FULL_RAW_DATA
int16_t yaw
Definition: dji_telemetry.hpp:411
Provides quaternion representing ground frame (NED) to body frame (FRD) rotation @ up to 200Hz.
Definition: dji_telemetry.hpp:61
struct for TopicInfo data used to subscribe packages from the FC
Definition: dji_telemetry.hpp:173
float32_t throttle
Definition: dji_telemetry.hpp:602
Provides raw remote controller stick, buttons and switch data @ up to 50Hz.
Definition: dji_telemetry.hpp:96
struct DJI::OSDK::Telemetry::LegacyVelocity LegacyVelocity
Matrice 100 Velocity struct, returned in Broadcast telemetry (only for M100)
int16_t leftWheel
Definition: dji_telemetry.hpp:654
float32_t roll
Definition: dji_telemetry.hpp:506
struct DJI::OSDK::Telemetry::GPSInfo GPSInfo
struct for GPSInfo of data broadcast
Provides aircraft's fused altitude from sea level using the ICAO model @ up to 200Hz.
Definition: dji_telemetry.hpp:68
Timestamp for GPS and RTK.
Definition: dji_telemetry.hpp:322
Provides states of the aircraft related to SDK/RC control.
Definition: dji_telemetry.hpp:92
uint8_t health
Definition: dji_telemetry.hpp:278
struct DJI::OSDK::Telemetry::Mag Mag
struct for data broadcast, return magnetometer reading
struct DJI::OSDK::Telemetry::ESCStatusIndividual ESCStatusIndividual
struct for status of each individual esc
struct for data broadcast, return gimbal angle
Definition: dji_telemetry.hpp:503
struct indicating RTK GPS Connection
Definition: dji_telemetry.hpp:588
struct for TOPIC_GPS_FUSED
Definition: dji_telemetry.hpp:287
SyncTimestamp ts
Definition: dji_telemetry.hpp:579
struct for data broadcast, timestamp from local cache
Definition: dji_telemetry.hpp:223
uint16_t temperatureHigh
Definition: dji_telemetry.hpp:626
uint32_t time1ns
Definition: dji_telemetry.hpp:558
struct DJI::OSDK::Telemetry::Gimbal Gimbal
struct for data broadcast, return gimbal angle
uint8_t rightHealth
Definition: dji_telemetry.hpp:310
Provides aircraft's acceleration w.r.t a ground-fixed NEU frame @ up to 200Hz.
Definition: dji_telemetry.hpp:62
uint8_t frontHealth
Definition: dji_telemetry.hpp:309
uint8_t flag
Definition: dji_telemetry.hpp:568
struct DJI::OSDK::Telemetry::RTK RTK
struct for data broadcast, return RTK info
struct for data broadcast, software sync timestamp from local cache
Definition: dji_telemetry.hpp:234
uint32_t rollPitchCtrlFail
Definition: dji_telemetry.hpp:727
uint8_t rollLimit
Definition: dji_telemetry.hpp:510
int16_t rightWheelButton
Definition: dji_telemetry.hpp:655
Provides status of whether the home point was set or not.
Definition: dji_telemetry.hpp:104
template struct maps a topic name to the corresponding data type
Definition: dji_telemetry.hpp:820
struct DJI::OSDK::Telemetry::VelocityInfo VelocityInfo
struct indicates the signal level of GPS velocity info
uint32_t impactInAir
Definition: dji_telemetry.hpp:724
int16_t videoPause
Definition: dji_telemetry.hpp:652
uint8_t leftHealth
Definition: dji_telemetry.hpp:312
float32_t back
Definition: dji_telemetry.hpp:305
uint16_t NSV
Definition: dji_telemetry.hpp:371
Provides obstacle info around the vehicle @ up to 100Hz.
Definition: dji_telemetry.hpp:103
uint8_t flight
Definition: dji_telemetry.hpp:520
TopicName
enum TopicName is the interface for user to create packages and access data It is also used as index ...
Definition: dji_telemetry.hpp:59
int32_t HFSL
Definition: dji_telemetry.hpp:385
uint16_t escDisconnected
Definition: dji_telemetry.hpp:625
uint32_t randomFly
Definition: dji_telemetry.hpp:725
uint32_t escRollStatus
Definition: dji_telemetry.hpp:492
Provides aircraft's acceleration w.r.t a body-fixed FRU frame @ up to 200Hz.
Definition: dji_telemetry.hpp:63
uint8_t status
Definition: dji_telemetry.hpp:353
Provides aircraft's angular velocity in an IMU-centered, body-fixed FRD frame @ up to 400Hz.
Definition: dji_telemetry.hpp:67
uint8_t controlMode
Definition: dji_telemetry.hpp:543
If motors failed to start, this topic provides reasons why. Available @ up to 50Hz.
Definition: dji_telemetry.hpp:90
struct DJI::OSDK::Telemetry::SyncTimestamp SyncTimestamp
sub struct for TOPIC_HARD_SYNC
struct DJI::OSDK::Telemetry::HardSyncData HardSyncData
struct for TOPIC_HARD_SYNC
int16_t camera
Definition: dji_telemetry.hpp:650
uint32_t time
Definition: dji_telemetry.hpp:325
struct for TOPIC_BATTERY_INFO and data broadcast, return battery status
Definition: dji_telemetry.hpp:530
Provides a granular state representation for various tasks/flight modes @ up to 50Hz.
Definition: dji_telemetry.hpp:88
uint32_t time_2p5ms
Definition: dji_telemetry.hpp:236
struct DJI::OSDK::Telemetry::HomeLocationSetStatus HomeLocationSetStatus
struct for TOPIC_HOME_POINT_SET_STATUS
Provides aircraft's raw GPS status and other details @ up to 5Hz.
Definition: dji_telemetry.hpp:77
Provides normalized remote controller stick input data, along with connection status @ up to 50Hz.
Definition: dji_telemetry.hpp:97
uint32_t date
Definition: dji_telemetry.hpp:324
uint32_t heightCtrlFail
Definition: dji_telemetry.hpp:726
struct for GPSInfo of data broadcast
Definition: dji_telemetry.hpp:802
struct for TOPIC_FLIGHT_ANOMALY
Definition: dji_telemetry.hpp:722
struct DJI::OSDK::Telemetry::LocalPositionVO LocalPositionVO
struct for TOPIC_POSITION_VO
uint8_t gear
Definition: dji_telemetry.hpp:522
uint32_t strongWindLevel1
Definition: dji_telemetry.hpp:730
struct for multiple Topics
Definition: dji_telemetry.hpp:199
uint32_t resetTime2p5ms
Definition: dji_telemetry.hpp:559
PositionFrame pos
Definition: dji_telemetry.hpp:407
uint32_t escTemperatureHigh
Definition: dji_telemetry.hpp:734
float64_t longitude
Definition: dji_telemetry.hpp:275
struct DJI::OSDK::Telemetry::RC RC
struct for data broadcast and data subscription, return RC reading
Quaternion q
Definition: dji_telemetry.hpp:580
struct DJI::OSDK::Telemetry::Vector3f Vector3f
struct for multiple Topics
struct DJI::OSDK::Telemetry::Vector3d Vector3d
struct for multiple Topics
struct DJI::OSDK::Telemetry::EscData EscData
struct for TOPIC_ESC_DATA
struct for data broadcast, return GPS data
Definition: dji_telemetry.hpp:272
float32_t yaw
Definition: dji_telemetry.hpp:601
TOPIC_UID
enum TOPIC_UID is the UID that is accepted by the FC
Definition: dji_telemetry.hpp:116
uint8_t yawLimit
Definition: dji_telemetry.hpp:511
uint16_t visibleSatelliteNumber
Definition: dji_telemetry.hpp:292
uint32_t compassInstallationError
Definition: dji_telemetry.hpp:732
float32_t yaw
Definition: dji_telemetry.hpp:508
float32_t HFSL
Definition: dji_telemetry.hpp:335
struct DJI::OSDK::Telemetry::SyncStamp SyncStamp
struct for data broadcast, software sync timestamp from local cache
struct DJI::OSDK::Telemetry::SDKInfo SDKInfo
struct for TOPIC_CONTROL_DEVICE and data broadcast, return SDK info
Provides raw data from the ESCs @ up to 50Hz.
Definition: dji_telemetry.hpp:98
Provides aircraft's raw Real-Time Kinematic (RTK) LLA @ up to 5Hz.
Definition: dji_telemetry.hpp:78
struct for TOPIC_CONTROL_DEVICE and data broadcast, return SDK info
Definition: dji_telemetry.hpp:541
struct DJI::OSDK::Telemetry::RCWithFlagData RCWithFlagData
struct for TOPIC_RC_WITH_FLAG_DATA
struct for data broadcast, return flight status
Definition: dji_telemetry.hpp:518
Provides aircraft's angular velocity in a ground-fixed NED frame @ up to 200Hz.
Definition: dji_telemetry.hpp:66
uint16_t voltage
Definition: dji_telemetry.hpp:620
float32_t up
Definition: dji_telemetry.hpp:307
union for TOPIC_RC_FULL_RAW_DATA Only support A3/N3/M600
Definition: dji_telemetry.hpp:683
uint32_t rollLimited
Definition: dji_telemetry.hpp:483
Provides aircraft's magnetometer reading, fused with IMU and GPS @ up to 100Hz.
Definition: dji_telemetry.hpp:83
Provides raw time information from GPS @ up to 5Hz.
Definition: dji_telemetry.hpp:74
uint32_t prevCalibrationgResult
Definition: dji_telemetry.hpp:486
float32_t hacc
Definition: dji_telemetry.hpp:367
float32_t left
Definition: dji_telemetry.hpp:306
Provides a number of flags which report different errors the aircraft may encounter in flight @ up to...
Definition: dji_telemetry.hpp:101
Provides aircraft's acceleration in an IMU-centered, body-fixed FRD frame @ up to 400Hz.
Definition: dji_telemetry.hpp:64
struct for TOPIC_POSITION_VO
Definition: dji_telemetry.hpp:743
Provides the relative height above ground at up to 100Hz.
Definition: dji_telemetry.hpp:71
struct for the light bridge 2 part of TOPIC_RC_FULL_RAW_DATA
Definition: dji_telemetry.hpp:642
uint16_t GPScounter
Definition: dji_telemetry.hpp:372
uint8_t LegacyStatus
Return type for flight status data broadcast (only for M100). Returns VehicleStatus::M100FlightStatus...
Definition: dji_telemetry.hpp:791
float32_t hdop
Definition: dji_telemetry.hpp:363
float32_t roll
Definition: dji_telemetry.hpp:600
float32_t pitch
Definition: dji_telemetry.hpp:599
struct DJI::OSDK::Telemetry::RelativePosition RelativePosition
struct for data broadcast and subscription, return obstacle info around the vehicle
uint32_t time2p5ms
Definition: dji_telemetry.hpp:556
Provides gimbal pitch, roll, yaw @ up to 50Hz.
Definition: dji_telemetry.hpp:85
Provides a measure of the quality of GPS signal @ up to 50Hz.
Definition: dji_telemetry.hpp:94
struct for TOPIC_GIMBAL_STATUS
Definition: dji_telemetry.hpp:478
struct DJI::OSDK::Telemetry::GPSDetail GPSDetail
struct for TOPIC_GPS_DETAILS and sub struct for GPSInfo of data broadcast
uint8_t LegacyBattery
Return type for battery data broadcast (only for M100). Returns percentage.
Definition: dji_telemetry.hpp:795
Provides aircraft's velocity in a ground-fixed NEU frame @ up to 200Hz.
Definition: dji_telemetry.hpp:65
Provides IMU and quaternion data time-synced with a hardware clock signal @ up to 400Hz.
Definition: dji_telemetry.hpp:93
Matrice 100 Timestamp data, available in Broadcast telemetry (only for M100)
Definition: dji_telemetry.hpp:759
Provides aircraft's raw Real-Time Kinematic (RTK) velocity @ up to 5Hz.
Definition: dji_telemetry.hpp:79
struct DJI::OSDK::Telemetry::LegacyGPSInfo LegacyGPSInfo
struct for GPSInfo of data broadcast
Provides raw date information from GPS @ up to 5Hz.
Definition: dji_telemetry.hpp:73
int16_t throttle
Definition: dji_telemetry.hpp:468
float32_t sacc
Definition: dji_telemetry.hpp:368
Data type and Data Structure definitions for use throughout DJI OSDK.
Vector3f a
Definition: dji_telemetry.hpp:581
struct DJI::OSDK::Telemetry::PositionFrame PositionFrame
sub struct for RTK of data broadcast
uint32_t gyroFalut
Definition: dji_telemetry.hpp:490
uint32_t atLeastOneEscDisconnected
Definition: dji_telemetry.hpp:735
struct DJI::OSDK::Telemetry::GimbalThreeData GimbalThreeData
struct for TOPIC_THREE_GIMBAL_DATA
float32_t gnssStatus
Definition: dji_telemetry.hpp:366
struct for GPSInfo of data broadcast
Definition: dji_telemetry.hpp:380
uint8_t mode
Definition: dji_telemetry.hpp:521
struct DJI::OSDK::Telemetry::TimeStamp TimeStamp
struct for data broadcast, timestamp from local cache
Provides a status on aircraft's Real-Time Kinematic (RTK) positioning solution @ up to 5Hz.
Definition: dji_telemetry.hpp:81
float32_t right
Definition: dji_telemetry.hpp:304
int16_t pitch
Definition: dji_telemetry.hpp:466
struct DJI::OSDK::Telemetry::LegacyTimeStamp LegacyTimeStamp
Matrice 100 Timestamp data, available in Broadcast telemetry (only for M100)
struct DJI::OSDK::Telemetry::RTKConnectStatus RTKConnectStatus
struct indicating RTK GPS Connection
int16_t mode
Definition: dji_telemetry.hpp:469
struct for TOPIC_RTK_POSITION and sub struct for RTK of data broadcast
Definition: dji_telemetry.hpp:331
struct DJI::OSDK::Telemetry::PositionData PositionData
struct for TOPIC_RTK_POSITION and sub struct for RTK of data broadcast
uint32_t FWUpdating
Definition: dji_telemetry.hpp:496
uint16_t stall
Definition: dji_telemetry.hpp:622
Provides status for the landing gear state @ up to 50Hz.
Definition: dji_telemetry.hpp:89
uint8_t logicConnected
Definition: dji_telemetry.hpp:605
int16_t current
Definition: dji_telemetry.hpp:618
float32_t altitude
Definition: dji_telemetry.hpp:291
Vector3f velocityNED
Definition: dji_telemetry.hpp:386
Provides the mode in which the gimbal will interpret control commands @ up to 50Hz.
Definition: dji_telemetry.hpp:100
struct for the sbus part of TOPIC_RC_FULL_RAW_DATA
Definition: dji_telemetry.hpp:673
Definition: dji_ack.cpp:38
struct DJI::OSDK::Telemetry::Status Status
struct for data broadcast, return flight status
struct for data broadcast, return magnetometer reading
Definition: dji_telemetry.hpp:439
uint32_t aircraftIsFalling
Definition: dji_telemetry.hpp:729
float32_t z
Definition: dji_telemetry.hpp:747
int16_t pitch
Definition: dji_telemetry.hpp:645
int16_t gear
Definition: dji_telemetry.hpp:471
int32_t longitude
Definition: dji_telemetry.hpp:805
float32_t pitch
Definition: dji_telemetry.hpp:507
struct for TOPIC_DUAL_GIMBAL_DATA
Definition: dji_telemetry.hpp:706
int16_t yaw
Definition: dji_telemetry.hpp:467
uint32_t calibrating
Definition: dji_telemetry.hpp:485
Provides aircraft's raw GPS LLA @ up to 5Hz.
Definition: dji_telemetry.hpp:75
struct for status of each individual esc
Definition: dji_telemetry.hpp:616
Provides remote controller stick inputs @ up to 100Hz.
Definition: dji_telemetry.hpp:84
int16_t video
Definition: dji_telemetry.hpp:651
Provides aircraft's position in a Cartesian frame @ up to 50Hz, without the need for GPS.
Definition: dji_telemetry.hpp:102
uint32_t initUnfinished
Definition: dji_telemetry.hpp:495
struct for data broadcast and data subscription, return RC reading
Definition: dji_telemetry.hpp:463
float32_t y
Definition: dji_telemetry.hpp:746
struct DJI::OSDK::Telemetry::HomeLocationData HomeLocationData
struct for TOPIC_HOME_POINT_INFO
float64_t latitude
Definition: dji_telemetry.hpp:344
float32_t altitude
Definition: dji_telemetry.hpp:276
Vector3f w
Definition: dji_telemetry.hpp:582
int16_t roll
Definition: dji_telemetry.hpp:465
int32_t latitude
Definition: dji_telemetry.hpp:806
struct DJI::OSDK::Telemetry::GPSFused GPSFused
struct for TOPIC_GPS_FUSED
uint8_t downHealth
Definition: dji_telemetry.hpp:308
struct DJI::OSDK::Telemetry::GimbalDualData GimbalDualData
struct for TOPIC_DUAL_GIMBAL_DATA
uint32_t escPitchStatus
Definition: dji_telemetry.hpp:491
float32_t height
Definition: dji_telemetry.hpp:277
Provides aircraft's raw GPS velocity @ up to 5Hz.
Definition: dji_telemetry.hpp:76
uint8_t groundConnected
Definition: dji_telemetry.hpp:607
Provides aircraft's pressure altitude from sea level using the ICAO model @ up to 200Hz.
Definition: dji_telemetry.hpp:69
int16_t speed
Definition: dji_telemetry.hpp:619
Provides homepoint information, the valid of the home point infomation can ref to the topic DJI_DATA_...
Definition: dji_telemetry.hpp:105
uint8_t pitchLimit
Definition: dji_telemetry.hpp:509
int16_t gear
Definition: dji_telemetry.hpp:649
uint8_t reserved
Definition: dji_telemetry.hpp:314
uint8_t error
Definition: dji_telemetry.hpp:523
uint32_t usedGPS
Definition: dji_telemetry.hpp:369
float32_t q3
Definition: dji_telemetry.hpp:193
uint8_t skyConnected
Definition: dji_telemetry.hpp:606
struct DJI::OSDK::Telemetry::PositionTimeStamp PositionTimeStamp
Timestamp for GPS and RTK.
float32_t pdop
Definition: dji_telemetry.hpp:364
int16_t goHome
Definition: dji_telemetry.hpp:653
sub struct for TOPIC_HARD_SYNC
Definition: dji_telemetry.hpp:554
uint16_t unbalanced
Definition: dji_telemetry.hpp:624
Matrice 100 Velocity struct, returned in Broadcast telemetry (only for M100)
Definition: dji_telemetry.hpp:772