DJI_Type.h
Go to the documentation of this file.
00001 
00019 #ifndef DJI_TYPE
00020 #define DJI_TYPE
00021 
00022 #include "DJI_Config.h"
00023 #include "DJICommonType.h"
00024 #include <stdio.h>
00025 #include <exception>
00026 #include <stdexcept>
00027 
00028 #define NAME(x) #x
00029 
00031 #ifdef __GNUC__
00032 #define __UNUSED __attribute__((__unused__))
00033 #define __DELETE(x) delete (char *) x
00034 #else
00035 #define __UNUSED
00036 #define __DELETE(x) delete x
00037 
00038 
00040 #ifndef STM32
00041 #pragma warning(disable : 4100)
00042 #pragma warning(disable : 4800)
00043 #pragma warning(disable : 4996)
00044 #pragma warning(disable : 4244)
00045 #pragma warning(disable : 4267)
00046 #pragma warning(disable : 4700)
00047 #pragma warning(disable : 4101)
00048 #endif // STM32
00049 #endif //__GNUC__
00050 
00051 #ifdef WIN32
00052 #define __func__ __FUNCTION__
00053 #endif // WIN32
00054 
00055 
00057 #define API_LOG(driver, title, fmt, ...)                                  \
00058   if ((title))                                                            \
00059   {                                                                       \
00060     int len = (sprintf(DJI::onboardSDK::buffer, "%s %s,line %d: " fmt,    \
00061         (title) ? (title) : "NONE", __func__, __LINE__, ##__VA_ARGS__));  \
00062     if ((len != -1) && (len < 1024))                                      \
00063       (driver)->displayLog();                                             \
00064     else                                                                  \
00065       (driver)->displayLog("ERROR: log printer inner fault\n");           \
00066   }
00067 
00068 #ifdef API_TRACE_DATA
00069 #define TRACE_LOG "TRACE"
00070 #else
00071 #define TRACE_LOG 0
00072 #endif
00073 
00074 #ifdef API_DEBUG_DATA
00075 #define DEBUG_LOG "DEBUG"
00076 #else
00077 #define DEBUG_LOG 0
00078 #endif
00079 
00080 #ifdef API_ERROR_DATA
00081 #define ERROR_LOG "ERROR"
00082 #else
00083 #define ERROR_LOG 0
00084 #endif
00085 
00086 #ifdef API_BUFFER_DATA
00087 #define BUFFER_LOG "BUFFER"
00088 #else
00089 #define BUFFER_LOG 0
00090 #endif
00091 
00092 #ifdef API_STATUS_DATA
00093 #define STATUS_LOG "STATUS"
00094 #else
00095 #define STATUS_LOG 0
00096 #endif
00097 
00098 #ifdef API_MISSION_DATA
00099 #define MISSION_LOG "MISSION"
00100 #else
00101 #define MISSION_LOG 0
00102 #endif
00103 
00104 #ifdef API_RTK_DEBUG
00105 #define RTK_LOG "MISSION"
00106 #else
00107 #define RTK_LOG 0
00108 #endif
00109 
00111 #ifdef ARMCC
00112 #pragma anon_unions
00113 #endif
00114 
00115 namespace DJI
00116 {
00117 namespace onboardSDK
00118 {
00119 
00120 const size_t bufsize = 1024;
00121 extern char buffer[];
00122 extern uint8_t encrypt;
00123 
00124 const size_t SESSION_TABLE_NUM = 32;
00125 const size_t CALLBACK_LIST_NUM = 10;
00126 
00130 const size_t MAX_ACK_SIZE = 64;
00131 const size_t M100_MAX_ACK_SIZE = 64;
00132 const size_t A3_MAX_ACK_SIZE = 63;
00133 
00135 class CoreAPI;
00136 
00138 typedef struct Header
00139 {
00140   unsigned int sof : 8;
00141   unsigned int length : 10;
00142   unsigned int version : 6;
00143   unsigned int sessionID : 5;
00144   unsigned int isAck : 1;
00146   unsigned int reversed0 : 2; // always 0
00147 
00148   unsigned int padding : 5;
00149   unsigned int enc : 3;
00151   unsigned int reversed1 : 24;
00152 
00153   unsigned int sequenceNumber : 16;
00154   unsigned int crc : 16;
00155 } Header;
00156 
00158 typedef void (*CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData);
00159 
00161 typedef struct CallBackHandler
00162 {
00163   CallBack callback;
00164   UserData userData;
00165 } CallBackHandler;
00166 
00167 typedef struct Command
00168 {
00169   unsigned short sessionMode : 2;
00170   unsigned short encrypt : 1;
00171   unsigned short retry : 13;
00172   unsigned short timeout; // unit is ms
00173   size_t length;
00174   uint8_t *buf;
00175   CallBack handler;
00176   UserData userData;
00177 } Command;
00178 
00180 typedef struct SDKFilter
00181 {
00182   unsigned short reuseIndex;
00183   unsigned short reuseCount;
00184   unsigned short recvIndex;
00185   unsigned char recvBuf[BUFFER_SIZE];
00186   // for encrypt
00187   unsigned char sdkKey[32];
00188   unsigned char encode;
00189 } SDKFilter;
00190 
00192 typedef struct MMU_Tab
00193 {
00194   unsigned int tabIndex : 8;
00195   unsigned int usageFlag : 8;
00196   unsigned int memSize : 16;
00197   unsigned char *pmem;
00198 } MMU_Tab;
00199 
00200 typedef struct CMDSession
00201 {
00202   uint32_t sessionID : 5;
00203   uint32_t usageFlag : 1;
00204   uint32_t sent : 5;
00205   uint32_t retry : 5;
00206   uint32_t timeout : 16;
00207   MMU_Tab *mmu;
00208   CallBack handler;
00209   UserData userData;
00210   uint32_t preSeqNum;
00211   time_ms preTimestamp;
00212 } CMDSession;
00213 
00214 typedef struct ACKSession
00215 {
00216   uint32_t sessionID : 5;
00217   uint32_t sessionStatus : 2;
00218   uint32_t res : 25;
00219   MMU_Tab *mmu;
00220 } ACKSession;
00221 
00222 typedef struct Ack
00223 {
00224   uint16_t sessionID : 8;
00225   uint16_t encrypt : 8;
00226   uint16_t seqNum;
00227   uint32_t length;
00228   uint8_t *buf;
00229 } Ack;
00230 
00231 #pragma pack(1)
00232 
00233 typedef uint8_t BatteryData;
00234 
00238 typedef struct GimbalAngleData
00239 {  
00240   int16_t yaw;
00241   int16_t roll;
00242   int16_t pitch;
00243   uint8_t mode;
00244   uint8_t duration;
00245 } GimbalAngleData;
00246 
00247 typedef struct GimbalSpeedData
00248 {
00249   int16_t yaw;
00250   int16_t roll;
00251   int16_t pitch;
00252   uint8_t reserved; // always 0x80;
00253 } GimbalSpeedData;
00254 
00255 typedef float float32_t;
00256 typedef double float64_t;
00257 
00261 typedef struct HotPointData
00262 {
00263   uint8_t version;
00264 
00265   float64_t latitude;
00266   float64_t longitude;
00267   float64_t height;
00268 
00269   float64_t radius;
00270   float32_t yawRate; // degree
00271 
00272   uint8_t clockwise;
00273   uint8_t startPoint;
00274   uint8_t yawMode;
00275   uint8_t reserved[11];
00276 } HotPointData;
00277 
00281 typedef struct WayPointInitData
00282 {
00283   uint8_t indexNumber;
00284   float32_t maxVelocity;
00285   float32_t idleVelocity;
00286 
00287   uint8_t finishAction;
00288   uint8_t executiveTimes;
00289   uint8_t yawMode;
00290   uint8_t traceMode;
00291   uint8_t RCLostAction;
00292   uint8_t gimbalPitch;
00293   float64_t latitude;  
00294   float64_t longitude; 
00295   float32_t altitude;
00296 
00297   uint8_t reserved[16];
00298 } WayPointInitData;
00299 
00300 typedef struct WayPointData
00301 {
00302   uint8_t index;
00303 
00304   float64_t latitude;
00305   float64_t longitude;
00306   float32_t altitude;
00307   float32_t damping;
00308 
00309   int16_t yaw;
00310   int16_t gimbalPitch;
00311   uint8_t turnMode;
00312 
00313   uint8_t reserved[8];
00314   uint8_t hasAction;
00315   uint16_t actionTimeLimit;
00316 
00317   uint8_t actionNumber : 4;
00318   uint8_t actionRepeat : 4;
00319 
00320   uint8_t commandList[16];
00321   int16_t commandParameter[16];
00322 } WayPointData;
00323 
00328 typedef uint8_t MissionACK;
00329 typedef uint16_t SimpleACK;
00330 
00331 typedef struct HotPointStartACK
00332 {
00333   uint8_t ack;
00334   float32_t maxRadius;
00335 } HotpointStartACK;
00336 
00337 typedef struct WayPointDataACK
00338 {
00339   uint8_t ack;
00340   uint8_t index;
00341 } WayPointDataACK;
00342 
00343 typedef struct WayPointVelocityACK
00344 {
00345   uint8_t ack;
00346   float32_t idleVelocity;
00347 } WayPointVelocityACK;
00348 
00349 // HotPoint data read from flight controller
00350 typedef struct HotPointReadACK
00351 {
00352   MissionACK ack;
00353   HotPointData data;
00354 } HotpointReadACK;
00355 
00356 typedef struct WayPointInitACK
00357 {
00358   uint8_t ack;
00359   WayPointInitData data;
00360 } WayPointInitACK;
00361 
00362 typedef struct DroneVersionACK
00363 {
00364   unsigned char ack[MAX_ACK_SIZE];
00365 };
00366 
00367 typedef union MissionACKUnion
00368 { 
00369   uint8_t raw_ack_array[MAX_ACK_SIZE];
00370   DroneVersionACK droneVersion;
00371   MissionACK missionACK;
00372 
00373   SimpleACK simpleACK;
00374 
00375   HotPointStartACK hotpointStartACK;
00376 
00377   // Contains 1-Byte ACK plus hotpoint mission
00378   // information read from flight controller
00379   HotpointReadACK hotpointReadACK;
00380 
00381   // Contains 1-Byte ACK plus waypoint mission
00382   // information read from flight controller
00383   WayPointInitACK waypointInitACK;
00384 
00385   WayPointDataACK waypointDataACK;
00386   WayPointVelocityACK waypointVelocityACK;
00387 } MissionACKUnion; 
00388 
00389 typedef struct QuaternionData
00390 {
00391   float32_t q0;
00392   float32_t q1;
00393   float32_t q2;
00394   float32_t q3;
00395 } QuaternionData;
00396 
00398 typedef struct CommonData
00399 {
00400   float32_t x;
00401   float32_t y;
00402   float32_t z;
00403 } CommonData;
00404 
00407 typedef struct Vector3fData
00408 {
00409   float32_t x;
00410   float32_t y;
00411   float32_t z;
00412 } Vector3fData;
00413 
00414 typedef struct VelocityData
00415 {
00416   float32_t x;
00417   float32_t y;
00418   float32_t z;
00419   uint8_t health : 1;
00420   uint8_t sensorID : 4;
00421   uint8_t reserve : 3;
00422 } VelocityData;
00423 
00424 typedef struct PositionData
00425 {
00426   float64_t latitude;
00427   float64_t longitude;
00431   float32_t altitude;
00432 
00436   float32_t height;
00437 
00438   uint8_t health;
00439 } PositionData;
00440 
00442 typedef struct RadioData
00443 {
00444   int16_t roll;
00445   int16_t pitch;
00446   int16_t yaw;
00447   int16_t throttle;
00448   int16_t mode;
00449   int16_t gear;
00450 } RadioData;
00451 
00453 typedef struct RCData
00454 {
00455   int16_t roll;
00456   int16_t pitch;
00457   int16_t yaw;
00458   int16_t throttle;
00459   int16_t mode;
00460   int16_t gear;
00461 } RCData;
00462 
00464 typedef struct MagnetData
00465 {
00466   int16_t x;
00467   int16_t y;
00468   int16_t z;
00469 } MagnetData;
00470 
00472 typedef struct MagData
00473 {
00474   int16_t x;
00475   int16_t y;
00476   int16_t z;
00477 } MagData;
00478 
00481 typedef struct GPSPositionData
00482 {
00483   float64_t latitude;
00484   float64_t longitude;
00486   float64_t altitude;
00487 
00488 } GPSPositionData;
00489 
00490 typedef struct CtrlInfoData
00491 {
00492   uint8_t mode;
00494   uint8_t deviceStatus : 3; /*0->rc  1->app  2->serial*/
00495   uint8_t flightStatus : 1; /*1->opensd  0->close*/
00496   uint8_t vrcStatus : 1;
00497   uint8_t reserved : 3;
00498 } CtrlInfoData;
00499 
00500 typedef struct TimeStampData
00501 {
00503   uint32_t time;
00504   uint32_t nanoTime;
00505   uint8_t syncFlag;
00506 } TimeStampData;
00507 
00508 typedef struct GimbalData
00509 {
00510   float32_t roll;
00511   float32_t pitch;
00512   float32_t yaw;
00513   uint8_t pitchLimit : 1;
00514   uint8_t rollLimit : 1;
00515   uint8_t yawLimit : 1;
00516   uint8_t reserved : 5;
00517 } GimbalData;
00518 
00519 typedef uint8_t FlightStatus;
00520 
00521 typedef struct TaskData
00522 {
00523   unsigned char cmdSequence;
00524   unsigned char cmdData;
00525 } TaskData;
00526 
00529 typedef struct RTKData
00530 {
00531   uint32_t date;
00532   uint32_t time;
00533   float64_t longitude;
00534   float64_t latitude;
00536   float32_t Hmsl;
00537 
00538   float32_t velocityNorth;
00539   float32_t velocityEast;
00541   float32_t velocityGround;
00542   
00543   int16_t yaw;
00544   uint8_t posFlag;
00545   uint8_t yawFlag;
00546 
00547 } RTKData;
00548 
00551 typedef struct GPSData
00552 {
00553   uint32_t date;
00554   uint32_t time;
00555   int32_t longitude;
00556   int32_t latitude;
00558   int32_t Hmsl;
00559 
00560   float32_t velocityNorth;
00561   float32_t velocityEast;
00563   float32_t velocityGround;
00564 
00565 } GPSData;
00566 
00567 #ifndef SDK_DEV
00568 
00569 typedef struct BroadcastData
00570 {
00571   unsigned short dataFlag;
00572   TimeStampData timeStamp;
00573   QuaternionData q;
00575   CommonData a;
00576   VelocityData v;
00578   CommonData w;
00579   PositionData pos;
00581   MagnetData mag;
00582   GPSData gps;
00583   RTKData rtk;
00585   RadioData rc;
00586   GimbalData gimbal;
00587   FlightStatus status; 
00588   BatteryData battery;
00589   CtrlInfoData ctrlInfo;
00590 
00593   uint8_t activation;
00594 } BroadcastData;
00595 #endif // SDK_DEV
00596 
00597 typedef struct VirtualRCSetting
00598 {
00599   uint8_t enable : 1;
00600   uint8_t cutoff : 1;
00601   uint8_t reserved : 6;
00602 } VirtualRCSetting;
00603 
00604 typedef struct VirtualRCData
00605 {
00609   uint32_t roll;
00610   uint32_t pitch;
00611   uint32_t throttle;
00612   uint32_t yaw;
00613   uint32_t gear;
00614   uint32_t reserved;
00615   uint32_t mode;
00616   uint32_t Channel_07;
00617   uint32_t Channel_08;
00618   uint32_t Channel_09;
00619   uint32_t Channel_10;
00620   uint32_t Channel_11;
00621   uint32_t Channel_12;
00622   uint32_t Channel_13;
00623   uint32_t Channel_14;
00624   uint32_t Channel_15;
00625 } VirtualRCData;
00626 
00627 typedef struct ActivateData
00628 {
00629   unsigned int ID;
00630   unsigned int reserved;
00631   unsigned int version;
00632   unsigned char iosID[32];
00633   char *encKey;
00634 } ActivateData;
00635 
00636 typedef struct VersionData
00637 {
00638   unsigned short version_ack;
00639   unsigned int version_crc;
00640   char version_ID[11];
00641   char version_name[32];
00642   DJI::onboardSDK::Version version;
00643 } VersionData;
00644 
00645 #pragma pack()
00646 #ifdef SDK_DEV
00647 #include "devtype.h"
00648 #endif // SDK_DEV
00649 } // namespace onboardSDK
00650 } // namespace DJI
00651 
00652 #define PRO_PURE_DATA_MAX_SIZE 1007 // 2^10 - header size
00653 const size_t MMU_TABLE_NUM = 32;
00654 
00655 
00656 #endif // DJI_TYPE


dji_sdk_lib
Author(s):
autogenerated on Thu Jun 6 2019 17:55:25