DJI_API.h
Go to the documentation of this file.
00001 
00012 // The comment block below is made for doxygen.
00013 
00026 #ifndef DJI_API_H
00027 #define DJI_API_H
00028 
00029 #include "DJI_Type.h"
00030 #include "DJI_HardDriver.h"
00031 #include "DJI_App.h"
00032 
00033 namespace DJI
00034 {
00035 namespace onboardSDK
00036 {
00037 class CoreAPI;
00038 class Flight;
00039 class Camera;
00040 class VirtualRC;
00041 class HotPoint;
00042 
00044 
00045 enum ACK_ERROR_CODE
00046 {
00047   ACK_SUCCESS = 0x0000,
00048   ACK_PARAM_ERROR = 0x0001
00049 };
00050 
00051 enum ACK_COMMON_CODE
00052 {
00053   ACK_COMMON_SUCCESS = 0x0000,
00054   ACK_COMMON_KEYERROR = 0xFF00,
00055   ACK_COMMON_NO_AUTHORIZATION = 0xFF01,
00056   ACK_COMMON_NO_RIGHTS = 0xFF02,
00057   ACK_COMMON_NO_RESPONSE = 0xFFFF
00058 };
00059 
00060 enum ACK_ACTIVE_CODE
00061 {
00062   ACK_ACTIVE_SUCCESS = 0x0000,
00063   ACK_ACTIVE_PARAMETER_ERROR = 0x0001,
00064   ACK_ACTIVE_ENCODE_ERROR = 0x0002,
00065   ACK_ACTIVE_NEW_DEVICE = 0x0003,
00066   ACK_ACTIVE_APP_NOT_CONNECTED = 0x0004,
00067   ACK_ACTIVE_NO_INTERNET = 0x0005,
00068   ACK_ACTIVE_SERVER_REFUSED = 0x0006,
00069   ACK_ACTIVE_ACCESS_LEVEL_ERROR = 0x0007,
00070   ACK_ACTIVE_VERSION_ERROR = 0x0008
00071 };
00072 
00073 enum ACK_SETCONTROL_CODE
00074 {
00075   ACK_SETCONTROL_ERROR_MODE = 0x0000,
00076   ACK_SETCONTROL_RELEASE_SUCCESS = 0x0001,
00077   ACK_SETCONTROL_OBTAIN_SUCCESS = 0x0002,
00078   ACK_SETCONTROL_OBTAIN_RUNNING = 0x0003,
00079   ACK_SETCONTROL_RELEASE_RUNNING = 0x0004,
00080   ACK_SETCONTROL_NEED_MODE_F = 0x0006,
00081   ACK_SETCONTROL_NEED_MODE_P = 0x0005,
00082   ACK_SETCONTROL_IOC = 0x00C9,
00083 
00084 };
00085 
00086 enum ACK_ARM_CODE
00087 {
00088   ACK_ARM_SUCCESS = 0x0000,
00089   ACK_ARM_NEED_CONTROL = 0x0001,
00090   ACK_ARM_ALREADY_ARMED = 0x0002,
00091   ACK_ARM_IN_AIR = 0x0003,
00092 };
00093 
00094 enum TASK_ACK_CODE
00095 { 
00096   TASK_FAILURE = 0x01,
00097   TASK_SUCCESS = 0x02
00098 };
00099 
00100 
00102 
00103 enum CMD_SET
00104 {
00105   SET_ACTIVATION = 0x00,
00106   SET_CONTROL = 0x01,
00107   SET_BROADCAST = 0x02,
00108   SET_MISSION = 0x03,
00109   SET_SYNC = 0x04,
00110   SET_VIRTUALRC = 0x05
00111 };
00112 
00113 enum SYNC_CODE
00114 {
00115   CODE_SYNC_BROADCAST = 0x00
00116 };
00117 
00118 enum HOTPOINT_CODE
00119 {
00120   CODE_HOTPOINT_START = 0x20,
00121   CODE_HOTPOINT_STOP = 0x21,
00122   CODE_HOTPOINT_SETPAUSE = 0x22,
00123   CODE_HOTPOINT_YAWRATE = 0x23,
00124   CODE_HOTPOINT_RADIUS = 0x24,
00125   CODE_HOTPOINT_SETYAW = 0x25,
00126   CODE_HOTPOINT_LOAD = 0x26
00127 };
00128 
00129 enum FOLLOW_CODE
00130 {
00131   CODE_FOLLOW_START = 0x30,
00132   CODE_FOLLOW_STOP = 0x31,
00133   CODE_FOLLOW_SETPAUSE = 0X32,
00134   CODE_FOLLOW_TARGET = 0X33
00135 };
00136 
00137 enum WAYPOINT_CODE
00138 {
00139   CODE_WAYPOINT_INIT = 0x10,
00140   CODE_WAYPOINT_ADDPOINT = 0x11,
00141   CODE_WAYPOINT_SETSTART = 0x12,
00142   CODE_WAYPOINT_SETPAUSE = 0x13,
00143   CODE_WAYPOINT_DOWNLOAD = 0x14,
00144   CODE_WAYPOINT_INDEX = 0x15,
00145   CODE_WAYPOINT_SETVELOCITY = 0x16,
00146   CODE_WAYPOINT_GETVELOCITY = 0x17,
00147 };
00148 
00149 enum ACTIVATION_CODE
00150 {
00151   CODE_GETVERSION = 0,
00152   CODE_ACTIVATE = 1,
00153   CODE_FREQUENCY = 0x10,
00154   CODE_TOMOBILE = 0xFE
00155 };
00156 
00157 enum CONTROL_CODE
00158 {
00159   CODE_SETCONTROL = 0,
00160   CODE_TASK = 1,
00161   CODE_STATUS = 2,
00162   CODE_CONTROL = 3,
00163   CODE_SETARM = 5,
00164 };
00165 
00166 enum BROADCAST_CODE
00167 {
00168   CODE_BROADCAST = 0x00,
00169   CODE_LOSTCTRL = 0x01,
00170   CODE_FROMMOBILE = 0x02,
00171   CODE_MISSION = 0x03,
00172   CODE_WAYPOINT = 0x04
00173 };
00174 
00175 enum VIRTUALRC_CODE
00176 {
00177   CODE_VIRTUALRC_SETTINGS,
00178   CODE_VIRTUALRC_DATA
00179 };
00180 
00181 enum MISSION_TYPE
00182 {
00183   MISSION_MODE_A,
00184   MISSION_WAYPOINT,
00185   MISSION_HOTPOINT,
00186   MISSION_FOLLOW,
00187   MISSION_IOC
00188 };
00189 
00190 enum BROADCAST_FREQ
00191 {
00192   BROADCAST_FREQ_0HZ = 0,
00193   BROADCAST_FREQ_1HZ = 1,
00194   BROADCAST_FREQ_10HZ = 2,
00195   BROADCAST_FREQ_50HZ = 3,
00196   BROADCAST_FREQ_100HZ = 4,
00197   BROADCAST_FREQ_HOLD = 5,
00198 };
00199 
00201 
00212 class CoreAPI
00213 {
00214   public:
00215   CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false,
00216         CallBack userRecvCallback = 0, UserData userData = 0);
00217   CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback,
00218         bool userCallbackThread = false);
00219   void sendPoll(void);
00220   void readPoll(void);
00222   void callbackPoll(CoreAPI *api);
00223 
00225   void byteHandler(const uint8_t in_data);
00227   void byteStreamHandler(uint8_t *buffer, size_t size);
00228 
00229   void ack(req_id_t req_id, unsigned char *ackdata, int len);
00230 
00232   void allocateACK(Header *protocolHeader);
00233   void notifyCaller(Header *protocolHeader);
00234   void notifyNonBlockingCaller(Header *protocolHeader);
00235 
00237 
00246   void send(unsigned char session_mode, unsigned char is_enc, CMD_SET cmd_set,
00247       unsigned char cmd_id, void *pdata, int len, CallBack ack_callback,
00249       int timeout = 0, int retry_time = 1);
00250   void send(unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id,
00251       void *pdata, size_t len, int timeout = 0, int retry_time = 1,
00252       CallBack ack_handler = 0,
00254       UserData userData = 0);
00255 
00257   void send(Command *parameter);
00259 
00261 
00269   void activate(ActivateData *data, CallBack callback = 0, UserData userData = 0);
00270 
00272 
00287   unsigned short activate(ActivateData *data, int timeout);
00288 
00289   void setControl(bool enable, CallBack callback = 0, UserData userData = 0);
00290 
00292 
00304   unsigned short setControl(bool enable, int timeout);
00305 
00307 
00311   void setActivation(bool isActivated);
00312 
00314 
00317   ActivateData getAccountData() const;
00318 
00320   void setAccountData(const ActivateData &value);
00321 
00322   void sendToMobile(uint8_t *data, uint8_t len, CallBack callback = 0, UserData userData = 0);
00323 
00343   void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback = 0, UserData userData = 0);
00344   unsigned short setBroadcastFreq(uint8_t *dataLenIs16, int timeout);
00345 
00349   void setBroadcastFreqDefaults();
00350 
00363   unsigned short setBroadcastFreqDefaults(int timeout);
00364    
00365   /*
00366    * Set all broadcast frequencies to zero. Only ACK data will stay on the line.
00367    */
00368   void setBroadcastFreqToZero();
00369 
00373   void setACKFrameStatus(uint32_t usageFlag);
00374   uint32_t getACKFrameStatus();
00375   void setBroadcastFrameStatus(bool isFrame);
00376   bool getBroadcastFrameStatus();
00377 
00378   void setSyncFreq(uint32_t freqInHz);
00379   void setKey(const char *key);
00380 
00382 
00388   void getDroneVersion(CallBack callback = 0, UserData userData = 0);
00389 
00403   VersionData getDroneVersion(int timeout);
00404 
00406   BroadcastData getBroadcastData() const;
00407 
00408   bool nonBlockingCBThreadEnable;
00409 
00417   TimeStampData getTime() const;
00418 
00422   FlightStatus getFlightStatus() const;
00423   CtrlInfoData getCtrlInfo() const;
00424 
00433   BatteryData getBatteryCapacity() const;
00435 
00436 
00440   HardDriver *getDriver() const;
00441 
00442   SimpleACK getSimpleACK() const;
00446   Version getSDKVersion() const;
00447   void setBroadcastCallback(CallBackHandler callback) { broadcastCallback = callback; }
00448   void setFromMobileCallback(CallBackHandler FromMobileEntrance);
00449 
00450   void setBroadcastCallback(CallBack handler, UserData userData = 0);
00451   void setFromMobileCallback(CallBack handler, UserData userData = 0);
00452 
00453   void setMisssionCallback(CallBackHandler callback) { missionCallback = callback; }
00454   void setHotPointCallback(CallBackHandler callback) { hotPointCallback = callback; }
00455   void setWayPointCallback(CallBackHandler callback) { wayPointCallback = callback; }
00456   void setFollowCallback(CallBackHandler callback) { followCallback = callback; }
00457   void setWayPointEventCallback(CallBackHandler callback);
00458 
00459   void setMisssionCallback(CallBack handler, UserData userData = 0);
00460   void setHotPointCallback(CallBack handler, UserData userData = 0);
00461   void setWayPointCallback(CallBack handler, UserData userData = 0);
00462   void setFollowCallback(CallBack handler, UserData userData = 0);
00463   void setWayPointEventCallback(CallBack handler, UserData userData = 0);
00464 
00465 
00466   static void activateCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
00467   static void getDroneVersionCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
00468   static void setControlCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
00469   static void sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
00470   static void setFrequencyCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
00471 
00479   void parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
00480   
00484   void setObtainControlMobileCallback(CallBackHandler callback) {obtainControlMobileCallback = callback;}
00485   void setReleaseControlMobileCallback(CallBackHandler callback) {releaseControlMobileCallback = callback;}
00486   void setActivateMobileCallback(CallBackHandler callback) {activateMobileCallback = callback;}
00487   void setArmMobileCallback(CallBackHandler callback) {armMobileCallback = callback;}
00488   void setDisArmMobileCallback(CallBackHandler callback) {disArmMobileCallback = callback;}
00489   void setTakeOffMobileCallback(CallBackHandler callback) {takeOffMobileCallback = callback;}
00490   void setLandingMobileCallback(CallBackHandler callback) {landingMobileCallback = callback;}
00491   void setGoHomeMobileCallback(CallBackHandler callback) {goHomeMobileCallback = callback;}
00492   void setTakePhotoMobileCallback(CallBackHandler callback) {takePhotoMobileCallback = callback;}
00493   void setStartVideoMobileCallback(CallBackHandler callback) {startVideoMobileCallback = callback;}
00494   void setStopVideoMobileCallback(CallBackHandler callback) {stopVideoMobileCallback = callback;}
00495 
00499   bool decodeACKStatus(unsigned short ack);
00500 
00504   bool decodeMissionStatus(uint8_t ack);
00505 
00509   bool stopCond;
00510 
00515   uint32_t ack_data;
00516   HotPointReadACK hotpointReadACK;
00517   WayPointInitACK waypointInitACK;
00518   MissionACKUnion missionACKUnion;
00519 
00521 
00524   SDKFilter getFilter() const;
00525 
00527   bool getHotPointData() const;
00528 
00530   bool getWayPointData() const;
00531 
00532   // FollowMe mission Control
00533   bool getFollowData() const;
00534 
00536   void setHotPointData(bool value);
00537 
00539   void setWayPointData(bool value);
00540 
00542   void setFollowData(bool value);
00543 
00547   void setDriver(HardDriver *value);
00548 
00552   void setVersion(const Version &value);
00553 
00560   bool getObtainControlMobileCMD() {return obtainControlMobileCMD;}
00561   bool getReleaseControlMobileCMD() {return releaseControlMobileCMD;}
00562   bool getActivateMobileCMD() {return activateMobileCMD;}
00563   bool getArmMobileCMD() {return armMobileCMD;}
00564   bool getDisArmMobileCMD() {return disArmMobileCMD;}
00565   bool getTakeOffMobileCMD() {return takeOffMobileCMD;}
00566   bool getLandingMobileCMD() {return landingMobileCMD;}
00567   bool getGoHomeMobileCMD() {return goHomeMobileCMD;}
00568   bool getTakePhotoMobileCMD() {return takePhotoMobileCMD;}
00569   bool getStartVideoMobileCMD() {return startVideoMobileCMD;}
00570   bool getStopVideoMobileCMD() {return stopVideoMobileCMD;}
00571 
00573   bool getDrawCirMobileCMD() {return drawCirMobileCMD;}
00574   bool getDrawSqrMobileCMD() {return drawSqrMobileCMD;}
00575   bool getAttiCtrlMobileCMD() {return attiCtrlMobileCMD;}
00576   bool getGimbalCtrlMobileCMD() {return gimbalCtrlMobileCMD;}
00577   bool getWayPointTestMobileCMD() {return wayPointTestMobileCMD;}
00578   bool getLocalNavTestMobileCMD() {return localNavTestMobileCMD;}
00579   bool getGlobalNavTestMobileCMD() {return globalNavTestMobileCMD;}
00580   bool getVRCTestMobileCMD() {return VRCTestMobileCMD;}
00581   bool getLocalMissionPlanCMD() {return localMissionPlanCMD;}
00582 
00584   void setObtainControlMobileCMD(bool userInput) {obtainControlMobileCMD = userInput;}
00585   void setReleaseControlMobileCMD(bool userInput) {releaseControlMobileCMD= userInput;}
00586   void setActivateMobileCMD(bool userInput) {activateMobileCMD= userInput;}
00587   void setArmMobileCMD(bool userInput) {armMobileCMD= userInput;}
00588   void setDisArmMobileCMD(bool userInput) {disArmMobileCMD= userInput;}
00589   void setTakeOffMobileCMD(bool userInput) {takeOffMobileCMD= userInput;}
00590   void setLandingMobileCMD(bool userInput) {landingMobileCMD= userInput;}
00591   void setGoHomeMobileCMD(bool userInput) {goHomeMobileCMD= userInput;}
00592   void setTakePhotoMobileCMD(bool userInput) {takePhotoMobileCMD= userInput;}
00593   void setStartVideoMobileCMD(bool userInput) {startVideoMobileCMD= userInput;}
00594   void setStopVideoMobileCMD(bool userInput) {stopVideoMobileCMD= userInput;}
00595 
00597   void setDrawCirMobileCMD(bool userInput) {drawCirMobileCMD = userInput;}
00598   void setDrawSqrMobileCMD(bool userInput) {drawSqrMobileCMD = userInput;}
00599   void setAttiCtrlMobileCMD(bool userInput) {attiCtrlMobileCMD = userInput;}
00600   void setGimbalCtrlMobileCMD(bool userInput) {gimbalCtrlMobileCMD = userInput;}
00601   void setWayPointTestMobileCMD(bool userInput) {wayPointTestMobileCMD = userInput;}
00602   void setLocalNavTestMobileCMD(bool userInput) {localNavTestMobileCMD = userInput;}
00603   void setGlobalNavTestMobileCMD(bool userInput) {globalNavTestMobileCMD = userInput;}
00604   void setVRCTestMobileCMD(bool userInput) {VRCTestMobileCMD = userInput;}
00605   void setLocalMissionPlanCMD(bool userInput) {localMissionPlanCMD = userInput;}
00606 
00607   private:
00608   BroadcastData broadcastData;
00609   uint32_t ackFrameStatus;
00610   bool broadcastFrameStatus;
00611   unsigned char encodeSendData[BUFFER_SIZE];
00612   unsigned char encodeACK[ACK_SIZE];
00613 
00615   CallBackHandler fromMobileCallback;
00616   CallBackHandler broadcastCallback;
00617   CallBackHandler hotPointCallback;
00618   CallBackHandler wayPointCallback;
00619   CallBackHandler wayPointEventCallback;
00620   CallBackHandler followCallback;
00621   CallBackHandler missionCallback;
00622   CallBackHandler recvCallback;
00623 
00624   CallBackHandler obtainControlMobileCallback;
00625   CallBackHandler releaseControlMobileCallback;
00626   CallBackHandler activateMobileCallback;
00627   CallBackHandler armMobileCallback;
00628   CallBackHandler disArmMobileCallback;
00629   CallBackHandler takeOffMobileCallback;
00630   CallBackHandler landingMobileCallback;
00631   CallBackHandler goHomeMobileCallback;
00632   CallBackHandler takePhotoMobileCallback;
00633   CallBackHandler startVideoMobileCallback;
00634   CallBackHandler stopVideoMobileCallback;
00635 
00637 
00638   bool obtainControlMobileCMD;
00639   bool releaseControlMobileCMD;
00640   bool activateMobileCMD;
00641   bool armMobileCMD;
00642   bool disArmMobileCMD;
00643   bool takeOffMobileCMD;
00644   bool landingMobileCMD;
00645   bool goHomeMobileCMD;
00646   bool takePhotoMobileCMD;
00647   bool startVideoMobileCMD;
00648   bool stopVideoMobileCMD;
00649 
00650   bool drawCirMobileCMD;
00651   bool drawSqrMobileCMD;
00652   bool attiCtrlMobileCMD;
00653   bool gimbalCtrlMobileCMD;
00654   bool wayPointTestMobileCMD;
00655   bool localNavTestMobileCMD;
00656   bool globalNavTestMobileCMD;
00657   bool VRCTestMobileCMD;
00658   bool localMissionPlanCMD;
00659 
00660   VersionData versionData;
00661   ActivateData accountData;
00662 
00663   unsigned short seq_num;
00664 
00665   SDKFilter filter;
00666 
00668   void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread,
00669       Version SDKVersion);
00670   void recvReqData(Header *protocolHeader);
00671   void appHandler(Header *protocolHeader);
00672   void broadcast(Header *protocolHeader);
00673 
00674   int sendInterface(Command *parameter);
00675   int ackInterface(Ack *parameter);
00676   void sendData(unsigned char *buf);
00677   void setup(void);
00678   void setupMMU(void);
00679   void setupSession(void);
00680 
00681   MMU_Tab *allocMemory(unsigned short size);
00682 
00683   void freeSession(CMDSession *session);
00684   CMDSession *allocSession(unsigned short session_id, unsigned short size);
00685 
00686   void freeACK(ACKSession *session);
00687   ACKSession *allocACK(unsigned short session_id, unsigned short size);
00688   MMU_Tab MMU[MMU_TABLE_NUM];
00689   CMDSession CMDSessionTab[SESSION_TABLE_NUM];
00690   ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
00691   unsigned char memory[MEMORY_SIZE];
00692   unsigned short encrypt(unsigned char *pdest, const unsigned char *psrc,
00693       unsigned short w_len, unsigned char is_ack, unsigned char is_enc,
00694       unsigned char session_id, unsigned short seq_num);
00695 
00696   void streamHandler(SDKFilter *p_filter, unsigned char in_data);
00697   void checkStream(SDKFilter *p_filter);
00698   void verifyHead(SDKFilter *p_filter);
00699   void verifyData(SDKFilter *p_filter);
00700   void callApp(SDKFilter *p_filter);
00701   void storeData(SDKFilter *p_filter, unsigned char in_data);
00702 public:
00703   HardDriver *serialDevice;
00704 private:
00705   bool callbackThread;
00706   bool hotPointData;
00707   bool wayPointData;
00708   bool followData;
00709 
00710 #ifdef API_BUFFER_DATA
00711   public:
00712   void setTotalRead(const size_t &value) { totalRead = value; }
00713   void setOnceRead(const size_t &value) { onceRead = value; }
00714 
00715   size_t getTotalRead() const { return totalRead; }
00716   size_t getOnceRead() const { return onceRead; }
00717 
00718   private:
00719   size_t onceRead;
00720   size_t totalRead;
00721 #endif // API_BUFFER_DATA
00722 };
00723 
00724 } // namespace onboardSDK
00725 } // namespace DJI
00726 
00727 #endif // DJI_API_H


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