45 ACK_COMMON_SUCCESS = 0x0000,
46 ACK_COMMON_KEYERROR = 0xFF00,
47 ACK_COMMON_NO_AUTHORIZATION = 0xFF01,
48 ACK_COMMON_NO_RIGHTS = 0xFF02,
49 ACK_COMMON_NO_RESPONSE = 0xFFFF
54 ACK_ACTIVE_SUCCESS = 0x0000,
55 ACK_ACTIVE_PARAMETER_ERROR = 0x0001,
56 ACK_ACTIVE_ENCODE_ERROR = 0x0002,
57 ACK_ACTIVE_NEW_DEVICE = 0x0003,
58 ACK_ACTIVE_APP_NOT_CONNECTED = 0x0004,
59 ACK_ACTIVE_NO_INTERNET = 0x0005,
60 ACK_ACTIVE_SERVER_REFUSED = 0x0006,
61 ACK_ACTIVE_ACCESS_LEVEL_ERROR = 0x0007,
62 ACK_ACTIVE_VERSION_ERROR = 0x0008
65 enum ACK_SETCONTROL_CODE
67 ACK_SETCONTROL_NEED_MODE_F = 0x0000,
68 ACK_SETCONTROL_RELEASE_SUCCESS = 0x0001,
69 ACK_SETCONTROL_OBTAIN_SUCCESS = 0x0002,
70 ACK_SETCONTROL_OBTAIN_RUNNING = 0x0003,
71 ACK_SETCONTROL_RELEASE_RUNNING = 0x0004,
72 ACK_SETCONTROL_IOC = 0x00C9,
78 ACK_ARM_SUCCESS = 0x0000,
79 ACK_ARM_NEED_CONTROL = 0x0001,
80 ACK_ARM_ALREADY_ARMED = 0x0002,
81 ACK_ARM_IN_AIR = 0x0003,
88 SET_ACTIVATION = 0x00,
98 CODE_SYNC_BROADCAST = 0x00
103 CODE_HOTPOINT_START = 0x20,
104 CODE_HOTPOINT_STOP = 0x21,
105 CODE_HOTPOINT_SETPAUSE = 0x22,
106 CODE_HOTPOINT_YAWRATE = 0x23,
107 CODE_HOTPOINT_RADIUS = 0x24,
108 CODE_HOTPOINT_SETYAW = 0x25,
109 CODE_HOTPOINT_LOAD = 0x26
114 CODE_FOLLOW_START = 0x30,
115 CODE_FOLLOW_STOP = 0x31,
116 CODE_FOLLOW_SETPAUSE = 0X32,
117 CODE_FOLLOW_TARGET = 0X33
122 CODE_WAYPOINT_INIT = 0x10,
123 CODE_WAYPOINT_ADDPOINT = 0x11,
124 CODE_WAYPOINT_SETSTART = 0x12,
125 CODE_WAYPOINT_SETPAUSE = 0x13,
126 CODE_WAYPOINT_DOWNLOAD = 0x14,
127 CODE_WAYPOINT_INDEX = 0x15,
128 CODE_WAYPOINT_SETVELOCITY = 0x16,
129 CODE_WAYPOINT_GETVELOCITY = 0x17,
136 CODE_FREQUENCY = 0x10,
151 CODE_BROADCAST = 0x00,
152 CODE_LOSTCTRL = 0x01,
153 CODE_FROMMOBILE = 0x02,
160 CODE_VIRTUALRC_SETTINGS,
175 BROADCAST_FREQ_0HZ = 0,
176 BROADCAST_FREQ_1HZ = 1,
177 BROADCAST_FREQ_10HZ = 2,
178 BROADCAST_FREQ_50HZ = 3,
179 BROADCAST_FREQ_100HZ = 4,
180 BROADCAST_FREQ_HOLD = 5,
210 CallBack userRecvCallback = 0, UserData userData = 0);
212 bool userCallbackThread =
false);
214 void ack(
req_id_t req_id,
unsigned char *ackdata,
int len);
226 void send(
unsigned char session_mode,
unsigned char is_enc,
CMD_SET cmd_set,
227 unsigned char cmd_id,
void *pdata,
int len, CallBack ack_callback,
229 int timeout = 0,
int retry_time = 1);
230 void send(
unsigned char session_mode,
bool is_enc,
CMD_SET cmd_set,
unsigned char cmd_id,
231 void *pdata,
size_t len,
int timeout = 0,
int retry_time = 1,
232 CallBack ack_handler = 0,
234 UserData userData = 0);
250 void setControl(
bool enable, CallBack callback = 0, UserData userData = 0);
268 void sendToMobile(uint8_t *data, uint8_t len, CallBack callback = 0, UserData userData = 0);
289 void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback = 0, UserData userData = 0);
290 void setSessionStatus(uint32_t usageFlag);
291 uint32_t getSessionStatus();
292 void setSyncFreq(uint32_t freqInHz);
293 void setKey(
const char *key);
344 void setBroadcastCallback(
CallBackHandler callback) { broadcastCallback = callback; }
347 void setBroadcastCallback(CallBack handler, UserData userData = 0);
348 void setFromMobileCallback(CallBack handler, UserData userData = 0);
350 void setMisssionCallback(
CallBackHandler callback) { missionCallback = callback; }
351 void setHotPointCallback(
CallBackHandler callback) { hotPointCallback = callback; }
352 void setWayPointCallback(
CallBackHandler callback) { wayPointCallback = callback; }
353 void setFollowCallback(
CallBackHandler callback) { followCallback = callback; }
356 void setMisssionCallback(CallBack handler, UserData userData = 0);
357 void setHotPointCallback(CallBack handler, UserData userData = 0);
358 void setWayPointCallback(CallBack handler, UserData userData = 0);
359 void setFollowCallback(CallBack handler, UserData userData = 0);
360 void setWayPointEventCallback(CallBack handler, UserData userData = 0);
363 static void activateCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
364 static void getDroneVersionCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
365 static void setControlCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
366 static void sendToMobileCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
367 static void setFrequencyCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
371 uint32_t sessionStatus;
374 unsigned char encodeSendData[BUFFER_SIZE];
375 unsigned char encodeACK[ACK_SIZE];
391 unsigned short seq_num;
400 void recvReqData(
Header *protocolHeader);
401 void appHandler(
Header *protocolHeader);
402 void broadcast(
Header *protocolHeader);
404 int sendInterface(
Command *parameter);
405 int ackInterface(
Ack *parameter);
406 void sendData(
unsigned char *buf);
411 void setupSession(
void);
413 MMU_Tab *allocMemory(
unsigned short size);
416 CMDSession *allocSession(
unsigned short session_id,
unsigned short size);
419 ACKSession *allocACK(
unsigned short session_id,
unsigned short size);
424 ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
425 unsigned char memory[MEMORY_SIZE];
428 unsigned short encrypt(
unsigned char *pdest,
const unsigned char *psrc,
429 unsigned short w_len,
unsigned char is_ack,
unsigned char is_enc,
430 unsigned char session_id,
unsigned short seq_num);
432 void streamHandler(
SDKFilter *p_filter,
unsigned char in_data);
437 void storeData(
SDKFilter *p_filter,
unsigned char in_data);
465 bool getFollowData()
const;
493 #ifdef API_BUFFER_DATA 495 void setTotalRead(
const size_t &value) { totalRead = value; }
496 void setOnceRead(
const size_t &value) { onceRead = value; }
498 size_t getTotalRead()
const {
return totalRead; }
499 size_t getOnceRead()
const {
return onceRead; }
504 #endif // API_BUFFER_DATA TimeStampData getTime() const
Definition: DJI_API.cpp:219
void send(unsigned char session_mode, unsigned char is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, int len, CallBack ack_callback, int timeout=0, int retry_time=1)
Definition: DJI_API.cpp:87
BroadcastData getBroadcastData() const
Definition: DJI_App.cpp:46
void getDroneVersion(CallBack callback=0, UserData userData=0)
Definition: DJI_API.cpp:154
HardDriver * getDriver() const
Definition: DJI_API.cpp:245
void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)
Definition: DJI_API.cpp:193
void setWayPointData(bool value)
WayPoint Mission Control.
Definition: DJI_API.cpp:232
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
Definition: DJI_Type.h:345
Definition: DJI_HardDriver.h:31
Definition: DJI_Type.h:178
ACK_COMMON_CODE
Definition: DJI_API.h:43
ActivateData getAccountData() const
Activation Control.
Definition: DJI_API.cpp:228
Definition: DJI_Type.h:192
void setHotPointData(bool value)
HotPoint Mission Control.
Definition: DJI_API.cpp:231
bool getHotPointData() const
HotPoint Mission Control.
Definition: DJI_API.cpp:234
Definition: DJI_Type.h:170
uint32_t Version
Definition: DJI_Version.h:34
CMD_SET
Definition: DJI_API.h:86
Version getFwVersion() const
Definition: DJI_API.cpp:377
Definition: DJI_Type.h:158
void activate(ActivateData *data, CallBack callback=0, UserData userData=0)
Activation Control.
Definition: DJI_API.cpp:168
void setFollowData(bool value)
Follow Me Mission Control.
Definition: DJI_API.cpp:233
void byteHandler(const uint8_t in_data)
Definition: DJI_Codec.cpp:761
void sendPoll(void)
Definition: DJI_Link.cpp:131
Definition: DJI_Type.h:200
BatteryData getBatteryCapacity() const
Definition: DJI_App.cpp:48
Definition: DJI_Type.h:145
void byteStreamHandler(uint8_t *buffer, size_t size)
Definition: DJI_Codec.cpp:806
bool decodeACKStatus(unsigned short ack)
Definition: DJI_Codec.cpp:607
void callbackPoll(void)
Definition: DJI_Link.cpp:194
Definition: DJI_Type.h:139
FlightStatus getFlightStatus() const
Definition: DJI_API.cpp:221
bool decodeMissionStatus(uint8_t ack)
Definition: DJI_Mission.cpp:89
void setVersion(const Version &value)
Definition: DJI_API.cpp:381
void setDriver(HardDriver *value)
Definition: DJI_API.cpp:247
Definition: DJI_Mission.cpp:16
bool getWayPointData() const
WayPoint Mission Control.
Definition: DJI_API.cpp:235
Definition: DJI_Type.h:412
void setActivation(bool isActivated)
Activation Control.
Definition: DJI_Link.cpp:208
Definition: DJI_Type.h:335
void setAccountData(const ActivateData &value)
Activation Control.
Definition: DJI_API.cpp:230
SDKFilter getFilter() const
Open Protocol Control.
Definition: DJI_API.cpp:379