diff --git a/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h b/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h index 4cd776ea..44b30653 100644 --- a/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h +++ b/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h @@ -141,7 +141,6 @@ class ROSAdapter { void activate(ActivateData *data, CallBack callback) { - coreAPI->setVersion(data->version); coreAPI->activate(data, callback); } diff --git a/dji_sdk/launch/sdk_manifold.launch b/dji_sdk/launch/sdk_manifold.launch index 7b3c95d4..ebb51445 100644 --- a/dji_sdk/launch/sdk_manifold.launch +++ b/dji_sdk/launch/sdk_manifold.launch @@ -1,13 +1,11 @@ - - - + diff --git a/dji_sdk/launch/sdk_osx.launch b/dji_sdk/launch/sdk_osx.launch index 4d9eb597..912bec1a 100644 --- a/dji_sdk/launch/sdk_osx.launch +++ b/dji_sdk/launch/sdk_osx.launch @@ -1,7 +1,6 @@ - diff --git a/dji_sdk/package.xml b/dji_sdk/package.xml index d338085a..71680128 100644 --- a/dji_sdk/package.xml +++ b/dji_sdk/package.xml @@ -1,14 +1,14 @@ dji_sdk - 0.1.9 + 3.2.0 A ROS package using DJI Onboard SDK. Norman Li - Botao Hu + Arjun Menon @@ -20,13 +20,13 @@ - + http://developer.dji.com/onboard-sdk/documentation/github-platform-docs/ROS/README.html - Botao Hu + Arjun Menon diff --git a/dji_sdk/src/modules/dji_sdk_node_main.cpp b/dji_sdk/src/modules/dji_sdk_node_main.cpp index 84b1465c..027cb67c 100644 --- a/dji_sdk/src/modules/dji_sdk_node_main.cpp +++ b/dji_sdk/src/modules/dji_sdk_node_main.cpp @@ -29,7 +29,7 @@ void DJISDKNode::broadcast_callback() { DJI::onboardSDK::BroadcastData bc_data = rosAdapter->coreAPI->getBroadcastData(); - DJI::onboardSDK::Version version = rosAdapter->coreAPI->getSDKVersion(); + DJI::onboardSDK::Version version = rosAdapter->coreAPI->getFwVersion(); unsigned short msg_flags = bc_data.dataFlag; static int frame_id = 0; @@ -143,10 +143,10 @@ void DJISDKNode::broadcast_callback() } /****************************************************************** -****************************If using A3**************************** +****************************If using A3/N3/M600******************** ******************************************************************/ - if(version == DJI::onboardSDK::versionA3_31 || version == DJI::onboardSDK::versionA3_32) { + if(version > MAKE_VERSION(3,1,10,0)) { //update gimbal msg if (msg_flags & A3_HAS_GIMBAL) { @@ -321,7 +321,6 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private) std::string serial_name; int baud_rate; int app_id; - int app_version; std::string app_bundle_id; //reserved std::string enc_key; int uart_or_usb; @@ -330,7 +329,6 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private) nh_private.param("serial_name", serial_name, std::string("/dev/ttyTHS1")); nh_private.param("baud_rate", baud_rate, 230400); nh_private.param("app_id", app_id, 1022384); - nh_private.param("app_version", app_version, 1); nh_private.param("enc_key", enc_key, std::string("e7bad64696529559318bb35d0a8c6050d3b88e791e1808cfe8f7802150ee6f0d")); @@ -339,32 +337,12 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private) // activation user_act_data.ID = app_id; - - if((uart_or_usb)&&(drone_version.compare("M100"))) - { - printf("M100 does not support USB API.\n"); - return -1; - } - - if(!drone_version.compare("M100")) - { - user_act_data.version = versionM100_31; - } - else if (!drone_version.compare("A3_31")) - { - user_act_data.version = versionA3_31; - } - else if (!drone_version.compare("A3_32")) - { - user_act_data.version = versionA3_32; - } user_act_data.encKey = app_key; strcpy(user_act_data.encKey, enc_key.c_str()); printf("=================================================\n"); - printf("app id: %d\n", user_act_data.ID); - printf("app version: 0x0%X\n", user_act_data.version); - printf("app key: %s\n", user_act_data.encKey); + printf("app id : %d\n", user_act_data.ID); + printf("app key : %s\n", user_act_data.encKey); printf("=================================================\n"); if(uart_or_usb) //use usb port for SDK @@ -373,6 +351,14 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private) } rosAdapter->init(serial_name, baud_rate); + rosAdapter->coreAPI->getDroneVersion(); + //usleep(1000000); + ros::Duration(1.0).sleep(); + printf("=================================================\n"); + printf("Hardware : %s\n", rosAdapter->coreAPI->getHwVersion()); + printf("Firmware : 0x0%X\n", rosAdapter->coreAPI->getFwVersion()); + printf("=================================================\n"); + rosAdapter->activate(&user_act_data, NULL); rosAdapter->setBroadcastCallback(&DJISDKNode::broadcast_callback, this); rosAdapter->setFromMobileCallback(&DJISDKNode::transparent_transmission_callback,this); diff --git a/dji_sdk/src/modules/dji_sdk_node_services.cpp b/dji_sdk/src/modules/dji_sdk_node_services.cpp index 9c3e8779..9ca35d89 100644 --- a/dji_sdk/src/modules/dji_sdk_node_services.cpp +++ b/dji_sdk/src/modules/dji_sdk_node_services.cpp @@ -218,7 +218,7 @@ bool DJISDKNode::velocity_control_callback(dji_sdk::VelocityControl::Request& re bool DJISDKNode::version_check_callback(dji_sdk::VersionCheck::Request& request, dji_sdk::VersionCheck::Response& response) { int sdkVer; - sdkVer = rosAdapter->coreAPI->getSDKVersion(); + sdkVer = rosAdapter->coreAPI->getFwVersion(); std::cout << std::hex << sdkVer << '\n'; response.result = true; return true; diff --git a/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html index ef04f305..e22bfa10 100644 --- a/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html @@ -90,7 +90,7 @@
DJI_API.h
-Go to the documentation of this file.
1 
24 #ifndef DJI_API_H
25 #define DJI_API_H
26 #include "DJI_Type.h"
27 //#include "DJI_Mission.h"
28 
29 #include "DJI_HardDriver.h"
30 #include "DJI_App.h"
31 namespace DJI
32 {
33 namespace onboardSDK
34 {
35 class CoreAPI;
36 class Flight;
37 class Camera;
38 class VirtualRC;
39 class HotPoint;
40 
42 
44 {
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
50 };
51 
52 enum ACK_ACTIVE_CODE
53 {
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
63 };
64 
65 enum ACK_SETCONTROL_CODE
66 {
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,
73 
74 };
75 
76 enum ACK_ARM_CODE
77 {
78  ACK_ARM_SUCCESS = 0x0000,
79  ACK_ARM_NEED_CONTROL = 0x0001,
80  ACK_ARM_ALREADY_ARMED = 0x0002,
81  ACK_ARM_IN_AIR = 0x0003,
82 };
83 
85 
86 enum CMD_SET
87 {
88  SET_ACTIVATION = 0x00,
89  SET_CONTROL = 0x01,
90  SET_BROADCAST = 0x02,
91  SET_MISSION = 0x03,
92  SET_SYNC = 0x04,
93  SET_VIRTUALRC = 0x05
94 };
95 
96 enum SYNC_CODE
97 {
98  CODE_SYNC_BROADCAST = 0x00
99 };
100 
101 enum HOTPOINT_CODE
102 {
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
110 };
111 
112 enum FOLLOW_CODE
113 {
114  CODE_FOLLOW_START = 0x30,
115  CODE_FOLLOW_STOP = 0x31,
116  CODE_FOLLOW_SETPAUSE = 0X32,
117  CODE_FOLLOW_TARGET = 0X33
118 };
119 
120 enum WAYPOINT_CODE
121 {
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,
130 };
131 
132 enum ACTIVATION_CODE
133 {
134  CODE_GETVERSION = 0,
135  CODE_ACTIVATE = 1,
136  CODE_FREQUENCY = 0x10,
137  CODE_TOMOBILE = 0xFE
138 };
139 
140 enum CONTROL_CODE
141 {
142  CODE_SETCONTROL = 0,
143  CODE_TASK = 1,
144  CODE_STATUS = 2,
145  CODE_CONTROL = 3,
146  CODE_SETARM = 5,
147 };
148 
149 enum BROADCAST_CODE
150 {
151  CODE_BROADCAST = 0x00,
152  CODE_LOSTCTRL = 0x01,
153  CODE_FROMMOBILE = 0x02,
154  CODE_MISSION = 0x03,
155  CODE_WAYPOINT = 0x04
156 };
157 
158 enum VIRTUALRC_CODE
159 {
160  CODE_VIRTUALRC_SETTINGS,
161  CODE_VIRTUALRC_DATA
162 };
163 
164 enum MISSION_TYPE
165 {
166  MISSION_MODE_A,
167  MISSION_WAYPOINT,
168  MISSION_HOTPOINT,
169  MISSION_FOLLOW,
170  MISSION_IOC
171 };
172 
173 enum BROADCAST_FREQ
174 {
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,
181 };
182 
184 
195 class CoreAPI
196 {
197  public:
198  void sendPoll(void);
199  void readPoll(void);
201  void callbackPoll(void);
202 
204  void byteHandler(const uint8_t in_data);
206  void byteStreamHandler(uint8_t *buffer, size_t size);
207 
208  public:
209  CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false,
210  CallBack userRecvCallback = 0, UserData userData = 0);
211  CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback,
212  bool userCallbackThread = false);
213 
214  void ack(req_id_t req_id, unsigned char *ackdata, int len);
215 
217 
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);
235 
237  void send(Command *parameter);
239 
241 
249  void activate(ActivateData *data, CallBack callback = 0, UserData userData = 0);
250  void setControl(bool enable, CallBack callback = 0, UserData userData = 0);
251 
253 
257  void setActivation(bool isActivated);
258 
260 
264 
266  void setAccountData(const ActivateData &value);
267 
268  void sendToMobile(uint8_t *data, uint8_t len, CallBack callback = 0, UserData userData = 0);
269 
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);
294 
296 
302  void getDroneVersion(CallBack callback = 0, UserData userData = 0);
303 
306 
314  TimeStampData getTime() const;
315 
319  FlightStatus getFlightStatus() const;
320  CtrlInfoData getCtrlInfo() const;
321 
330  BatteryData getBatteryCapacity() const;
332 
333 
337  HardDriver *getDriver() const;
338 
342  Version getSDKVersion() const;
343  public:
344  void setBroadcastCallback(CallBackHandler callback) { broadcastCallback = callback; }
345  void setFromMobileCallback(CallBackHandler FromMobileEntrance);
346 
347  void setBroadcastCallback(CallBack handler, UserData userData = 0);
348  void setFromMobileCallback(CallBack handler, UserData userData = 0);
349 
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; }
354  void setWayPointEventCallback(CallBackHandler callback);
355 
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);
361 
362 
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);
368 
369  private:
370  BroadcastData broadcastData;
371  uint32_t sessionStatus;
372 
373  private:
374  unsigned char encodeSendData[BUFFER_SIZE];
375  unsigned char encodeACK[ACK_SIZE];
376 
377 // uint8_t cblistTail;
378 // CallBackHandler cbList[CALLBACK_LIST_NUM];
379  CallBackHandler fromMobileCallback;
380  CallBackHandler broadcastCallback;
381  CallBackHandler hotPointCallback;
382  CallBackHandler wayPointCallback;
383  CallBackHandler wayPointEventCallback;
384  CallBackHandler followCallback;
385  CallBackHandler missionCallback;
386  CallBackHandler recvCallback;
387 
388  VersionData versionData;
389  ActivateData accountData;
390 
391  unsigned short seq_num;
392 
393  SDKFilter filter;
394 
395  private:
396 
398  void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread,
399  Version SDKVersion);
400  void recvReqData(Header *protocolHeader);
401  void appHandler(Header *protocolHeader);
402  void broadcast(Header *protocolHeader);
403 
404  int sendInterface(Command *parameter);
405  int ackInterface(Ack *parameter);
406  void sendData(unsigned char *buf);
407 
408  private:
409  void setup(void);
410  void setupMMU(void);
411  void setupSession(void);
412 
413  MMU_Tab *allocMemory(unsigned short size);
414 
415  void freeSession(CMDSession *session);
416  CMDSession *allocSession(unsigned short session_id, unsigned short size);
417 
418  void freeACK(ACKSession *session);
419  ACKSession *allocACK(unsigned short session_id, unsigned short size);
420 
421  private:
422  MMU_Tab MMU[MMU_TABLE_NUM];
423  CMDSession CMDSessionTab[SESSION_TABLE_NUM];
424  ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
425  unsigned char memory[MEMORY_SIZE];
426 
427  private:
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);
431 
432  void streamHandler(SDKFilter *p_filter, unsigned char in_data);
433  void checkStream(SDKFilter *p_filter);
434  void verifyHead(SDKFilter *p_filter);
435  void verifyData(SDKFilter *p_filter);
436  void callApp(SDKFilter *p_filter);
437  void storeData(SDKFilter *p_filter, unsigned char in_data);
438 
439  public:
443  bool decodeACKStatus(unsigned short ack);
444 
448  bool decodeMissionStatus(uint8_t ack);
449 
450  public:
451 
453 
456  SDKFilter getFilter() const;
457 
459  bool getHotPointData() const;
460 
462  bool getWayPointData() const;
463 
464  // FollowMe mission Control
465  bool getFollowData() const;
466 
468  void setHotPointData(bool value);
469 
471  void setWayPointData(bool value);
472 
474  void setFollowData(bool value);
475 
479  void setDriver(HardDriver *value);
480 
484  void setVersion(const Version &value);
485 
486  private:
487  HardDriver *serialDevice;
488  bool callbackThread;
489  bool hotPointData;
490  bool wayPointData;
491  bool followData;
492 
493 #ifdef API_BUFFER_DATA
494  public:
495  void setTotalRead(const size_t &value) { totalRead = value; }
496  void setOnceRead(const size_t &value) { onceRead = value; }
497 
498  size_t getTotalRead() const { return totalRead; }
499  size_t getOnceRead() const { return onceRead; }
500 
501  private:
502  size_t onceRead;
503  size_t totalRead;
504 #endif // API_BUFFER_DATA
505 };
506 
507 } // namespace onboardSDK
508 } // namespace DJI
509 
510 #endif // DJI_API_H
TimeStampData getTime() const
Definition: DJI_API.cpp:219
+Go to the documentation of this file.
1 
24 #ifndef DJI_API_H
25 #define DJI_API_H
26 #include "DJI_Type.h"
27 //#include "DJI_Mission.h"
28 
29 #include "DJI_HardDriver.h"
30 #include "DJI_App.h"
31 namespace DJI
32 {
33 namespace onboardSDK
34 {
35 class CoreAPI;
36 class Flight;
37 class Camera;
38 class VirtualRC;
39 class HotPoint;
40 
42 
44 {
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
50 };
51 
52 enum ACK_ACTIVE_CODE
53 {
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
63 };
64 
65 enum ACK_SETCONTROL_CODE
66 {
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,
73 
74 };
75 
76 enum ACK_ARM_CODE
77 {
78  ACK_ARM_SUCCESS = 0x0000,
79  ACK_ARM_NEED_CONTROL = 0x0001,
80  ACK_ARM_ALREADY_ARMED = 0x0002,
81  ACK_ARM_IN_AIR = 0x0003,
82 };
83 
85 
86 enum CMD_SET
87 {
88  SET_ACTIVATION = 0x00,
89  SET_CONTROL = 0x01,
90  SET_BROADCAST = 0x02,
91  SET_MISSION = 0x03,
92  SET_SYNC = 0x04,
93  SET_VIRTUALRC = 0x05
94 };
95 
96 enum SYNC_CODE
97 {
98  CODE_SYNC_BROADCAST = 0x00
99 };
100 
101 enum HOTPOINT_CODE
102 {
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
110 };
111 
112 enum FOLLOW_CODE
113 {
114  CODE_FOLLOW_START = 0x30,
115  CODE_FOLLOW_STOP = 0x31,
116  CODE_FOLLOW_SETPAUSE = 0X32,
117  CODE_FOLLOW_TARGET = 0X33
118 };
119 
120 enum WAYPOINT_CODE
121 {
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,
130 };
131 
132 enum ACTIVATION_CODE
133 {
134  CODE_GETVERSION = 0,
135  CODE_ACTIVATE = 1,
136  CODE_FREQUENCY = 0x10,
137  CODE_TOMOBILE = 0xFE
138 };
139 
140 enum CONTROL_CODE
141 {
142  CODE_SETCONTROL = 0,
143  CODE_TASK = 1,
144  CODE_STATUS = 2,
145  CODE_CONTROL = 3,
146  CODE_SETARM = 5,
147 };
148 
149 enum BROADCAST_CODE
150 {
151  CODE_BROADCAST = 0x00,
152  CODE_LOSTCTRL = 0x01,
153  CODE_FROMMOBILE = 0x02,
154  CODE_MISSION = 0x03,
155  CODE_WAYPOINT = 0x04
156 };
157 
158 enum VIRTUALRC_CODE
159 {
160  CODE_VIRTUALRC_SETTINGS,
161  CODE_VIRTUALRC_DATA
162 };
163 
164 enum MISSION_TYPE
165 {
166  MISSION_MODE_A,
167  MISSION_WAYPOINT,
168  MISSION_HOTPOINT,
169  MISSION_FOLLOW,
170  MISSION_IOC
171 };
172 
173 enum BROADCAST_FREQ
174 {
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,
181 };
182 
184 
195 class CoreAPI
196 {
197  public:
198  void sendPoll(void);
199  void readPoll(void);
201  void callbackPoll(void);
202 
204  void byteHandler(const uint8_t in_data);
206  void byteStreamHandler(uint8_t *buffer, size_t size);
207 
208  public:
209  CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false,
210  CallBack userRecvCallback = 0, UserData userData = 0);
211  CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback,
212  bool userCallbackThread = false);
213 
214  void ack(req_id_t req_id, unsigned char *ackdata, int len);
215 
217 
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);
235 
237  void send(Command *parameter);
239 
241 
249  void activate(ActivateData *data, CallBack callback = 0, UserData userData = 0);
250  void setControl(bool enable, CallBack callback = 0, UserData userData = 0);
251 
253 
257  void setActivation(bool isActivated);
258 
260 
264 
266  void setAccountData(const ActivateData &value);
267 
268  void sendToMobile(uint8_t *data, uint8_t len, CallBack callback = 0, UserData userData = 0);
269 
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);
294 
296 
302  void getDroneVersion(CallBack callback = 0, UserData userData = 0);
303 
306 
314  TimeStampData getTime() const;
315 
319  FlightStatus getFlightStatus() const;
320  CtrlInfoData getCtrlInfo() const;
321 
330  BatteryData getBatteryCapacity() const;
332 
333 
337  HardDriver *getDriver() const;
338 
342  Version getFwVersion() const;
343  public:
344  void setBroadcastCallback(CallBackHandler callback) { broadcastCallback = callback; }
345  void setFromMobileCallback(CallBackHandler FromMobileEntrance);
346 
347  void setBroadcastCallback(CallBack handler, UserData userData = 0);
348  void setFromMobileCallback(CallBack handler, UserData userData = 0);
349 
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; }
354  void setWayPointEventCallback(CallBackHandler callback);
355 
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);
361 
362 
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);
368 
369  private:
370  BroadcastData broadcastData;
371  uint32_t sessionStatus;
372 
373  private:
374  unsigned char encodeSendData[BUFFER_SIZE];
375  unsigned char encodeACK[ACK_SIZE];
376 
377 // uint8_t cblistTail;
378 // CallBackHandler cbList[CALLBACK_LIST_NUM];
379  CallBackHandler fromMobileCallback;
380  CallBackHandler broadcastCallback;
381  CallBackHandler hotPointCallback;
382  CallBackHandler wayPointCallback;
383  CallBackHandler wayPointEventCallback;
384  CallBackHandler followCallback;
385  CallBackHandler missionCallback;
386  CallBackHandler recvCallback;
387 
388  VersionData versionData;
389  ActivateData accountData;
390 
391  unsigned short seq_num;
392 
393  SDKFilter filter;
394 
395  private:
396 
398  void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread,
399  Version SDKVersion);
400  void recvReqData(Header *protocolHeader);
401  void appHandler(Header *protocolHeader);
402  void broadcast(Header *protocolHeader);
403 
404  int sendInterface(Command *parameter);
405  int ackInterface(Ack *parameter);
406  void sendData(unsigned char *buf);
407 
408  private:
409  void setup(void);
410  void setupMMU(void);
411  void setupSession(void);
412 
413  MMU_Tab *allocMemory(unsigned short size);
414 
415  void freeSession(CMDSession *session);
416  CMDSession *allocSession(unsigned short session_id, unsigned short size);
417 
418  void freeACK(ACKSession *session);
419  ACKSession *allocACK(unsigned short session_id, unsigned short size);
420 
421  private:
422  MMU_Tab MMU[MMU_TABLE_NUM];
423  CMDSession CMDSessionTab[SESSION_TABLE_NUM];
424  ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
425  unsigned char memory[MEMORY_SIZE];
426 
427  private:
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);
431 
432  void streamHandler(SDKFilter *p_filter, unsigned char in_data);
433  void checkStream(SDKFilter *p_filter);
434  void verifyHead(SDKFilter *p_filter);
435  void verifyData(SDKFilter *p_filter);
436  void callApp(SDKFilter *p_filter);
437  void storeData(SDKFilter *p_filter, unsigned char in_data);
438 
439  public:
443  bool decodeACKStatus(unsigned short ack);
444 
448  bool decodeMissionStatus(uint8_t ack);
449 
450  public:
451 
453 
456  SDKFilter getFilter() const;
457 
459  bool getHotPointData() const;
460 
462  bool getWayPointData() const;
463 
464  // FollowMe mission Control
465  bool getFollowData() const;
466 
468  void setHotPointData(bool value);
469 
471  void setWayPointData(bool value);
472 
474  void setFollowData(bool value);
475 
479  void setDriver(HardDriver *value);
480 
484  void setVersion(const Version &value);
485 
486  private:
487  HardDriver *serialDevice;
488  bool callbackThread;
489  bool hotPointData;
490  bool wayPointData;
491  bool followData;
492 
493 #ifdef API_BUFFER_DATA
494  public:
495  void setTotalRead(const size_t &value) { totalRead = value; }
496  void setOnceRead(const size_t &value) { onceRead = value; }
497 
498  size_t getTotalRead() const { return totalRead; }
499  size_t getOnceRead() const { return onceRead; }
500 
501  private:
502  size_t onceRead;
503  size_t totalRead;
504 #endif // API_BUFFER_DATA
505 };
506 
507 } // namespace onboardSDK
508 } // namespace DJI
509 
510 #endif // DJI_API_H
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
@@ -112,7 +112,7 @@
Definition: DJI_Type.h:170
uint32_t Version
Definition: DJI_Version.h:34
CMD_SET
Definition: DJI_API.h:86
-
Version getSDKVersion() const
Definition: DJI_API.cpp:377
+
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
diff --git a/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html index 7c488d82..15ced10a 100644 --- a/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html @@ -90,7 +90,7 @@
DJI_App.h
-Go to the documentation of this file.
1 
13 #ifndef DJI_APP_H
14 #define DJI_APP_H
15 
16 #include <stdint.h>
17 
18 #include "DJI_Link.h"
19 #include "DJI_Type.h"
20 
21 #define MSG_ENABLE_FLAG_LEN 2
22 
23 //----------------------------------------------------------------------
24 // App layer function
25 //----------------------------------------------------------------------
26 typedef struct
27 {
28  unsigned short sequence_number;
29  unsigned char session_id : 5;
30  unsigned char need_encrypt : 1;
31  unsigned char reserve : 2;
32 } req_id_t;
33 
34 #define EXC_DATA_SIZE (16u)
35 #define SET_CMD_SIZE (2u)
36 
37 //----------------------------------------------------------------------
38 // for cmd agency
39 //----------------------------------------------------------------------
40 #define REQ_TIME_OUT 0x0000
41 #define REQ_REFUSE 0x0001
42 #define CMD_RECIEVE 0x0002
43 #define STATUS_CMD_EXECUTING 0x0003
44 #define STATUS_CMD_EXE_FAIL 0x0004
45 #define STATUS_CMD_EXE_SUCCESS 0x0005
46 
48 #pragma pack(1)
49 
50 typedef struct ActivateData
51 {
52  unsigned int ID;
53  unsigned int reserved;
54  unsigned int version;
55  unsigned char iosID[32];
56  char *encKey;
57 } ActivateData;
58 
59 typedef struct VersionData
60 {
61  unsigned short version_ack;
62  unsigned int version_crc;
63  char version_ID[11];
64  char version_name[32];
66 } VersionData;
67 
68 #pragma pack()
69 
70 #endif // DJI_APP_H
Definition: DJI_App.h:50
+Go to the documentation of this file.
1 
13 #ifndef DJI_APP_H
14 #define DJI_APP_H
15 
16 #include <stdint.h>
17 
18 #include "DJI_Link.h"
19 #include "DJI_Type.h"
20 
21 #define MSG_ENABLE_FLAG_LEN 2
22 
23 //----------------------------------------------------------------------
24 // App layer function
25 //----------------------------------------------------------------------
26 typedef struct
27 {
28  unsigned short sequence_number;
29  unsigned char session_id : 5;
30  unsigned char need_encrypt : 1;
31  unsigned char reserve : 2;
32 } req_id_t;
33 
34 #define EXC_DATA_SIZE (16u)
35 #define SET_CMD_SIZE (2u)
36 
37 //----------------------------------------------------------------------
38 // for cmd agency
39 //----------------------------------------------------------------------
40 #define REQ_TIME_OUT 0x0000
41 #define REQ_REFUSE 0x0001
42 #define CMD_RECIEVE 0x0002
43 #define STATUS_CMD_EXECUTING 0x0003
44 #define STATUS_CMD_EXE_FAIL 0x0004
45 #define STATUS_CMD_EXE_SUCCESS 0x0005
46 
48 #pragma pack(1)
49 
50 typedef struct ActivateData
51 {
52  unsigned int ID;
53  unsigned int reserved;
54  unsigned int version;
55  unsigned char iosID[32];
56  char *encKey;
57 } ActivateData;
58 
59 typedef struct VersionData
60 {
61  unsigned short version_ack;
62  unsigned int version_crc;
63  char hw_serial_num[11];
64  char version_name[32];
66 } VersionData;
67 
68 #pragma pack()
69 
70 #endif // DJI_APP_H
Definition: DJI_App.h:50
Definition: DJI_App.h:26
uint32_t Version
Definition: DJI_Version.h:34
diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI-members.html index 0a0758fb..492e6dfa 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI-members.html @@ -115,7 +115,7 @@ getFlightStatus() const DJI::onboardSDK::CoreAPI getFollowData() const (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI getHotPointData() const DJI::onboardSDK::CoreAPI - getSDKVersion() const DJI::onboardSDK::CoreAPI + getFwVersion() const DJI::onboardSDK::CoreAPI getSessionStatus() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI getTime() const DJI::onboardSDK::CoreAPI getWayPointData() const DJI::onboardSDK::CoreAPI diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI.html index 9e0c68d7..57569779 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1CoreAPI.html @@ -158,7 +158,7 @@   HardDrivergetDriver () const   -Version getSDKVersion () const +Version getFwVersion () const   void setBroadcastCallback (CallBackHandler callback) @@ -571,7 +571,7 @@
- + diff --git a/dji_sdk_doc/doxygen/html/functions.html b/dji_sdk_doc/doxygen/html/functions.html index d8fcb06a..0ad55397 100644 --- a/dji_sdk_doc/doxygen/html/functions.html +++ b/dji_sdk_doc/doxygen/html/functions.html @@ -222,7 +222,7 @@

- g -

  • getRCData() : DJI::onboardSDK::VirtualRC
  • -
  • getSDKVersion() +
  • getFwVersion() : DJI::onboardSDK::CoreAPI
  • getTime() diff --git a/dji_sdk_doc/doxygen/html/functions_func.html b/dji_sdk_doc/doxygen/html/functions_func.html index e67a0fe8..cf287b68 100644 --- a/dji_sdk_doc/doxygen/html/functions_func.html +++ b/dji_sdk_doc/doxygen/html/functions_func.html @@ -196,7 +196,7 @@

    - g -

    • getRCData() : DJI::onboardSDK::VirtualRC
    • -
    • getSDKVersion() +
    • getFwVersion() : DJI::onboardSDK::CoreAPI
    • getTime() diff --git a/dji_sdk_doc/doxygen/html/structVersionData-members.html b/dji_sdk_doc/doxygen/html/structVersionData-members.html index 1c250576..05d2a124 100644 --- a/dji_sdk_doc/doxygen/html/structVersionData-members.html +++ b/dji_sdk_doc/doxygen/html/structVersionData-members.html @@ -93,7 +93,7 @@
- +
Version CoreAPI::getSDKVersion Version CoreAPI::getFwVersion ( ) const
version (defined in VersionData)VersionData
version_ack (defined in VersionData)VersionData
version_crc (defined in VersionData)VersionData
version_ID (defined in VersionData)VersionData
hw_serial_num (defined in VersionData)VersionData
version_name (defined in VersionData)VersionData
diff --git a/dji_sdk_doc/doxygen/html/structVersionData.html b/dji_sdk_doc/doxygen/html/structVersionData.html index 5b20e70a..b47bfd7a 100644 --- a/dji_sdk_doc/doxygen/html/structVersionData.html +++ b/dji_sdk_doc/doxygen/html/structVersionData.html @@ -100,7 +100,7 @@ unsigned int version_crc   -char version_ID [11] +char hw_serial_num [11]   char version_name [32] diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h index df6b34c0..062bf142 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h @@ -140,8 +140,8 @@ enum WAYPOINT_CODE CODE_WAYPOINT_ADDPOINT = 0x11, CODE_WAYPOINT_SETSTART = 0x12, CODE_WAYPOINT_SETPAUSE = 0x13, - CODE_WAYPOINT_DOWNLOAD = 0x14, - CODE_WAYPOINT_INDEX = 0x15, + CODE_WAYPOINT_INFO_READ = 0x14, + CODE_WAYPOINT_INDEX_READ = 0x15, CODE_WAYPOINT_SETVELOCITY = 0x16, CODE_WAYPOINT_GETVELOCITY = 0x17, }; @@ -212,10 +212,13 @@ enum BROADCAST_FREQ class CoreAPI { public: - CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false, - CallBack userRecvCallback = 0, UserData userData = 0); - CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback, - bool userCallbackThread = false); + CoreAPI(HardDriver *Driver = 0, + bool userCallbackThread = false, + CallBack userRecvCallback = 0, + UserData userData = 0); + CoreAPI(HardDriver *Driver, + CallBackHandler userRecvCallback, + bool userCallbackThread = false); void sendPoll(void); void readPoll(void); //! @todo Implement callback poll handler @@ -362,7 +365,7 @@ class CoreAPI */ unsigned short setBroadcastFreqDefaults(int timeout); - /* + /** * Set all broadcast frequencies to zero. Only ACK data will stay on the line. */ void setBroadcastFreqToZero(); @@ -402,6 +405,18 @@ class CoreAPI */ VersionData getDroneVersion(int timeout); + /** + * Get SDK version + */ + Version getFwVersion() const; + char * getHwVersion() const; + char * getHwSerialNum() const; + + /** + * Parse SDK version returned from drone, and populate the API versionData member + */ + bool parseDroneVersionInfo(unsigned char *ackPtr); + /**Get broadcasted data values from flight controller.*/ BroadcastData getBroadcastData() const; @@ -440,10 +455,7 @@ class CoreAPI HardDriver *getDriver() const; SimpleACK getSimpleACK() const; - /** - * Get SDK version - */ - Version getSDKVersion() const; + void setBroadcastCallback(CallBackHandler callback) { broadcastCallback = callback; } void setFromMobileCallback(CallBackHandler FromMobileEntrance); @@ -497,6 +509,7 @@ class CoreAPI * ACK decoder. */ bool decodeACKStatus(unsigned short ack); + void setBroadcastActivation(uint32_t ack); /** * Flight mission decoder. @@ -517,6 +530,12 @@ class CoreAPI WayPointInitACK waypointInitACK; MissionACKUnion missionACKUnion; + /** + *@note Activation status to override BroadcastData activation flag + * + */ + uint32_t ack_activation; + /// Open Protocol Control /** * Get Open Protocol packet information. @@ -546,11 +565,6 @@ class CoreAPI */ void setDriver(HardDriver *value); - /** - * Set SDK version. - */ - void setVersion(const Version &value); - /** * Setters and getters for Mobile CMD variables - these are used * when interacting with a Data Transparent Transmission App @@ -578,7 +592,15 @@ class CoreAPI bool getLocalNavTestMobileCMD() {return localNavTestMobileCMD;} bool getGlobalNavTestMobileCMD() {return globalNavTestMobileCMD;} bool getVRCTestMobileCMD() {return VRCTestMobileCMD;} - bool getLocalMissionPlanCMD() {return localMissionPlanCMD;} + + + /** Advanced features: LiDAR Mapping, Collision Avoidance, Precision Missions */ + bool getStartLASMapLoggingCMD() {return startLASMapLoggingCMD;} + bool getStopLASMapLoggingCMD() {return stopLASMapLoggingCMD;} + bool getPrecisionMissionsCMD() {return precisionMissionCMD;} + bool getPrecisionMissionsCollisionAvoidanceCMD() {return precisionMissionsCollisionAvoidanceCMD;} + bool getPrecisionMissionsLidarMappingCMD() {return precisionMissionsLidarMappingCMD;} + bool getPrecisionMissionsCollisionAvoidanceLidarMappingCMD() {return precisionMissionsCollisionAvoidanceLidarMappingCMD;} /** Core functions - setters */ void setObtainControlMobileCMD(bool userInput) {obtainControlMobileCMD = userInput;} @@ -593,6 +615,15 @@ class CoreAPI void setStartVideoMobileCMD(bool userInput) {startVideoMobileCMD= userInput;} void setStopVideoMobileCMD(bool userInput) {stopVideoMobileCMD= userInput;} + /** Advanced features: LiDAR Mapping, Collision Avoidance, Precision Missions */ + void setStartLASMapLoggingCMD(bool userInput) {startLASMapLoggingCMD = userInput;} + void setStopLASMapLoggingCMD(bool userInput) {stopLASMapLoggingCMD = userInput;} + void setPrecisionMissionsCMD(bool userInput) {precisionMissionCMD = userInput;} + void setPrecisionMissionsCollisionAvoidanceCMD(bool userInput) {precisionMissionsCollisionAvoidanceCMD = userInput;} + void setPrecisionMissionsLidarMappingCMD(bool userInput) {precisionMissionsLidarMappingCMD = userInput;} + void setPrecisionMissionsCollisionAvoidanceLidarMappingCMD(bool userInput) {precisionMissionsCollisionAvoidanceLidarMappingCMD = userInput;} + + /** Custom missions - setters */ void setDrawCirMobileCMD(bool userInput) {drawCirMobileCMD = userInput;} void setDrawSqrMobileCMD(bool userInput) {drawSqrMobileCMD = userInput;} @@ -602,7 +633,8 @@ class CoreAPI void setLocalNavTestMobileCMD(bool userInput) {localNavTestMobileCMD = userInput;} void setGlobalNavTestMobileCMD(bool userInput) {globalNavTestMobileCMD = userInput;} void setVRCTestMobileCMD(bool userInput) {VRCTestMobileCMD = userInput;} - void setLocalMissionPlanCMD(bool userInput) {localMissionPlanCMD = userInput;} + + private: BroadcastData broadcastData; @@ -635,6 +667,7 @@ class CoreAPI //! Mobile Data Transparent Transmission - flags + //! Core functions bool obtainControlMobileCMD; bool releaseControlMobileCMD; bool activateMobileCMD; @@ -647,6 +680,7 @@ class CoreAPI bool startVideoMobileCMD; bool stopVideoMobileCMD; + //! Custom Mission examples bool drawCirMobileCMD; bool drawSqrMobileCMD; bool attiCtrlMobileCMD; @@ -655,8 +689,18 @@ class CoreAPI bool localNavTestMobileCMD; bool globalNavTestMobileCMD; bool VRCTestMobileCMD; - bool localMissionPlanCMD; + + //! Advanced features: LiDAR Mapping, Collision Avoidance, Precision Missions + bool startLASMapLoggingCMD; + bool stopLASMapLoggingCMD; + //! Various flavors of precision missions + bool precisionMissionCMD; + bool precisionMissionsCollisionAvoidanceCMD; + bool precisionMissionsLidarMappingCMD; + bool precisionMissionsCollisionAvoidanceLidarMappingCMD; + + //! Versioning and activation VersionData versionData; ActivateData accountData; @@ -665,8 +709,7 @@ class CoreAPI SDKFilter filter; /// Serial Device Initialization - void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread, - Version SDKVersion); + void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread); void recvReqData(Header *protocolHeader); void appHandler(Header *protocolHeader); void broadcast(Header *protocolHeader); diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h index 12916fe2..e23eee57 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h @@ -82,6 +82,7 @@ class Flight enum Status { + STATUS_MOTOR_OFF = 0, STATUS_GROUND_STANDBY = 1, STATUS_TAKE_OFF = 2, STATUS_SKY_STANDBY = 3, diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h index cf0bcc59..f4ae236e 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h @@ -25,6 +25,7 @@ class HardDriver { public: HardDriver() {} + virtual ~HardDriver() {} /*! @note How to use * In order to provide platform crossable DJI onboardSDK library, diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h index 842a6878..cbfb9a66 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h @@ -15,6 +15,7 @@ #include "DJI_API.h" #include "DJI_Type.h" +#ifdef API_TRACE_DATA namespace DJI { namespace onboardSDK { @@ -43,5 +44,5 @@ typedef struct __ActivationGetProtocolVersionAck { void printFrame(HardDriver *hardDriver, Header *header, bool toAircraft); } } - +#endif // API_TRACE_DATA #endif // ONBOARDSDK_DJI_LOGGING_H diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h index 1ab0bf98..b59f5213 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h @@ -127,9 +127,7 @@ const size_t CALLBACK_LIST_NUM = 10; /** * @note size is in Bytes */ -const size_t MAX_ACK_SIZE = 64; -const size_t M100_MAX_ACK_SIZE = 64; -const size_t A3_MAX_ACK_SIZE = 63; +const size_t MAX_ACK_SIZE = 107; //! The CoreAPI class definition is detailed in DJI_API.h class CoreAPI; @@ -334,10 +332,17 @@ typedef struct HotPointStartACK float32_t maxRadius; } HotpointStartACK; +typedef struct WayPointInitACK +{ + uint8_t ack; + WayPointInitData data; +} WayPointInitACK; + typedef struct WayPointDataACK { uint8_t ack; uint8_t index; + WayPointData data; } WayPointDataACK; typedef struct WayPointVelocityACK @@ -353,16 +358,10 @@ typedef struct HotPointReadACK HotPointData data; } HotpointReadACK; -typedef struct WayPointInitACK -{ - uint8_t ack; - WayPointInitData data; -} WayPointInitACK; - typedef struct DroneVersionACK { unsigned char ack[MAX_ACK_SIZE]; -}; +} DroneVersionACK; typedef union MissionACKUnion { @@ -382,7 +381,10 @@ typedef union MissionACKUnion // information read from flight controller WayPointInitACK waypointInitACK; + // Contains 1-Byte ACK plus waypoint mission + // information read from flight controller WayPointDataACK waypointDataACK; + WayPointVelocityACK waypointVelocityACK; } MissionACKUnion; @@ -588,8 +590,7 @@ typedef struct BroadcastData BatteryData battery; CtrlInfoData ctrlInfo; - //! @note these variables are not sent from FC, - //! just a record for user. + //! @note this variable is not set by the FC but populated by the API uint8_t activation; } BroadcastData; #endif // SDK_DEV @@ -633,15 +634,23 @@ typedef struct ActivateData char *encKey; } ActivateData; +/** + * Versioning. VersionData struct updated @ FW 3.2.15.73 + */ + typedef struct VersionData { unsigned short version_ack; unsigned int version_crc; - char version_ID[11]; + char hw_serial_num[16]; + char hwVersion[12]; //! Current longest product code: pm820v3pro + DJI::onboardSDK::Version fwVersion; + + //! Legacy member char version_name[32]; - DJI::onboardSDK::Version version; } VersionData; + #pragma pack() #ifdef SDK_DEV #include "devtype.h" diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h index 77e324cf..8d30f61f 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h @@ -38,29 +38,37 @@ class WayPoint //! @note true for pause, false for resume void pause(bool isPause, CallBack callback = 0, UserData userData = 0); MissionACK pause(bool isPause, int timer); - void readInitData(CallBack callback = 0, UserData userData = 0);//! @todo implement - void readIndexData(uint8_t index, CallBack callback = 0, UserData userData = 0); //! @todo implement void readIdleVelocity(CallBack callback = 0, UserData userData = 0); //! @todo uploadAll - //void uploadAll(CallBack callback = 0, UserData userData = 0); + void uploadAll(CallBack callback = 0, UserData userData = 0); bool uploadIndexData(WayPointData *data, CallBack callback = 0, UserData userData = 0); WayPointDataACK uploadIndexData(WayPointData *data, int timer); + + /* + * Read information about WayPoint mission from flight controller + */ + WayPointInitACK getWaypointSettings(int timeout); + // Callback example + void getWaypointSettings(CallBack callback, UserData userData); + + /* + * @note Get Waypoint status/settings at a given index + */ + WayPointDataACK getIndex(uint8_t index, int timeout); + // Callback example + void getIndex(uint8_t index, CallBack callback, UserData userData); + bool uploadIndexData(uint8_t pos, CallBack callback = 0, UserData userData = 0); void updateIdleVelocity(float32_t meterPreSecond, CallBack callback = 0, UserData userData = 0); void setInfo(const WayPointInitData &value); - void setIndex(WayPointData *value, size_t pos); WayPointInitData getInfo() const; - WayPointData *getIndex() const; - WayPointData *getIndex(size_t pos) const; - - public: + void setIndex(WayPointData *value, size_t pos); static void idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi); - static void readInitDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi); + static void getWaypointSettingsCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi); static void uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi); //! @todo add uploadAllCallback - //! @todo add readIndexCallback private: CoreAPI *api; diff --git a/dji_sdk_lib/src/DJI_API.cpp b/dji_sdk_lib/src/DJI_API.cpp old mode 100644 new mode 100755 index b841ef76..cf9520f8 --- a/dji_sdk_lib/src/DJI_API.cpp +++ b/dji_sdk_lib/src/DJI_API.cpp @@ -11,7 +11,6 @@ #include "DJI_API.h" #include -#include using namespace DJI; using namespace DJI::onboardSDK; @@ -22,17 +21,18 @@ uint8_t DJI::onboardSDK::encrypt = 1; uint8_t DJI::onboardSDK::encrypt = 0; #endif // USE_ENCRYPT -CoreAPI::CoreAPI(HardDriver *sDevice, Version SDKVersion, bool userCallbackThread, - CallBack userRecvCallback, UserData userData) +CoreAPI::CoreAPI(HardDriver *sDevice, + bool userCallbackThread, + CallBack userRecvCallback, + UserData userData) { CallBackHandler handler; handler.callback = userRecvCallback; handler.userData = userData; - init(sDevice, handler, userCallbackThread, SDKVersion); + init(sDevice, handler, userCallbackThread); } -void CoreAPI::init(HardDriver *sDevice, CallBackHandler userRecvCallback, - bool userCallbackThread, Version SDKVersion) +void CoreAPI::init(HardDriver *sDevice, CallBackHandler userRecvCallback, bool userCallbackThread) { serialDevice = sDevice; // serialDevice->init(); @@ -72,19 +72,26 @@ void CoreAPI::init(HardDriver *sDevice, CallBackHandler userRecvCallback, nonBlockingCBThreadEnable = false; ack_data = 99; - versionData.version = SDKVersion; + versionData.fwVersion = 0; //! Default init value + ack_activation = 0xFF; + //! @todo simplify code above + serialDevice->lockMSG(); memset((unsigned char *)&broadcastData, 0, sizeof(broadcastData)); + serialDevice->freeMSG(); setup(); + + } -CoreAPI::CoreAPI(HardDriver *sDevice, Version SDKVersion, CallBackHandler userRecvCallback, - bool userCallbackThread) +CoreAPI::CoreAPI(HardDriver *sDevice, + CallBackHandler userRecvCallback, + bool userCallbackThread) { - init(sDevice, userRecvCallback, userCallbackThread, SDKVersion); - getSDKVersion(); + init(sDevice, userRecvCallback, userCallbackThread); + getFwVersion(); } void CoreAPI::send(unsigned char session, unsigned char is_enc, CMD_SET cmdSet, @@ -172,6 +179,7 @@ VersionData CoreAPI::getDroneVersion(int timeout) { versionData.version_ack = ACK_COMMON_NO_RESPONSE; versionData.version_crc = 0x0; + versionData.fwVersion = 0; versionData.version_name[0] = 0; unsigned cmd_timeout = 100; // unit is ms @@ -181,59 +189,225 @@ VersionData CoreAPI::getDroneVersion(int timeout) send(2, 0, SET_ACTIVATION, CODE_GETVERSION, (unsigned char *)&cmd_data, 1, cmd_timeout, retry_time, 0, 0); - // Wait for end of ACK frame to arrive + //! Wait for end of ACK frame to arrive serialDevice->lockACK(); serialDevice->wait(timeout); serialDevice->freeACK(); - // Parse return value + //! Pointer to ACK unsigned char *ptemp = &(missionACKUnion.droneVersion.ack[0]); - if(versionData.version != versionA3_32){ - versionData.version_ack = ptemp[0] + (ptemp[1] << 8); - ptemp += 2; - versionData.version_crc = ptemp[0] + (ptemp[1] << 8) + (ptemp[2] << 16) + (ptemp[3] << 24); - ptemp += 4; - if (versionData.version != versionM100_23) - { - memcpy(versionData.version_ID, ptemp, 11); - ptemp += 11; - } - memcpy(versionData.version_name, ptemp, 32); - }else{ - versionData.version_ack = missionACKUnion.missionACK; - memcpy(versionData.version_name, "versionA3_32", strlen("versionA3_32")+1); + //! Parse the HW & SW version, Serial no. and ACK. Discard return value, we don't process it right now. + if(!parseDroneVersionInfo(ptemp)) { + versionData.version_crc = 0x0; + versionData.fwVersion = 0; + versionData.version_name[0] = 0; } return versionData; } +bool CoreAPI::parseDroneVersionInfo(unsigned char *ackPtrIncoming) { + + //! Local copy to prevent overwriting the ACK store + unsigned char buf[64] = {}; + memcpy(buf, ackPtrIncoming, 64); + unsigned char* ackPtr = &buf[0]; + + //! Note down our starting point as a sanity check + unsigned char* startPtr = ackPtr; + //! 2b ACK. + versionData.version_ack = ackPtr[0] + (ackPtr[1] << 8); + ackPtr += 2; + + //! Next, we might have CRC or ID; Put them into a variable that we will parse later. Find next \0 + unsigned char crc_id[16] = {}; + int i = 0; + while(*ackPtr != '\0') { + crc_id[i] = *ackPtr; + i++; + ackPtr++; + if (ackPtr - startPtr > 18) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } + //! Fill in the termination character + crc_id[i] = *ackPtr; + ackPtr++; + + //! Now we're at the name. First, let's fill up the name field. + memcpy(versionData.version_name, ackPtr, 32); + + //! Now, we start parsing the name. Let's find the second space character. + while (*ackPtr != ' ') { + ackPtr++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } //! Found first space ("SDK-v1.x") + ackPtr++; + + while (*ackPtr != ' ') { + ackPtr++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } //! Found second space ("BETA") + ackPtr++; + + //! Next is the HW version + int j = 0; + while (*ackPtr != '-') { + this->versionData.hwVersion[j] = *ackPtr; + ackPtr++; + j++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } + //! Fill in the termination character + this->versionData.hwVersion[j] = '\0'; + ackPtr++; + + //! Finally, we come to the FW version. We don't know if each clause is 2 or 3 digits long. + int ver1 = 0, ver2 = 0, ver3 = 0, ver4 = 0; + + while (*ackPtr != '.') { + ver1 = (*ackPtr - 48) + 10*ver1; + ackPtr++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } + ackPtr++; + while (*ackPtr != '.') { + ver2 = (*ackPtr - 48) + 10*ver2; + ackPtr++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } + ackPtr++; + while (*ackPtr != '.') { + ver3 = (*ackPtr - 48) + 10*ver3; + ackPtr++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } + ackPtr++; + while (*ackPtr != '\0') { + ver4 = (*ackPtr - 48) + 10*ver4; + ackPtr++; + if (ackPtr - startPtr > 64) { + API_LOG(serialDevice, ERROR_LOG, "Drone version was not obtained. Please restart the program or call getDroneVersion\n"); + return false; + } + } + + this->versionData.fwVersion = MAKE_VERSION(ver1, ver2, ver3, ver4); + + //! Special cases + //! M100: + if (strcmp(versionData.hwVersion,"M100") == 0) { + //! Bug in M100 does not report the right FW. + ver3 = 10*ver3; + this->versionData.fwVersion = MAKE_VERSION(ver1, ver2, ver3, ver4); + } + + //! Now, we can parse the CRC and ID based on FW version. If it's older than 3.2 then it'll have a CRC, else not. + if (this->versionData.fwVersion < MAKE_VERSION(3,2,0,0)) { + this->versionData.version_crc = crc_id[0] + (crc_id[1] << 8) + (crc_id[2] << 16) + (crc_id[3] << 24) ; + unsigned char *id_ptr = &crc_id[4]; + + int i = 0; + while (*id_ptr != '\0') { + this->versionData.hw_serial_num[i] = *id_ptr; + i++; + id_ptr++; + if (id_ptr - &crc_id[4] > 12) { + API_LOG(serialDevice, ERROR_LOG, "Drone ID was not obtained."); + return false; //!Not catastrophic error + } + } + //! Fill in the termination character + this->versionData.hw_serial_num[i] = *id_ptr; + } else { + versionData.version_crc = 0; + unsigned char *id_ptr = &crc_id[0]; + + int i = 0; + while (*id_ptr != '\0') { + this->versionData.hw_serial_num[i] = *id_ptr; + i++; + id_ptr++; + if (id_ptr - &crc_id[0] > 16) { + API_LOG(serialDevice, ERROR_LOG, "Drone ID was not obtained."); + return false; //!Not catastrophic error + } + } + //! Fill in the termination character + this->versionData.hw_serial_num[i] = *id_ptr; + } + + //! Finally, we print stuff out. + /* + if (this->versionData.fwVersion > MAKE_VERSION(3,1,0,0)) { + API_LOG(this->serialDevice, STATUS_LOG, "Device Serial No. = %.16s\n", this->versionData.hw_serial_num); + } + API_LOG(this->serialDevice, STATUS_LOG, "Hardware = %.12s\n", + this->versionData.hwVersion); + API_LOG(this->serialDevice, STATUS_LOG, "Firmware = %d.%d.%d.%d\n", + ver1, ver2, ver3, ver4); + if (this->versionData.fwVersion < MAKE_VERSION(3,2,0,0)) { + API_LOG(this->serialDevice, STATUS_LOG, "Version CRC = 0x%X\n", this->versionData.version_crc); + } + */ + return true; +} + + + void CoreAPI::activate(ActivateData *data, CallBack callback, UserData userData) { - data->version = versionData.version; + //! First, we need to check if getDroneVersion has been called + if (versionData.fwVersion == 0) { + API_LOG(serialDevice, ERROR_LOG, "Please call getDroneVersion first.\n"); + return; + } + data->version = versionData.fwVersion; accountData = *data; accountData.reserved = 2; for (int i = 0; i < 32; ++i) accountData.iosID[i] = '0'; //! @note for ios verification - API_LOG(serialDevice, DEBUG_LOG, "version 0x%X/n", versionData.version); + API_LOG(serialDevice, DEBUG_LOG, "version 0x%X\n", versionData.fwVersion); API_LOG(serialDevice, DEBUG_LOG, "%.32s", accountData.iosID); send(2, 0, SET_ACTIVATION, CODE_ACTIVATE, (unsigned char *)&accountData, sizeof(accountData) - sizeof(char *), 1000, 3, callback ? callback : CoreAPI::activateCallback, userData); - ack_data = missionACKUnion.simpleACK; - if(ack_data == ACK_ACTIVE_SUCCESS && accountData.encKey) - setKey(accountData.encKey); } unsigned short CoreAPI::activate(ActivateData *data, int timeout) { - data->version = versionData.version; + //! First, we need to check if getDroneVersion has been called + if (versionData.fwVersion == 0) { + this->getDroneVersion(1); + } + //! Now, look into versionData and set for activation. + data->version = versionData.fwVersion; accountData = *data; accountData.reserved = 2; for (int i = 0; i < 32; ++i) accountData.iosID[i] = '0'; //! @note for ios verification - API_LOG(serialDevice, DEBUG_LOG, "version 0x%X/n", versionData.version); + API_LOG(serialDevice, DEBUG_LOG, "version 0x%X\n", versionData.fwVersion); API_LOG(serialDevice, DEBUG_LOG, "%.32s", accountData.iosID); send(2, 0, SET_ACTIVATION, CODE_ACTIVATE, (unsigned char *)&accountData, sizeof(accountData) - sizeof(char *), 1000, 3, 0, 0); @@ -265,7 +439,7 @@ void CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback, UserData //! @note see also enum BROADCAST_FREQ in DJI_API.h for (int i = 0; i < 16; ++i) { - if (versionData.version == versionM100_31) + if (strcmp(versionData.hwVersion, "M100") == 0) if (i < 12) { dataLenIs16[i] = (dataLenIs16[i] > 5 ? 5 : dataLenIs16[i]); @@ -291,7 +465,7 @@ unsigned short CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, int timeout) //! @note see also enum BROADCAST_FREQ in DJI_API.h for (int i = 0; i < 16; ++i) { - if (versionData.version == versionM100_31) + if (strcmp(versionData.hwVersion, "M100") == 0) if (i < 12) { dataLenIs16[i] = (dataLenIs16[i] > 5 ? 5 : dataLenIs16[i]); @@ -348,13 +522,13 @@ void CoreAPI::setBroadcastFreqDefaults() * 8 - Magnetometer * 9 - RC Channels Data * 10 - Gimbal Data - * 11 - Flight Status + * 11 - Flight Statusack * 12 - Battery Level * 13 - Control Information * */ - if (versionData.version == versionM100_31 || versionData.version == versionM100_23) { + if (strcmp(versionData.hwVersion, "M100") == 0) { freq[0] = BROADCAST_FREQ_1HZ; freq[1] = BROADCAST_FREQ_10HZ; freq[2] = BROADCAST_FREQ_50HZ; @@ -368,7 +542,7 @@ void CoreAPI::setBroadcastFreqDefaults() freq[10] = BROADCAST_FREQ_50HZ; freq[11] = BROADCAST_FREQ_10HZ; } - else if (versionData.version == versionA3_31 || versionData.version == versionA3_32) { + else {//! A3/N3/M600 freq[0] = BROADCAST_FREQ_1HZ; freq[1] = BROADCAST_FREQ_10HZ; freq[2] = BROADCAST_FREQ_50HZ; @@ -436,11 +610,8 @@ void CoreAPI::setBroadcastFreqToZero() freq[9] = BROADCAST_FREQ_0HZ; freq[10] = BROADCAST_FREQ_0HZ; freq[11] = BROADCAST_FREQ_0HZ; - if(versionData.version == versionA3_31 || versionData.version == versionA3_32) - { - freq[12] = BROADCAST_FREQ_0HZ; - freq[13] = BROADCAST_FREQ_0HZ; - } + freq[12] = BROADCAST_FREQ_0HZ; + freq[13] = BROADCAST_FREQ_0HZ; setBroadcastFreq(freq); } @@ -482,7 +653,7 @@ unsigned short CoreAPI::setBroadcastFreqDefaults(int timeout) * */ - if (versionData.version == versionM100_31 || versionData.version == versionM100_23) { + if (strcmp(versionData.hwVersion, "M100") == 0) { freq[0] = BROADCAST_FREQ_1HZ; freq[1] = BROADCAST_FREQ_10HZ; freq[2] = BROADCAST_FREQ_50HZ; @@ -496,7 +667,7 @@ unsigned short CoreAPI::setBroadcastFreqDefaults(int timeout) freq[10] = BROADCAST_FREQ_50HZ; freq[11] = BROADCAST_FREQ_10HZ; } - else if (versionData.version == versionA3_31 || versionData.version == versionA3_32) { + else { //! A3/N3/M600 freq[0] = BROADCAST_FREQ_1HZ; freq[1] = BROADCAST_FREQ_10HZ; freq[2] = BROADCAST_FREQ_50HZ; @@ -516,9 +687,9 @@ unsigned short CoreAPI::setBroadcastFreqDefaults(int timeout) return setBroadcastFreq(freq, timeout); } -TimeStampData CoreAPI::getTime() const { return broadcastData.timeStamp; } +TimeStampData CoreAPI::getTime() const { return getBroadcastData().timeStamp; } -FlightStatus CoreAPI::getFlightStatus() const { return broadcastData.status; } +FlightStatus CoreAPI::getFlightStatus() const { return getBroadcastData().status; } void CoreAPI::setFromMobileCallback(CallBackHandler FromMobileEntrance) { @@ -555,7 +726,7 @@ unsigned short CoreAPI::setControl(bool enable, int timeout) if (missionACKUnion.simpleACK == ACK_SETCONTROL_ERROR_MODE) { - if(versionData.version != versionA3_32) + if(versionData.fwVersion < MAKE_VERSION(3,2,0,0)) missionACKUnion.simpleACK = ACK_SETCONTROL_NEED_MODE_F; else missionACKUnion.simpleACK = ACK_SETCONTROL_NEED_MODE_P; @@ -573,35 +744,11 @@ void CoreAPI::setDriver(HardDriver *sDevice) { serialDevice = sDevice; } void CoreAPI::getDroneVersionCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED) { unsigned char *ptemp = ((unsigned char *)protocolHeader) + sizeof(Header); - size_t ack_length = protocolHeader->length - EXC_DATA_SIZE; - - if(ack_length > 1){ - api->versionData.version_ack = ptemp[0] + (ptemp[1] << 8); - ptemp += 2; - api->versionData.version_crc = - ptemp[0] + (ptemp[1] << 8) + (ptemp[2] << 16) + (ptemp[3] << 24); - ptemp += 4; - if (api->versionData.version != versionM100_23) - { - memcpy(api->versionData.version_ID, ptemp, 11); - ptemp += 11; - } - memcpy(api->versionData.version_name, ptemp, 32); - }else{ - api->versionData.version_ack = ptemp[0]; - memcpy(api->versionData.version_name, "versionA3_32", strlen("versionA3_32")+1); - } - - API_LOG(api->serialDevice, STATUS_LOG, "version ack = %d\n", api->versionData.version_ack); - - if(api->versionData.version != versionA3_32){ - API_LOG(api->serialDevice, STATUS_LOG, "version crc = 0x%X\n", api->versionData.version_crc); - if (api->versionData.version != versionM100_23) - API_LOG(api->serialDevice, STATUS_LOG, "version ID = %.11s\n", api->versionData.version_ID); + if(!api->parseDroneVersionInfo(ptemp)) { + api->versionData.version_crc = 0x0; + api->versionData.fwVersion = 0; + api->versionData.version_name[0] = 0; } - - API_LOG(api->serialDevice, STATUS_LOG, "version name = %.32s\n", - api->versionData.version_name); } void CoreAPI::activateCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED) @@ -612,6 +759,10 @@ void CoreAPI::activateCallback(CoreAPI *api, Header *protocolHeader, UserData us { memcpy((unsigned char *)&ack_data, ((unsigned char *)protocolHeader) + sizeof(Header), (protocolHeader->length - EXC_DATA_SIZE)); + + // Write activation status to the broadcast data + api->setBroadcastActivation(ack_data); + switch (ack_data) { case ACK_ACTIVE_SUCCESS: @@ -646,7 +797,6 @@ void CoreAPI::activateCallback(CoreAPI *api, Header *protocolHeader, UserData us break; case ACK_ACTIVE_VERSION_ERROR: API_LOG(api->serialDevice, ERROR_LOG, "SDK version did not match\n"); - api->getDroneVersion(); break; default: if (!api->decodeACKStatus(ack_data)) @@ -813,6 +963,26 @@ void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, User stopVideoMobileCMD = true; } break; + //! Advanced features: LiDAR Mapping, Collision Avoidance, Precision Missions + case 20: + startLASMapLoggingCMD = true; + break; + case 21: + stopLASMapLoggingCMD = true; + break; + case 24: + precisionMissionCMD = true; + break; + case 25: + precisionMissionsCollisionAvoidanceCMD = true; + break; + case 26: + precisionMissionsLidarMappingCMD = true; + break; + case 27: + precisionMissionsCollisionAvoidanceLidarMappingCMD = true; + break; + //! The next few are only polling based and do not use callbacks. See usage in Linux Sample. case 61: drawCirMobileCMD = true; @@ -839,7 +1009,7 @@ void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, User VRCTestMobileCMD = true; break; case 69: - localMissionPlanCMD = true; + precisionMissionCMD = true; break; } } @@ -872,12 +1042,12 @@ void CoreAPI::setFrequencyCallback(CoreAPI *api __UNUSED, Header *protocolHeader } } -Version CoreAPI::getSDKVersion() const { return versionData.version; } +Version CoreAPI::getFwVersion() const { return versionData.fwVersion; } +char * CoreAPI::getHwVersion() const { return (char *)versionData.hwVersion; } +char * CoreAPI::getHwSerialNum() const { return (char *)versionData.hw_serial_num; } SDKFilter CoreAPI::getFilter() const { return filter; } -void CoreAPI::setVersion(const Version &value) { versionData.version = value; } - void CoreAPI::setControlCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED) { unsigned short ack_data = ACK_COMMON_NO_RESPONSE; @@ -897,13 +1067,13 @@ void CoreAPI::setControlCallback(CoreAPI *api, Header *protocolHeader, UserData switch (ack_data) { case ACK_SETCONTROL_ERROR_MODE: - if(api->versionData.version != versionA3_32) + if(api->versionData.fwVersion < MAKE_VERSION(3,2,0,0)) { API_LOG(api->serialDevice, STATUS_LOG, "Obtain control failed: switch to F mode\n"); } else { - API_LOG(api->serialDevice, STATUS_LOG, "Obtain control failed: switch to P mode\n"); + API_LOG(api->serialDevice, STATUS_LOG, "Obtain control failed: switch to P mode\n"); } break; case ACK_SETCONTROL_RELEASE_SUCCESS: diff --git a/dji_sdk_lib/src/DJI_App.cpp b/dji_sdk_lib/src/DJI_App.cpp index b3dd2285..d10dcdc8 100644 --- a/dji_sdk_lib/src/DJI_App.cpp +++ b/dji_sdk_lib/src/DJI_App.cpp @@ -42,14 +42,16 @@ unsigned char getCmdCode(Header *protocolHeader) return *ptemp; } -BroadcastData DJI::onboardSDK::CoreAPI::getBroadcastData() const { return broadcastData; } - -BatteryData DJI::onboardSDK::CoreAPI::getBatteryCapacity() const -{ - return broadcastData.battery; +BroadcastData DJI::onboardSDK::CoreAPI::getBroadcastData() const { + serialDevice->lockMSG(); + BroadcastData data = broadcastData; + serialDevice->freeMSG(); + return data; } -CtrlInfoData DJI::onboardSDK::CoreAPI::getCtrlInfo() const { return broadcastData.ctrlInfo; } +BatteryData DJI::onboardSDK::CoreAPI::getBatteryCapacity() const { return getBroadcastData().battery; } + +CtrlInfoData DJI::onboardSDK::CoreAPI::getCtrlInfo() const { return getBroadcastData().ctrlInfo; } void DJI::onboardSDK::CoreAPI::setBroadcastFrameStatus(bool isFrame) { @@ -78,7 +80,17 @@ void DJI::onboardSDK::CoreAPI::broadcast(Header *protocolHeader) uint16_t DATA_FLAG = 0x0001; //! @todo better algorithm - if (versionData.version != versionM100_23) + /** + *@note Write activation status + * + * Default value: 0xFF + * Activation successful: 0x00 + * Activation error codes: 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08 + * (see DJI_API.h for detailed description of the error codes) + */ + broadcastData.activation = ack_activation; + + if (versionData.fwVersion > MAKE_VERSION(3,1,0,0)) passData(*enableFlag, DATA_FLAG, &broadcastData.timeStamp, pdata, sizeof(TimeStampData), len); else @@ -91,7 +103,7 @@ void DJI::onboardSDK::CoreAPI::broadcast(Header *protocolHeader) passData(*enableFlag, DATA_FLAG, &broadcastData.w, pdata, sizeof(CommonData), len); passData(*enableFlag, DATA_FLAG, &broadcastData.pos, pdata, sizeof(PositionData), len); - if (versionData.version == versionA3_31 || versionData.version == versionA3_32) + if (strcmp(versionData.hwVersion, "M100") != 0) //! N3/A3/M600 { passData(*enableFlag, DATA_FLAG, &broadcastData.gps, pdata, sizeof(GPSData), len); passData(*enableFlag, DATA_FLAG, &broadcastData.rtk, pdata, sizeof(RTKData), len); @@ -103,11 +115,11 @@ void DJI::onboardSDK::CoreAPI::broadcast(Header *protocolHeader) passData(*enableFlag, DATA_FLAG, &broadcastData.mag, pdata, sizeof(MagnetData), len); passData(*enableFlag, DATA_FLAG, &broadcastData.rc, pdata, sizeof(RadioData), len); passData(*enableFlag, DATA_FLAG, &broadcastData.gimbal, pdata, - sizeof(GimbalData) - ((versionData.version == versionM100_23) ? 1 : 0), len); + sizeof(GimbalData) - ((versionData.fwVersion < MAKE_VERSION(3,1,0,0)) ? 1 : 0), len); passData(*enableFlag, DATA_FLAG, &broadcastData.status, pdata, sizeof(FlightStatus), len); passData(*enableFlag, DATA_FLAG, &broadcastData.battery, pdata, sizeof(BatteryData), len); passData(*enableFlag, DATA_FLAG, &broadcastData.ctrlInfo, pdata, - sizeof(CtrlInfoData) - ((versionData.version == versionM100_23) ? 1 : 0), len); + sizeof(CtrlInfoData) - ((versionData.fwVersion < MAKE_VERSION(3,1,0,0)) ? 1 : 0), len); serialDevice->freeMSG(); /** diff --git a/dji_sdk_lib/src/DJI_Camera.cpp b/dji_sdk_lib/src/DJI_Camera.cpp index 8aff386e..3f71c5a1 100644 --- a/dji_sdk_lib/src/DJI_Camera.cpp +++ b/dji_sdk_lib/src/DJI_Camera.cpp @@ -44,20 +44,20 @@ float32_t Camera::getPitch() const { return api->getBroadcastData().gimbal.pitch bool Camera::isYawLimit() const { - if (api->getSDKVersion() != versionM100_23) + if (api->getFwVersion() != versionM100_23) return api->getBroadcastData().gimbal.yawLimit ? true : false; return false; } bool Camera::isRollLimit() const { - if (api->getSDKVersion() != versionM100_23) + if (api->getFwVersion() != versionM100_23) return api->getBroadcastData().gimbal.rollLimit ? true : false; return false; } bool Camera::isPitchLimit() const { - if (api->getSDKVersion() != versionM100_23) + if (api->getFwVersion() != versionM100_23) return api->getBroadcastData().gimbal.pitchLimit ? true : false; return false; } diff --git a/dji_sdk_lib/src/DJI_Codec.cpp b/dji_sdk_lib/src/DJI_Codec.cpp index dbe9e34e..b1e90235 100644 --- a/dji_sdk_lib/src/DJI_Codec.cpp +++ b/dji_sdk_lib/src/DJI_Codec.cpp @@ -604,6 +604,11 @@ void DJI::onboardSDK::CoreAPI::callApp(SDKFilter *p_filter) sdk_stream_prepare_lambda(p_filter); } +void CoreAPI::setBroadcastActivation(uint32_t ack) +{ + ack_activation = ack; +} + bool CoreAPI::decodeACKStatus(unsigned short ack) { switch (ack) diff --git a/dji_sdk_lib/src/DJI_Flight.cpp b/dji_sdk_lib/src/DJI_Flight.cpp index 1592da3a..6c1fd3b5 100644 --- a/dji_sdk_lib/src/DJI_Flight.cpp +++ b/dji_sdk_lib/src/DJI_Flight.cpp @@ -68,7 +68,7 @@ void Flight::setArm(bool enable, CallBack ArmCallback, UserData userData) unsigned short Flight::setArm(bool enable, int timeout) { uint8_t data = enable ? 1 : 0; - api->send(2, encrypt, SET_CONTROL, CODE_SETARM, &data, 1, 0, 1, 0, 0); + api->send(2, encrypt, SET_CONTROL, CODE_SETARM, &data, 1, 10, 10, 0, 0); api->serialDevice->lockACK(); @@ -148,7 +148,7 @@ Flight::Status Flight::getStatus() const Flight::Mode Flight::getControlMode() const { - if (api->getSDKVersion() != versionM100_23) + if (api->getFwVersion() != versionM100_23) return (Flight::Mode)api->getBroadcastData().ctrlInfo.mode; return MODE_NOT_SUPPORTED; } diff --git a/dji_sdk_lib/src/DJI_Flight.cpp~ b/dji_sdk_lib/src/DJI_Flight.cpp~ deleted file mode 100644 index 28590a88..00000000 --- a/dji_sdk_lib/src/DJI_Flight.cpp~ +++ /dev/null @@ -1,267 +0,0 @@ -/** @brief - * @file DJI_Flight.cpp - * @version 3.1.7 - * @date July 1st, 2016 - * - * @abstract - * Flight Control API for DJI onboardSDK library - * - * @copyright 2016 DJI. All rights reserved. - * - */ - - -#include "DJI_Flight.h" -#include -#include - -using namespace DJI; -using namespace DJI::onboardSDK; - -Flight::Flight(DJI::onboardSDK::CoreAPI *ControlAPI) -{ - api = ControlAPI; -#ifdef USE_SIMULATION //! @note This functionality is not supported in this release. - simulating = 0; -#endif // USE_SIMULATION -} - -CoreAPI *Flight::getApi() const { return api; } - -void Flight::setApi(CoreAPI *value) { api = value; } - -#ifdef USE_SIMULATION //! @note This functionality is not supported in this release. -bool Flight::isSimulating() const { return simulating; } -void Flight::setSimulating(bool value) { simulating = value; } -#endif // USE_SIMULATION - -void Flight::task(TASK taskname, CallBack TaskCallback, UserData userData) -{ - taskData.cmdData = taskname; - taskData.cmdSequence++; - - api->send(2, encrypt, SET_CONTROL, CODE_TASK, (unsigned char *)&taskData, sizeof(taskData), - 100, 3, TaskCallback ? TaskCallback : Flight::taskCallback, userData); -} - -void Flight::setArm(bool enable, CallBack ArmCallback, UserData userData) -{ - uint8_t data = enable ? 1 : 0; - api->send(2, encrypt, SET_CONTROL, CODE_SETARM, &data, 1, 0, 1, - ArmCallback ? ArmCallback : Flight::armCallback, userData); -} - -void Flight::control(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw) -{ - FlightData data; - data.flag = flag; - data.x = x; - data.y = y; - data.z = z; - data.yaw = yaw; - setFlight(&data); -} - - -void Flight::setMovementControl(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw) -{ - FlightData data; - data.flag = flag; - data.x = x; - data.y = y; - data.z = z; - data.yaw = yaw; - api->send(0, encrypt, SET_CONTROL, CODE_CONTROL, &data, sizeof(FlightData)); -} - - -void Flight::setFlight(FlightData *data) -{ - api->send(0, encrypt, SET_CONTROL, CODE_CONTROL, (unsigned char *)data, sizeof(FlightData)); -} - -QuaternionData Flight::getQuaternion() const -{ -#ifdef USE_SIMULATION - if (simulating) - { - QuaternionData ans; - //! @todo better physical model - - return ans; - } - else -#endif // USE_SIMULATION - return api->getBroadcastData().q; -} - -EulerAngle Flight::getEulerAngle() const {return Flight::toEulerAngle(api->getBroadcastData().q); } - -PositionData Flight::getPosition() const { return api->getBroadcastData().pos; } - -VelocityData Flight::getVelocity() const { return api->getBroadcastData().v; } - -//! @warning The return type for getAcceleration will change to Vector3fData in a future release -CommonData Flight::getAcceleration() const { return api->getBroadcastData().a; } -//! @warning The return type for getYawRate will change to Vector3fData in a future release -CommonData Flight::getYawRate() const { return api->getBroadcastData().w; } - -//! @warning old interface. Will be replaced by MagData Flight::getMagData() in the next release. -MagnetData Flight::getMagnet() const { return api->getBroadcastData().mag; } - -Flight::Device Flight::getControlDevice() const -{ - return (Flight::Device)api->getBroadcastData().ctrlInfo.deviceStatus; -} - -Flight::Status Flight::getStatus() const -{ - return (Flight::Status)api->getBroadcastData().status; -} - -Flight::Mode Flight::getControlMode() const -{ - if (api->getSDKVersion() != versionM100_23) - return (Flight::Mode)api->getBroadcastData().ctrlInfo.mode; - return MODE_NOT_SUPPORTED; -} - -Angle Flight::getYaw() const -{ -#ifdef USE_SIMULATION - if (simulating) - return AngularSim.yaw; - else -#endif // USE_SIMULATION - return toEulerAngle(api->getBroadcastData().q).yaw; -} - -Angle Flight::getRoll() const -{ -#ifdef USE_SIMULATION - if (simulating) - return AngularSim.roll; - else -#endif // USE_SIMULATION - return toEulerAngle(api->getBroadcastData().q).roll; -} - -Angle Flight::getPitch() const -{ -#ifdef USE_SIMULATION - if (simulating) - return AngularSim.pitch; - else -#endif // USE_SIMULATION - return toEulerAngle(api->getBroadcastData().q).pitch; -} - -void Flight::armCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED) -{ - unsigned short ack_data; - if (protocolHeader->length - EXC_DATA_SIZE <= 2) - { - memcpy((unsigned char *)&ack_data, ((unsigned char *)protocolHeader) + sizeof(Header), - (protocolHeader->length - EXC_DATA_SIZE)); - switch (ack_data) - { - case ACK_ARM_SUCCESS: - API_LOG(api->getDriver(), STATUS_LOG, "Success,0x000%x\n", ack_data); - break; - case ACK_ARM_NEED_CONTROL: - API_LOG(api->getDriver(), STATUS_LOG, "Need to obtain control first, 0x000%x\n", ack_data); - break; - case ACK_ARM_ALREADY_ARMED: - API_LOG(api->getDriver(), STATUS_LOG, "Already done, 0x000%x\n", ack_data); - break; - case ACK_ARM_IN_AIR: - API_LOG(api->getDriver(), STATUS_LOG, "Cannot execute while in air, 0x000%x\n", ack_data); - break; - } - } - else - { - API_LOG(api->getDriver(), ERROR_LOG, "ACK is exception,session id %d,sequence %d\n", - protocolHeader->sessionID, protocolHeader->sequenceNumber); - } -} - -void Flight::taskCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED) -{ - unsigned short ack_data; - if (protocolHeader->length - EXC_DATA_SIZE <= 2) - { - memcpy((unsigned char *)&ack_data, ((unsigned char *)protocolHeader) + sizeof(Header), - (protocolHeader->length - EXC_DATA_SIZE)); - API_LOG(api->getDriver(), STATUS_LOG, "Task running successfully,%d\n", ack_data); - } - else - { - API_LOG(api->getDriver(), ERROR_LOG, "ACK is exception,session id %d,sequence %d\n", - protocolHeader->sessionID, protocolHeader->sequenceNumber); - } -} - -//! @ deprecated Use toEulerAngle instead. -EulerianAngle Flight::toEulerianAngle(QuaternionData data) -{ - EulerianAngle ans; - - double q2sqr = data.q2 * data.q2; - double t0 = -2.0 * (q2sqr + data.q3 * data.q3) + 1.0; - double t1 = +2.0 * (data.q1 * data.q2 + data.q0 * data.q3); - double t2 = -2.0 * (data.q1 * data.q3 - data.q0 * data.q2); - double t3 = +2.0 * (data.q2 * data.q3 + data.q0 * data.q1); - double t4 = -2.0 * (data.q1 * data.q1 + q2sqr) + 1.0; - - t2 = t2 > 1.0 ? 1.0 : t2; - t2 = t2 < -1.0 ? -1.0 : t2; - - ans.pitch = asin(t2); - ans.roll = atan2(t3, t4); - ans.yaw = atan2(t1, t0); - - return ans; -} - - -EulerAngle Flight::toEulerAngle(QuaternionData quaternionData) -{ - EulerAngle ans; - - double q2sqr = quaternionData.q2 * quaternionData.q2; - double t0 = -2.0 * (q2sqr + quaternionData.q3 * quaternionData.q3) + 1.0; - double t1 = +2.0 * (quaternionData.q1 * quaternionData.q2 + quaternionData.q0 * quaternionData.q3); - double t2 = -2.0 * (quaternionData.q1 * quaternionData.q3 - quaternionData.q0 * quaternionData.q2); - double t3 = +2.0 * (quaternionData.q2 * quaternionData.q3 + quaternionData.q0 * quaternionData.q1); - double t4 = -2.0 * (quaternionData.q1 * quaternionData.q1 + q2sqr) + 1.0; - - t2 = t2 > 1.0 ? 1.0 : t2; - t2 = t2 < -1.0 ? -1.0 : t2; - - ans.pitch = asin(t2); - ans.roll = atan2(t3, t4); - ans.yaw = atan2(t1, t0); - - return ans; -} - -QuaternionData Flight::toQuaternion(EulerianAngle eulerAngleData) -{ - QuaternionData ans; - double t0 = cos(eulerAngleData.yaw * 0.5); - double t1 = sin(eulerAngleData.yaw * 0.5); - double t2 = cos(eulerAngleData.roll * 0.5); - double t3 = sin(eulerAngleData.roll * 0.5); - double t4 = cos(eulerAngleData.pitch * 0.5); - double t5 = sin(eulerAngleData.pitch * 0.5); - - ans.q0 = t2 * t4 * t0 + t3 * t5 * t1; - ans.q1 = t3 * t4 * t0 - t2 * t5 * t1; - ans.q2 = t2 * t5 * t0 + t3 * t4 * t1; - ans.q3 = t2 * t4 * t1 - t3 * t5 * t0; - return ans; -} -} - - diff --git a/dji_sdk_lib/src/DJI_Link.cpp b/dji_sdk_lib/src/DJI_Link.cpp index dcbf51a1..02705219 100644 --- a/dji_sdk_lib/src/DJI_Link.cpp +++ b/dji_sdk_lib/src/DJI_Link.cpp @@ -58,9 +58,10 @@ void CoreAPI::appHandler(Header *protocolHeader) { if (protocolHeader->sessionID > 1 && protocolHeader->sessionID < 32) { - if (CMDSessionTab[protocolHeader->sessionID].usageFlag == 1) + serialDevice->lockMemory(); + uint32_t usageFlag = CMDSessionTab[protocolHeader->sessionID].usageFlag; + if (usageFlag == 1) { - serialDevice->lockMemory(); p2protocolHeader = (Header *)CMDSessionTab[protocolHeader->sessionID].mmu->pmem; if (p2protocolHeader->sessionID == protocolHeader->sessionID && p2protocolHeader->sequenceNumber == protocolHeader->sequenceNumber) @@ -71,6 +72,7 @@ void CoreAPI::appHandler(Header *protocolHeader) data = CMDSessionTab[protocolHeader->sessionID].userData; freeSession(&CMDSessionTab[protocolHeader->sessionID]); serialDevice->freeMemory(); + if (callBack) { //! Non-blocking callback thread @@ -161,9 +163,6 @@ void CoreAPI::appHandler(Header *protocolHeader) void CoreAPI::allocateACK(Header *protocolHeader) { - const size_t MAX_ACK_SIZE = (versionData.version == versionM100_31) ? - M100_MAX_ACK_SIZE : A3_MAX_ACK_SIZE; - if (protocolHeader->length <= MAX_ACK_SIZE) { memcpy(missionACKUnion.raw_ack_array, ((unsigned char *)protocolHeader) + sizeof(Header), @@ -171,7 +170,9 @@ void CoreAPI::allocateACK(Header *protocolHeader) { } else { +#ifndef STM32 throw std::runtime_error("Unknown ACK"); +#endif } } @@ -293,10 +294,13 @@ void CoreAPI::setKey(const char *key) void CoreAPI::setActivation(bool isActivated) { - if (isActivated) + serialDevice->lockMSG(); + if (isActivated) { broadcastData.activation = 1; - else + } else { broadcastData.activation = 0; + } + serialDevice->freeMSG(); } void DJI::onboardSDK::CoreAPI::setACKFrameStatus(uint32_t usageFlag) diff --git a/dji_sdk_lib/src/DJI_Logging.cpp b/dji_sdk_lib/src/DJI_Logging.cpp index e78dbd76..9bfad75b 100644 --- a/dji_sdk_lib/src/DJI_Logging.cpp +++ b/dji_sdk_lib/src/DJI_Logging.cpp @@ -13,25 +13,26 @@ #include "DJI_API.h" #include "DJI_Link.h" #include "DJI_Type.h" +#ifdef API_TRACE_DATA #include namespace DJI { namespace onboardSDK { - pthread_mutex_t _logging_lock = PTHREAD_MUTEX_INITIALIZER; +pthread_mutex_t _logging_lock = PTHREAD_MUTEX_INITIALIZER; void printFrame(HardDriver *serialDevice, Header *header, bool onboardToAircraft) { pthread_mutex_lock(&_logging_lock); - uint32_t *crc32 = (uint32_t*) ((uint8_t*)header + header->length - 4); + uint32_t *crc32 = (uint32_t *)((uint8_t *)header + header->length - 4); - if (!header->isAck) { - __Command* command = (__Command*)((uint8_t*)header + sizeof(Header)); + if (!header->isAck) { + __Command *command = (__Command *)((uint8_t *)header + sizeof(Header)); - if (!onboardToAircraft && command->set_id == SET_BROADCAST) { - pthread_mutex_unlock(&_logging_lock); - return; - } + if (!onboardToAircraft && command->set_id == SET_BROADCAST) { + pthread_mutex_unlock(&_logging_lock); + return; + } API_LOG(serialDevice, DEBUG_LOG, "\n\n"); if (onboardToAircraft) { @@ -76,4 +77,5 @@ void printFrame(HardDriver *serialDevice, Header *header, bool onboardToAircraft pthread_mutex_unlock(&_logging_lock); } } -} \ No newline at end of file +} +#endif // API_TRACE_DATA diff --git a/dji_sdk_lib/src/DJI_WayPoint.cpp b/dji_sdk_lib/src/DJI_WayPoint.cpp index 8be9301b..c9608a7d 100644 --- a/dji_sdk_lib/src/DJI_WayPoint.cpp +++ b/dji_sdk_lib/src/DJI_WayPoint.cpp @@ -154,7 +154,9 @@ WayPointDataACK WayPoint::uploadIndexData(WayPointData *data, int timeout) if (data->index < info.indexNumber) wpData = index[data->index]; else - throw std::runtime_error("Range error\n"); +#ifndef STM32 + throw std::runtime_error("Range error\n"); +#endif api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_ADDPOINT, &wpData, sizeof(wpData), 1000, 4, 0, 0); @@ -165,6 +167,48 @@ WayPointDataACK WayPoint::uploadIndexData(WayPointData *data, int timeout) return api->missionACKUnion.waypointDataACK; } +/** + * @note Read Waypoint mission settings from the flight controller + * + * @return Information about uploaded Waypoint(s) + * + */ +WayPointInitACK WayPoint::getWaypointSettings(int timeout) +{ + uint8_t arbNumber = 0; + api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_INFO_READ, &arbNumber, sizeof(arbNumber), 1000, 4, 0, 0); + + api->serialDevice->lockACK(); + api->serialDevice->wait(timeout); + api->serialDevice->freeACK(); + + return api->missionACKUnion.waypointInitACK; +} + +void WayPoint::getWaypointSettings(CallBack callback, UserData userData) +{ + uint8_t arbNumber = 0; + api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_INFO_READ, &arbNumber, sizeof(arbNumber), 1000, 4, + callback ? callback : getWaypointSettingsCallback, userData ? userData : this); +} + +WayPointDataACK WayPoint::getIndex(uint8_t index, int timeout) +{ + api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_INDEX_READ, &index, sizeof(index), 1000, 4, 0, 0); + + api->serialDevice->lockACK(); + api->serialDevice->wait(timeout); + api->serialDevice->freeACK(); + + return api->missionACKUnion.waypointDataACK; +} + +void WayPoint::getIndex(uint8_t index, CallBack callback, UserData userData) +{ + api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_INDEX_READ, &index, sizeof(index), 1000, 4, + callback ? callback : uploadIndexDataCallback, userData ? userData : this); +} + void WayPoint::updateIdleVelocity(float32_t meterPreSecond, CallBack callback, UserData userData) { @@ -173,7 +217,7 @@ void WayPoint::updateIdleVelocity(float32_t meterPreSecond, CallBack callback, userData ? userData : this); } -WayPointInitData WayPoint::getInfo() const +WayPointInitData WayPoint::getInfo() const { return info; } @@ -193,16 +237,6 @@ void WayPoint::setInfo(const WayPointInitData &value) #endif // STATIC_MEMORY } -WayPointData *WayPoint::getIndex() const -{ - return index; -} - -WayPointData *WayPoint::getIndex(size_t pos) const -{ - return &(index[pos]); -} - void WayPoint::idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi) { WayPoint *wp = (WayPoint *)wpapi; @@ -222,7 +256,7 @@ void WayPoint::idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserDa API_LOG(api->getDriver(), STATUS_LOG, "Current idle velocity: %f", wp->info.idleVelocity); } -void WayPoint::readInitDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi) +void WayPoint::getWaypointSettingsCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi) { WayPoint *wp = (WayPoint *)wpapi; WayPointInitACK ack; @@ -256,7 +290,13 @@ void WayPoint::uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, Use return; } api->decodeMissionStatus(ack.ack); - API_LOG(api->getDriver(), STATUS_LOG, "Index number: %d\n", ack.index); + API_LOG(api->getDriver(), STATUS_LOG, "Index number: %d\n", ack.data.index); + API_LOG(api->getDriver(), STATUS_LOG, "Action number: %d\n", ack.data.actionNumber); + API_LOG(api->getDriver(), STATUS_LOG, "Latitude: %f\n", ack.data.latitude); + API_LOG(api->getDriver(), STATUS_LOG, "Longitude: %f\n", ack.data.longitude); + API_LOG(api->getDriver(), STATUS_LOG, "Altitude: %f\n", ack.data.altitude); + API_LOG(api->getDriver(), STATUS_LOG, "Yaw: %d\n", ack.data.yaw); + API_LOG(api->getDriver(), STATUS_LOG, "Gimbal pitch: %d\n", ack.data.gimbalPitch); } void WayPoint::setIndex(WayPointData *value, size_t pos)