From ce652e81345966d19028359671912f61e4b47489 Mon Sep 17 00:00:00 2001 From: Arjun Date: Mon, 21 Nov 2016 17:37:52 -0800 Subject: [PATCH] Hotfix 3.1.9.1 for A3 firmware 1.5.0.0. Fixes for SDK Version query and Obtain Control RC mode errors --- dji_sdk/launch/sdk_manifold.launch | 1 + dji_sdk/src/modules/dji_sdk_node_main.cpp | 12 +- .../doxygen/html/DJICommonType_8h.html | 15 +- .../doxygen/html/DJICommonType_8h_source.html | 6 +- dji_sdk_doc/doxygen/html/DJI__API_8cpp.html | 2 +- dji_sdk_doc/doxygen/html/DJI__API_8h.html | 18 +- .../doxygen/html/DJI__API_8h_source.html | 105 ++-- dji_sdk_doc/doxygen/html/DJI__App_8cpp.html | 9 +- dji_sdk_doc/doxygen/html/DJI__App_8h.html | 40 +- .../doxygen/html/DJI__App_8h_source.html | 12 +- .../doxygen/html/DJI__Camera_8cpp.html | 9 +- dji_sdk_doc/doxygen/html/DJI__Camera_8h.html | 10 +- .../doxygen/html/DJI__Camera_8h_source.html | 16 +- dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html | 2 +- dji_sdk_doc/doxygen/html/DJI__Codec_8h.html | 28 +- .../doxygen/html/DJI__Codec_8h_source.html | 4 +- dji_sdk_doc/doxygen/html/DJI__Config_8h.html | 27 +- .../doxygen/html/DJI__Config_8h_source.html | 4 +- .../doxygen/html/DJI__Flight_8cpp.html | 2 +- dji_sdk_doc/doxygen/html/DJI__Flight_8h.html | 2 +- .../doxygen/html/DJI__Flight_8h_source.html | 24 +- .../doxygen/html/DJI__Follow_8cpp.html | 9 +- dji_sdk_doc/doxygen/html/DJI__Follow_8h.html | 11 +- .../doxygen/html/DJI__Follow_8h_source.html | 17 +- .../doxygen/html/DJI__HardDriver_8cpp.html | 110 ---- .../doxygen/html/DJI__HardDriver_8h.html | 18 +- .../html/DJI__HardDriver_8h_source.html | 8 +- .../doxygen/html/DJI__HotPoint_8cpp.html | 13 +- .../doxygen/html/DJI__HotPoint_8h_source.html | 23 +- dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html | 2 +- dji_sdk_doc/doxygen/html/DJI__Link_8h.html | 21 +- .../doxygen/html/DJI__Link_8h_source.html | 4 +- .../doxygen/html/DJI__Memory_8cpp.html | 16 +- .../doxygen/html/DJI__Memory_8h_source.html | 4 +- .../doxygen/html/DJI__Mission_8cpp.html | 12 +- dji_sdk_doc/doxygen/html/DJI__Mission_8h.html | 164 ------ .../doxygen/html/DJI__Mission_8h_source.html | 17 +- dji_sdk_doc/doxygen/html/DJI__Type_8h.html | 152 +---- .../doxygen/html/DJI__Type_8h_source.html | 117 ++-- dji_sdk_doc/doxygen/html/DJI__Version_8h.html | 27 +- .../doxygen/html/DJI__Version_8h_source.html | 6 +- .../doxygen/html/DJI__VirtualRC_8cpp.html | 9 +- .../doxygen/html/DJI__VirtualRC_8h.html | 9 +- .../html/DJI__VirtualRC_8h_source.html | 28 +- .../doxygen/html/DJI__WayPoint_8cpp.html | 9 +- .../doxygen/html/DJI__WayPoint_8h.html | 52 +- .../doxygen/html/DJI__WayPoint_8h_source.html | 27 +- dji_sdk_doc/doxygen/html/annotated.html | 123 ++--- ...ssDJI_1_1onboardSDK_1_1Camera-members.html | 2 +- .../classDJI_1_1onboardSDK_1_1Camera.html | 11 +- ...sDJI_1_1onboardSDK_1_1CoreAPI-members.html | 94 +--- .../classDJI_1_1onboardSDK_1_1CoreAPI.html | 521 ++---------------- ...ssDJI_1_1onboardSDK_1_1Flight-members.html | 30 +- .../classDJI_1_1onboardSDK_1_1Flight.html | 22 +- ...ssDJI_1_1onboardSDK_1_1Follow-members.html | 37 +- .../classDJI_1_1onboardSDK_1_1Follow.html | 19 +- ...I_1_1onboardSDK_1_1HardDriver-members.html | 20 +- .../classDJI_1_1onboardSDK_1_1HardDriver.html | 19 +- ...DJI_1_1onboardSDK_1_1HotPoint-members.html | 43 +- .../classDJI_1_1onboardSDK_1_1HotPoint.html | 55 +- ...JI_1_1onboardSDK_1_1VirtualRC-members.html | 2 +- .../classDJI_1_1onboardSDK_1_1VirtualRC.html | 4 +- ...DJI_1_1onboardSDK_1_1WayPoint-members.html | 17 +- .../classDJI_1_1onboardSDK_1_1WayPoint.html | 61 +- dji_sdk_doc/doxygen/html/classes.html | 56 +- dji_sdk_doc/doxygen/html/deprecated.html | 2 +- .../dir_4858fddfe5c24bcac01c3c8697387c37.html | 2 +- .../dir_7d5f782014efafaf8289e99742765d5b.html | 2 +- .../dir_d6adb40f961893fe77ad1c93ece9fa6b.html | 12 +- .../dir_df193617b4317ea26407acd6acb5749e.html | 19 +- dji_sdk_doc/doxygen/html/files.html | 49 +- dji_sdk_doc/doxygen/html/functions.html | 31 +- dji_sdk_doc/doxygen/html/functions_enum.html | 2 +- dji_sdk_doc/doxygen/html/functions_eval.html | 2 +- dji_sdk_doc/doxygen/html/functions_func.html | 23 +- dji_sdk_doc/doxygen/html/functions_vars.html | 8 +- dji_sdk_doc/doxygen/html/globals.html | 6 +- dji_sdk_doc/doxygen/html/globals_defs.html | 5 +- dji_sdk_doc/doxygen/html/globals_func.html | 2 +- dji_sdk_doc/doxygen/html/globals_type.html | 5 +- dji_sdk_doc/doxygen/html/index.html | 4 +- dji_sdk_doc/doxygen/html/namespaceDJI.html | 14 +- .../doxygen/html/namespacemembers.html | 8 +- .../doxygen/html/namespacemembers_type.html | 8 +- dji_sdk_doc/doxygen/html/namespaces.html | 2 +- dji_sdk_doc/doxygen/html/pages.html | 2 +- dji_sdk_doc/doxygen/html/search/all_0.js | 14 +- dji_sdk_doc/doxygen/html/search/all_1.js | 19 +- dji_sdk_doc/doxygen/html/search/all_10.js | 37 +- dji_sdk_doc/doxygen/html/search/all_11.js | 11 +- dji_sdk_doc/doxygen/html/search/all_12.js | 15 +- dji_sdk_doc/doxygen/html/search/all_13.js | 18 +- dji_sdk_doc/doxygen/html/search/all_14.js | 10 +- dji_sdk_doc/doxygen/html/search/all_15.html | 26 - dji_sdk_doc/doxygen/html/search/all_15.js | 5 - dji_sdk_doc/doxygen/html/search/all_2.js | 16 +- dji_sdk_doc/doxygen/html/search/all_3.js | 45 +- dji_sdk_doc/doxygen/html/search/all_4.js | 37 +- dji_sdk_doc/doxygen/html/search/all_5.js | 11 +- dji_sdk_doc/doxygen/html/search/all_6.js | 32 +- dji_sdk_doc/doxygen/html/search/all_7.js | 36 +- dji_sdk_doc/doxygen/html/search/all_8.js | 12 +- dji_sdk_doc/doxygen/html/search/all_9.js | 2 +- dji_sdk_doc/doxygen/html/search/all_a.js | 16 +- dji_sdk_doc/doxygen/html/search/all_b.js | 19 +- dji_sdk_doc/doxygen/html/search/all_c.js | 7 +- dji_sdk_doc/doxygen/html/search/all_d.js | 6 +- dji_sdk_doc/doxygen/html/search/all_e.js | 16 +- dji_sdk_doc/doxygen/html/search/all_f.js | 40 +- dji_sdk_doc/doxygen/html/search/classes_0.js | 2 +- dji_sdk_doc/doxygen/html/search/classes_6.js | 4 +- dji_sdk_doc/doxygen/html/search/classes_7.js | 1 - dji_sdk_doc/doxygen/html/search/classes_a.js | 1 + dji_sdk_doc/doxygen/html/search/classes_b.js | 3 +- dji_sdk_doc/doxygen/html/search/classes_d.js | 2 +- dji_sdk_doc/doxygen/html/search/defines_0.js | 3 +- dji_sdk_doc/doxygen/html/search/defines_1.js | 3 +- dji_sdk_doc/doxygen/html/search/defines_2.js | 2 +- dji_sdk_doc/doxygen/html/search/defines_3.js | 2 +- .../doxygen/html/search/defines_4.html | 26 - dji_sdk_doc/doxygen/html/search/defines_4.js | 4 - dji_sdk_doc/doxygen/html/search/enums_0.js | 2 +- dji_sdk_doc/doxygen/html/search/files_0.js | 3 +- .../doxygen/html/search/functions_0.js | 2 +- .../doxygen/html/search/functions_5.js | 3 +- .../doxygen/html/search/functions_7.js | 3 +- .../doxygen/html/search/functions_8.js | 1 - .../doxygen/html/search/functions_a.js | 7 +- dji_sdk_doc/doxygen/html/search/searchdata.js | 8 +- dji_sdk_doc/doxygen/html/search/typedefs_0.js | 1 + dji_sdk_doc/doxygen/html/search/typedefs_2.js | 2 - dji_sdk_doc/doxygen/html/search/typedefs_4.js | 5 +- dji_sdk_doc/doxygen/html/search/typedefs_5.js | 4 +- dji_sdk_doc/doxygen/html/search/typedefs_6.js | 1 - dji_sdk_doc/doxygen/html/search/typedefs_a.js | 4 +- .../doxygen/html/search/typedefs_b.html | 26 - dji_sdk_doc/doxygen/html/search/typedefs_b.js | 6 - .../doxygen/html/search/typedefs_c.html | 26 - dji_sdk_doc/doxygen/html/search/typedefs_c.js | 4 - .../doxygen/html/search/variables_0.js | 3 +- .../doxygen/html/search/variables_8.js | 2 +- .../doxygen/html/search/variables_9.js | 2 +- .../doxygen/html/search/variables_a.js | 2 +- .../doxygen/html/search/variables_b.html | 26 - .../doxygen/html/search/variables_b.js | 4 - .../html/structDJI_1_1EulerAngle-members.html | 2 +- .../doxygen/html/structDJI_1_1EulerAngle.html | 2 +- .../structDJI_1_1EulerianAngle-members.html | 2 +- .../html/structDJI_1_1EulerianAngle.html | 2 +- .../html/structDJI_1_1Measure-members.html | 2 +- .../doxygen/html/structDJI_1_1Measure.html | 2 +- .../structDJI_1_1Measurement-members.html | 2 +- .../html/structDJI_1_1Measurement.html | 2 +- .../structDJI_1_1SpaceVector-members.html | 2 +- .../html/structDJI_1_1SpaceVector.html | 4 +- .../structDJI_1_1Vector3dData-members.html | 2 +- .../html/structDJI_1_1Vector3dData.html | 2 +- ...I_1_1onboardSDK_1_1ACKSession-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1ACKSession.html | 2 +- ...tructDJI_1_1onboardSDK_1_1Ack-members.html | 2 +- .../html/structDJI_1_1onboardSDK_1_1Ack.html | 2 +- ...1_1onboardSDK_1_1ActivateData-members.html | 110 ---- ...ructDJI_1_1onboardSDK_1_1ActivateData.html | 127 ----- ..._1onboardSDK_1_1BroadcastData-members.html | 2 +- ...uctDJI_1_1onboardSDK_1_1BroadcastData.html | 6 +- ...I_1_1onboardSDK_1_1CMDSession-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1CMDSession.html | 4 +- ...onboardSDK_1_1CallBackHandler-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1CallBackHandler.html | 13 +- ...tDJI_1_1onboardSDK_1_1Command-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1Command.html | 4 +- ...I_1_1onboardSDK_1_1CommonData-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1CommonData.html | 2 +- ...1_1onboardSDK_1_1CtrlInfoData-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1CtrlInfoData.html | 4 +- ...I_1_1onboardSDK_1_1FlightData-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1FlightData.html | 2 +- ...I_1_1onboardSDK_1_1FollowData-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1FollowData.html | 2 +- ...1_1onboardSDK_1_1FollowTarget-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1FollowTarget.html | 2 +- ...tDJI_1_1onboardSDK_1_1GPSData-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1GPSData.html | 4 +- ...onboardSDK_1_1GPSPositionData-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1GPSPositionData.html | 2 +- ...I_1_1onboardSDK_1_1GSPushData-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1GSPushData.html | 4 +- ...onboardSDK_1_1GimbalAngleData-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1GimbalAngleData.html | 8 +- ...I_1_1onboardSDK_1_1GimbalData-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1GimbalData.html | 2 +- ...onboardSDK_1_1GimbalSpeedData-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1GimbalSpeedData.html | 2 +- ...ctDJI_1_1onboardSDK_1_1Header-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1Header.html | 11 +- ...onboardSDK_1_1HotPointACKData-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1HotPointACKData.html | 2 +- ...1_1onboardSDK_1_1HotPointData-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1HotPointData.html | 10 +- ...onboardSDK_1_1HotPointReadACK-members.html | 107 ---- ...tDJI_1_1onboardSDK_1_1HotPointReadACK.html | 118 ---- ...nboardSDK_1_1HotPointStartACK-members.html | 107 ---- ...DJI_1_1onboardSDK_1_1HotPointStartACK.html | 118 ---- ...ardSDK_1_1HotPoint_1_1YawRate-members.html | 2 +- ..._1_1onboardSDK_1_1HotPoint_1_1YawRate.html | 2 +- ...DJI_1_1onboardSDK_1_1MMU__Tab-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1MMU__Tab.html | 2 +- ...tDJI_1_1onboardSDK_1_1MagData-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1MagData.html | 2 +- ...I_1_1onboardSDK_1_1MagnetData-members.html | 2 +- ...structDJI_1_1onboardSDK_1_1MagnetData.html | 2 +- ..._1onboardSDK_1_1MissionACKMap-members.html | 2 +- ...uctDJI_1_1onboardSDK_1_1MissionACKMap.html | 2 +- ...1_1onboardSDK_1_1PositionData-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1PositionData.html | 2 +- ...1onboardSDK_1_1QuaternionData-members.html | 2 +- ...ctDJI_1_1onboardSDK_1_1QuaternionData.html | 2 +- ...ctDJI_1_1onboardSDK_1_1RCData-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1RCData.html | 2 +- ...tDJI_1_1onboardSDK_1_1RTKData-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1RTKData.html | 4 +- ...JI_1_1onboardSDK_1_1RadioData-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1RadioData.html | 2 +- ...JI_1_1onboardSDK_1_1SDKFilter-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1SDKFilter.html | 2 +- ...DJI_1_1onboardSDK_1_1TaskData-members.html | 2 +- .../structDJI_1_1onboardSDK_1_1TaskData.html | 2 +- ..._1onboardSDK_1_1TimeStampData-members.html | 2 +- ...uctDJI_1_1onboardSDK_1_1TimeStampData.html | 4 +- ...1_1onboardSDK_1_1Vector3fData-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1Vector3fData.html | 2 +- ...1_1onboardSDK_1_1VelocityData-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1VelocityData.html | 2 +- ..._1_1onboardSDK_1_1VersionData-members.html | 110 ---- ...tructDJI_1_1onboardSDK_1_1VersionData.html | 127 ----- ..._1onboardSDK_1_1VirtualRCData-members.html | 2 +- ...uctDJI_1_1onboardSDK_1_1VirtualRCData.html | 4 +- ...nboardSDK_1_1VirtualRCSetting-members.html | 2 +- ...DJI_1_1onboardSDK_1_1VirtualRCSetting.html | 2 +- ...1_1onboardSDK_1_1WayPointData-members.html | 2 +- ...ructDJI_1_1onboardSDK_1_1WayPointData.html | 4 +- ...onboardSDK_1_1WayPointDataACK-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1WayPointDataACK.html | 4 +- ...onboardSDK_1_1WayPointInitACK-members.html | 2 +- ...tDJI_1_1onboardSDK_1_1WayPointInitACK.html | 4 +- ...nboardSDK_1_1WayPointInitData-members.html | 2 +- ...DJI_1_1onboardSDK_1_1WayPointInitData.html | 12 +- ...ardSDK_1_1WayPointVelocityACK-members.html | 2 +- ..._1_1onboardSDK_1_1WayPointVelocityACK.html | 4 +- .../html/structreq__id__t-members.html | 2 +- .../doxygen/html/structreq__id__t.html | 2 +- .../html/structtagAES256Context-members.html | 2 +- .../doxygen/html/structtagAES256Context.html | 2 +- dji_sdk_doc/doxygen/html/todo.html | 64 ++- ...onboardSDK_1_1MissionACKUnion-members.html | 111 ---- ...nDJI_1_1onboardSDK_1_1MissionACKUnion.html | 130 ----- dji_sdk_lib/include/dji_sdk_lib/DJI_API.h | 16 +- dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h | 2 +- dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h | 53 +- dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h | 1 + dji_sdk_lib/src/DJI_API.cpp | 293 +++++++--- dji_sdk_lib/src/DJI_App.cpp | 2 +- dji_sdk_lib/src/DJI_Link.cpp | 75 +-- dji_sdk_lib/src/DJI_WayPoint.cpp | 2 +- 264 files changed, 1458 insertions(+), 3716 deletions(-) delete mode 100644 dji_sdk_doc/doxygen/html/DJI__HardDriver_8cpp.html delete mode 100644 dji_sdk_doc/doxygen/html/DJI__Mission_8h.html delete mode 100644 dji_sdk_doc/doxygen/html/search/all_15.html delete mode 100644 dji_sdk_doc/doxygen/html/search/all_15.js delete mode 100644 dji_sdk_doc/doxygen/html/search/defines_4.html delete mode 100644 dji_sdk_doc/doxygen/html/search/defines_4.js delete mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_b.html delete mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_b.js delete mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_c.html delete mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_c.js delete mode 100644 dji_sdk_doc/doxygen/html/search/variables_b.html delete mode 100644 dji_sdk_doc/doxygen/html/search/variables_b.js delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData-members.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK-members.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK-members.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData-members.html delete mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData.html delete mode 100644 dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion-members.html delete mode 100644 dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion.html diff --git a/dji_sdk/launch/sdk_manifold.launch b/dji_sdk/launch/sdk_manifold.launch index 98c23a47..7b3c95d4 100644 --- a/dji_sdk/launch/sdk_manifold.launch +++ b/dji_sdk/launch/sdk_manifold.launch @@ -1,6 +1,7 @@ + diff --git a/dji_sdk/src/modules/dji_sdk_node_main.cpp b/dji_sdk/src/modules/dji_sdk_node_main.cpp index b3c59962..8216bb3a 100644 --- a/dji_sdk/src/modules/dji_sdk_node_main.cpp +++ b/dji_sdk/src/modules/dji_sdk_node_main.cpp @@ -146,7 +146,7 @@ void DJISDKNode::broadcast_callback() ****************************If using A3**************************** ******************************************************************/ - if(version == DJI::onboardSDK::versionA3_31) { + if(version == DJI::onboardSDK::versionA3_31 || DJI::onboardSDK::versionA3_32) { //update gimbal msg if (msg_flags & A3_HAS_GIMBAL) { @@ -348,11 +348,15 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private) if(!drone_version.compare("M100")) { - user_act_data.version = 0x03010a00; + user_act_data.version = versionM100_31; } - else + else if (!drone_version.compare("A3_31")) { - user_act_data.version = 0x03016400; + 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()); diff --git a/dji_sdk_doc/doxygen/html/DJICommonType_8h.html b/dji_sdk_doc/doxygen/html/DJICommonType_8h.html index b9eef27c..3ef12d56 100644 --- a/dji_sdk_doc/doxygen/html/DJICommonType_8h.html +++ b/dji_sdk_doc/doxygen/html/DJICommonType_8h.html @@ -94,9 +94,6 @@
DJICommonType.h File Reference
- -

Common Type definition for DJI onboardSDK library. Officially Maintained. -More...

#include <stdint.h>

Go to the source code of this file.

@@ -130,11 +127,11 @@ typedef uint64_t DJI::time_us   -typedef void * DJI::UserData - This is used as the datatype for all data arguments in callbacks.
+typedef void * DJI::UserData   -typedef uint32_t DJI::Flag +typedef uint32_t DJI::Flag + This is used as the datatype for all data arguments in callbacks.
  typedef uint8_t DJI::size8_t @@ -158,14 +155,14 @@  

Detailed Description

-

Common Type definition for DJI onboardSDK library. Officially Maintained.

-
Version
3.1.7
+
Version
3.1.7
Date
Jul 01 2016
+

Common Type definition for DJI onboardSDK library Officially Maintained

diff --git a/dji_sdk_doc/doxygen/html/DJICommonType_8h_source.html b/dji_sdk_doc/doxygen/html/DJICommonType_8h_source.html index 69191724..343d6092 100644 --- a/dji_sdk_doc/doxygen/html/DJICommonType_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJICommonType_8h_source.html @@ -90,15 +90,15 @@
DJICommonType.h
-Go to the documentation of this file.
1 
19 #ifndef DJICOMMONTYPE
20 #define DJICOMMONTYPE
21 
22 #include <stdint.h>
23 
24 namespace DJI
25 {
26 
27 typedef uint64_t time_ms;
28 typedef uint64_t time_us; // about 0.3 million years
29 
31 typedef void *UserData;
32 typedef uint32_t Flag;
33 
34 typedef uint8_t size8_t;
35 typedef uint16_t size16_t;
36 
38 typedef struct Measure
39 {
40  double data;
41  float precision;
42 } Measure;
44 typedef struct Measurement
45 {
46  double data;
47  float precision;
48 } Measurement;
49 
51 typedef struct SpaceVector
52 {
53  double x;
54  double y;
55  double z;
56 } SpaceVector;
57 
60 typedef struct Vector3dData
61 {
62  double x;
63  double y;
64  double z;
65 } Vector3dData;
66 
78 typedef double Angle;
79 
81 typedef struct EulerianAngle
82 {
83  Angle yaw;
84  Angle roll;
85  Angle pitch;
87 
89 typedef struct EulerAngle
90 {
91  Angle yaw;
92  Angle roll;
93  Angle pitch;
94 } EulerAngle;
95 
96 } // namespace DJI
97 
98 #endif // DJICOMMONTYPE
Definition: DJICommonType.h:81
+Go to the documentation of this file.
1 
20 #ifndef DJICOMMONTYPE
21 #define DJICOMMONTYPE
22 
23 #include <stdint.h>
24 
25 namespace DJI
26 {
27 
28 typedef uint64_t time_ms;
29 typedef uint64_t time_us; // about 0.3 million years
30 
31 typedef void *UserData;
32 typedef uint32_t Flag;
33 
34 typedef uint8_t size8_t;
35 typedef uint16_t size16_t;
36 
38 typedef struct Measure
39 {
40  double data;
41  float precision;
42 } Measure;
44 typedef struct Measurement
45 {
46  double data;
47  float precision;
48 } Measurement;
49 
51 typedef struct SpaceVector
52 {
53  double x;
54  double y;
55  double z;
56 } SpaceVector;
57 
60 typedef struct Vector3dData
61 {
62  double x;
63  double y;
64  double z;
65 } Vector3dData;
66 
78 typedef double Angle;
79 
81 typedef struct EulerianAngle
82 {
83  Angle yaw;
84  Angle roll;
85  Angle pitch;
87 
89 typedef struct EulerAngle
90 {
91  Angle yaw;
92  Angle roll;
93  Angle pitch;
94 } EulerAngle;
95 
96 } // namespace DJI
97 
98 #endif // DJICOMMONTYPE
Definition: DJICommonType.h:81
struct DJI::EulerAngle EulerAngle
+
uint32_t Flag
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:32
Definition: DJICommonType.h:60
struct DJI::EulerianAngle EulerianAngle
struct DJI::Measure Measure
double Angle
Definition: DJICommonType.h:78
Definition: DJICommonType.h:38
Definition: DJICommonType.h:44
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
struct DJI::SpaceVector SpaceVector
Definition: DJI_Mission.cpp:16
struct DJI::Measurement Measurement
@@ -108,7 +108,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__API_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__API_8cpp.html index a85cc637..81c418ab 100644 --- a/dji_sdk_doc/doxygen/html/DJI__API_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__API_8cpp.html @@ -104,7 +104,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__API_8h.html b/dji_sdk_doc/doxygen/html/DJI__API_8h.html index 519b70a3..59cf5825 100644 --- a/dji_sdk_doc/doxygen/html/DJI__API_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__API_8h.html @@ -116,11 +116,7 @@ - - - - -

Enumerations

enum  DJI::onboardSDK::ACK_ERROR_CODE { ACK_SUCCESS = 0x0000, -ACK_PARAM_ERROR = 0x0001 - }
 
enum  ACK_COMMON_CODE {
+
enum  DJI::onboardSDK::ACK_COMMON_CODE {
  ACK_COMMON_SUCCESS = 0x0000, ACK_COMMON_KEYERROR = 0xFF00, ACK_COMMON_NO_AUTHORIZATION = 0xFF01, @@ -162,10 +158,6 @@ ACK_ARM_IN_AIR = 0x0003 }
 
enum  TASK_ACK_CODE { TASK_FAILURE = 0x01, -TASK_SUCCESS = 0x02 - }
 
enum  DJI::onboardSDK::CMD_SET {
  SET_ACTIVATION = 0x00, SET_CONTROL = 0x01, @@ -269,16 +261,16 @@
Date
July 1st, 2016

Enumeration Type Documentation

- +
-
Todo:
sort enum and move to a new file
+
Todo:
sort enum and move to a new file
@@ -298,7 +290,7 @@ 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 6a926173..ef04f305 100644 --- a/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html @@ -90,73 +90,60 @@
DJI_API.h
-Go to the documentation of this file.
1 
12 // The comment block below is made for doxygen.
13 
26 #ifndef DJI_API_H
27 #define DJI_API_H
28 #include "DJI_Type.h"
29 //#include "DJI_Mission.h"
30 
31 #include "DJI_HardDriver.h"
32 #include "DJI_App.h"
33 namespace DJI
34 {
35 namespace onboardSDK
36 {
37 class CoreAPI;
38 class Flight;
39 class Camera;
40 class VirtualRC;
41 class HotPoint;
42 
44 
46 {
47  ACK_SUCCESS = 0x0000,
48  ACK_PARAM_ERROR = 0x0001
49 };
50 
51 enum ACK_COMMON_CODE
52 {
53  ACK_COMMON_SUCCESS = 0x0000,
54  ACK_COMMON_KEYERROR = 0xFF00,
55  ACK_COMMON_NO_AUTHORIZATION = 0xFF01,
56  ACK_COMMON_NO_RIGHTS = 0xFF02,
57  ACK_COMMON_NO_RESPONSE = 0xFFFF
58 };
59 
60 enum ACK_ACTIVE_CODE
61 {
62  ACK_ACTIVE_SUCCESS = 0x0000,
63  ACK_ACTIVE_PARAMETER_ERROR = 0x0001,
64  ACK_ACTIVE_ENCODE_ERROR = 0x0002,
65  ACK_ACTIVE_NEW_DEVICE = 0x0003,
66  ACK_ACTIVE_APP_NOT_CONNECTED = 0x0004,
67  ACK_ACTIVE_NO_INTERNET = 0x0005,
68  ACK_ACTIVE_SERVER_REFUSED = 0x0006,
69  ACK_ACTIVE_ACCESS_LEVEL_ERROR = 0x0007,
70  ACK_ACTIVE_VERSION_ERROR = 0x0008
71 };
72 
73 enum ACK_SETCONTROL_CODE
74 {
75  ACK_SETCONTROL_NEED_MODE_F = 0x0000,
76  ACK_SETCONTROL_RELEASE_SUCCESS = 0x0001,
77  ACK_SETCONTROL_OBTAIN_SUCCESS = 0x0002,
78  ACK_SETCONTROL_OBTAIN_RUNNING = 0x0003,
79  ACK_SETCONTROL_RELEASE_RUNNING = 0x0004,
80  ACK_SETCONTROL_IOC = 0x00C9,
81 
82 };
83 
84 enum ACK_ARM_CODE
85 {
86  ACK_ARM_SUCCESS = 0x0000,
87  ACK_ARM_NEED_CONTROL = 0x0001,
88  ACK_ARM_ALREADY_ARMED = 0x0002,
89  ACK_ARM_IN_AIR = 0x0003,
90 };
91 
92 enum TASK_ACK_CODE
93 {
94  TASK_FAILURE = 0x01,
95  TASK_SUCCESS = 0x02
96 };
97 
98 
100 
102 {
103  SET_ACTIVATION = 0x00,
104  SET_CONTROL = 0x01,
105  SET_BROADCAST = 0x02,
106  SET_MISSION = 0x03,
107  SET_SYNC = 0x04,
108  SET_VIRTUALRC = 0x05
109 };
110 
111 enum SYNC_CODE
112 {
113  CODE_SYNC_BROADCAST = 0x00
114 };
115 
116 enum HOTPOINT_CODE
117 {
118  CODE_HOTPOINT_START = 0x20,
119  CODE_HOTPOINT_STOP = 0x21,
120  CODE_HOTPOINT_SETPAUSE = 0x22,
121  CODE_HOTPOINT_YAWRATE = 0x23,
122  CODE_HOTPOINT_RADIUS = 0x24,
123  CODE_HOTPOINT_SETYAW = 0x25,
124  CODE_HOTPOINT_LOAD = 0x26
125 };
126 
127 enum FOLLOW_CODE
128 {
129  CODE_FOLLOW_START = 0x30,
130  CODE_FOLLOW_STOP = 0x31,
131  CODE_FOLLOW_SETPAUSE = 0X32,
132  CODE_FOLLOW_TARGET = 0X33
133 };
134 
135 enum WAYPOINT_CODE
136 {
137  CODE_WAYPOINT_INIT = 0x10,
138  CODE_WAYPOINT_ADDPOINT = 0x11,
139  CODE_WAYPOINT_SETSTART = 0x12,
140  CODE_WAYPOINT_SETPAUSE = 0x13,
141  CODE_WAYPOINT_DOWNLOAD = 0x14,
142  CODE_WAYPOINT_INDEX = 0x15,
143  CODE_WAYPOINT_SETVELOCITY = 0x16,
144  CODE_WAYPOINT_GETVELOCITY = 0x17,
145 };
146 
147 enum ACTIVATION_CODE
148 {
149  CODE_GETVERSION = 0,
150  CODE_ACTIVATE = 1,
151  CODE_FREQUENCY = 0x10,
152  CODE_TOMOBILE = 0xFE
153 };
154 
155 enum CONTROL_CODE
156 {
157  CODE_SETCONTROL = 0,
158  CODE_TASK = 1,
159  CODE_STATUS = 2,
160  CODE_CONTROL = 3,
161  CODE_SETARM = 5,
162 };
163 
164 enum BROADCAST_CODE
165 {
166  CODE_BROADCAST = 0x00,
167  CODE_LOSTCTRL = 0x01,
168  CODE_FROMMOBILE = 0x02,
169  CODE_MISSION = 0x03,
170  CODE_WAYPOINT = 0x04
171 };
172 
173 enum VIRTUALRC_CODE
174 {
175  CODE_VIRTUALRC_SETTINGS,
176  CODE_VIRTUALRC_DATA
177 };
178 
179 enum MISSION_TYPE
180 {
181  MISSION_MODE_A,
182  MISSION_WAYPOINT,
183  MISSION_HOTPOINT,
184  MISSION_FOLLOW,
185  MISSION_IOC
186 };
187 
188 enum BROADCAST_FREQ
189 {
190  BROADCAST_FREQ_0HZ = 0,
191  BROADCAST_FREQ_1HZ = 1,
192  BROADCAST_FREQ_10HZ = 2,
193  BROADCAST_FREQ_50HZ = 3,
194  BROADCAST_FREQ_100HZ = 4,
195  BROADCAST_FREQ_HOLD = 5,
196 };
197 
199 
210 class CoreAPI
211 {
212  public:
213  CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false,
214  CallBack userRecvCallback = 0, UserData userData = 0);
215  CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback,
216  bool userCallbackThread = false);
217  void sendPoll(void);
218  void readPoll(void);
220  void callbackPoll(void);
221 
223  void byteHandler(const uint8_t in_data);
225  void byteStreamHandler(uint8_t *buffer, size_t size);
226 
227  void ack(req_id_t req_id, unsigned char *ackdata, int len);
228 
230  void notifyCaller(Header *protocolHeader);
231 
233 
242  void send(unsigned char session_mode, unsigned char is_enc, CMD_SET cmd_set,
243  unsigned char cmd_id, void *pdata, int len, CallBack ack_callback,
245  int timeout = 0, int retry_time = 1);
246  void send(unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id,
247  void *pdata, size_t len, int timeout = 0, int retry_time = 1,
248  CallBack ack_handler = 0,
250  UserData userData = 0);
251 
253  void send(Command *parameter);
255 
257 
265  void activate(ActivateData *data, CallBack callback = 0, UserData userData = 0);
266 
268 
283  unsigned short activate(ActivateData *data, int timeout);
284 
285  void setControl(bool enable, CallBack callback = 0, UserData userData = 0);
286 
288 
300  unsigned short setControl(bool enable, int timeout);
301 
303 
307  void setActivation(bool isActivated);
308 
310 
314 
316  void setAccountData(const ActivateData &value);
317 
318  void sendToMobile(uint8_t *data, uint8_t len, CallBack callback = 0, UserData userData = 0);
319 
339  void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback = 0, UserData userData = 0);
340  unsigned short setBroadcastFreq(uint8_t *dataLenIs16, int timeout);
341 
346 
359  unsigned short setBroadcastFreqDefaults(int timeout);
360 
361  /*
362  * Set all broadcast frequencies to zero. Only ACK data will stay on the line.
363  */
364  void setBroadcastFreqToZero();
365 
369  void setACKFrameStatus(uint32_t usageFlag);
370  uint32_t getACKFrameStatus();
371  void setBroadcastFrameStatus(bool isFrame);
372  bool getBroadcastFrameStatus();
373 
374  void setSyncFreq(uint32_t freqInHz);
375  void setKey(const char *key);
376 
378 
384  void getDroneVersion(CallBack callback = 0, UserData userData = 0);
385 
399  VersionData getDroneVersion(int timeout);
400 
403 
411  TimeStampData getTime() const;
412 
416  FlightStatus getFlightStatus() const;
417  CtrlInfoData getCtrlInfo() const;
418 
427  BatteryData getBatteryCapacity() const;
429 
430 
434  HardDriver *getDriver() const;
435 
439  Version getSDKVersion() const;
440  void setBroadcastCallback(CallBackHandler callback) { broadcastCallback = callback; }
441  void setFromMobileCallback(CallBackHandler FromMobileEntrance);
442 
443  void setBroadcastCallback(CallBack handler, UserData userData = 0);
444  void setFromMobileCallback(CallBack handler, UserData userData = 0);
445 
446  void setMisssionCallback(CallBackHandler callback) { missionCallback = callback; }
447  void setHotPointCallback(CallBackHandler callback) { hotPointCallback = callback; }
448  void setWayPointCallback(CallBackHandler callback) { wayPointCallback = callback; }
449  void setFollowCallback(CallBackHandler callback) { followCallback = callback; }
450  void setWayPointEventCallback(CallBackHandler callback);
451 
452  void setMisssionCallback(CallBack handler, UserData userData = 0);
453  void setHotPointCallback(CallBack handler, UserData userData = 0);
454  void setWayPointCallback(CallBack handler, UserData userData = 0);
455  void setFollowCallback(CallBack handler, UserData userData = 0);
456  void setWayPointEventCallback(CallBack handler, UserData userData = 0);
457 
458 
459  static void activateCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
460  static void getDroneVersionCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
461  static void setControlCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
462  static void sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
463  static void setFrequencyCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
464 
472  void parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
473 
477  void setObtainControlMobileCallback(CallBackHandler callback) {obtainControlMobileCallback = callback;}
478  void setReleaseControlMobileCallback(CallBackHandler callback) {releaseControlMobileCallback = callback;}
479  void setActivateMobileCallback(CallBackHandler callback) {activateMobileCallback = callback;}
480  void setArmMobileCallback(CallBackHandler callback) {armMobileCallback = callback;}
481  void setDisArmMobileCallback(CallBackHandler callback) {disArmMobileCallback = callback;}
482  void setTakeOffMobileCallback(CallBackHandler callback) {takeOffMobileCallback = callback;}
483  void setLandingMobileCallback(CallBackHandler callback) {landingMobileCallback = callback;}
484  void setGoHomeMobileCallback(CallBackHandler callback) {goHomeMobileCallback = callback;}
485  void setTakePhotoMobileCallback(CallBackHandler callback) {takePhotoMobileCallback = callback;}
486  void setStartVideoMobileCallback(CallBackHandler callback) {startVideoMobileCallback = callback;}
487  void setStopVideoMobileCallback(CallBackHandler callback) {stopVideoMobileCallback = callback;}
488 
492  bool decodeACKStatus(unsigned short ack);
493 
497  bool decodeMissionStatus(uint8_t ack);
498 
502  bool stopCond;
503 
508  uint32_t ack_data;
509  HotPointReadACK hotpointReadACK;
510  WayPointInitACK waypointInitACK;
511  MissionACKUnion missionACKUnion;
512 
514 
517  SDKFilter getFilter() const;
518 
520  bool getHotPointData() const;
521 
523  bool getWayPointData() const;
524 
525  // FollowMe mission Control
526  bool getFollowData() const;
527 
529  void setHotPointData(bool value);
530 
532  void setWayPointData(bool value);
533 
535  void setFollowData(bool value);
536 
540  void setDriver(HardDriver *value);
541 
545  void setVersion(const Version &value);
546 
550  bool getObtainControlMobileCMD() {return obtainControlMobileCMD;}
551  bool getReleaseControlMobileCMD() {return releaseControlMobileCMD;}
552  bool getActivateMobileCMD() {return activateMobileCMD;}
553  bool getArmMobileCMD() {return armMobileCMD;}
554  bool getDisArmMobileCMD() {return disArmMobileCMD;}
555  bool getTakeOffMobileCMD() {return takeOffMobileCMD;}
556  bool getLandingMobileCMD() {return landingMobileCMD;}
557  bool getGoHomeMobileCMD() {return goHomeMobileCMD;}
558  bool getTakePhotoMobileCMD() {return takePhotoMobileCMD;}
559  bool getStartVideoMobileCMD() {return startVideoMobileCMD;}
560  bool getStopVideoMobileCMD() {return stopVideoMobileCMD;}
561  bool getFollowMeMobileCMD() {return followMeMobileCMD;}
562 
563  void setObtainControlMobileCMD(bool userInput) {obtainControlMobileCMD = userInput;}
564  void setReleaseControlMobileCMD(bool userInput) {releaseControlMobileCMD= userInput;}
565  void setActivateMobileCMD(bool userInput) {activateMobileCMD= userInput;}
566  void setArmMobileCMD(bool userInput) {armMobileCMD= userInput;}
567  void setDisArmMobileCMD(bool userInput) {disArmMobileCMD= userInput;}
568  void setTakeOffMobileCMD(bool userInput) {takeOffMobileCMD= userInput;}
569  void setLandingMobileCMD(bool userInput) {landingMobileCMD= userInput;}
570  void setGoHomeMobileCMD(bool userInput) {goHomeMobileCMD= userInput;}
571  void setTakePhotoMobileCMD(bool userInput) {takePhotoMobileCMD= userInput;}
572  void setStartVideoMobileCMD(bool userInput) {startVideoMobileCMD= userInput;}
573  void setStopVideoMobileCMD(bool userInput) {stopVideoMobileCMD= userInput;}
574  void setFollowMeMobileCMD(bool userInput) {followMeMobileCMD= userInput;}
575 
576 
577  private:
578  BroadcastData broadcastData;
579  uint32_t ackFrameStatus;
580  bool broadcastFrameStatus;
581  unsigned char encodeSendData[BUFFER_SIZE];
582  unsigned char encodeACK[ACK_SIZE];
583 
584 // uint8_t cblistTail;
585 // CallBackHandler cbList[CALLBACK_LIST_NUM];
586 
587  CallBackHandler fromMobileCallback;
588  CallBackHandler broadcastCallback;
589  CallBackHandler hotPointCallback;
590  CallBackHandler wayPointCallback;
591  CallBackHandler wayPointEventCallback;
592  CallBackHandler followCallback;
593  CallBackHandler missionCallback;
594  CallBackHandler recvCallback;
595 
596  CallBackHandler obtainControlMobileCallback;
597  CallBackHandler releaseControlMobileCallback;
598  CallBackHandler activateMobileCallback;
599  CallBackHandler armMobileCallback;
600  CallBackHandler disArmMobileCallback;
601  CallBackHandler takeOffMobileCallback;
602  CallBackHandler landingMobileCallback;
603  CallBackHandler goHomeMobileCallback;
604  CallBackHandler takePhotoMobileCallback;
605  CallBackHandler startVideoMobileCallback;
606  CallBackHandler stopVideoMobileCallback;
607 
608  bool obtainControlMobileCMD;
609  bool releaseControlMobileCMD;
610  bool activateMobileCMD;
611  bool armMobileCMD;
612  bool disArmMobileCMD;
613  bool takeOffMobileCMD;
614  bool landingMobileCMD;
615  bool goHomeMobileCMD;
616  bool takePhotoMobileCMD;
617  bool startVideoMobileCMD;
618  bool stopVideoMobileCMD;
619  bool followMeMobileCMD;
620 
621  VersionData versionData;
622  ActivateData accountData;
623 
624  unsigned short seq_num;
625  unsigned char *version_ack_data;
626 
627  SDKFilter filter;
628 
630  void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread,
631  Version SDKVersion);
632  void recvReqData(Header *protocolHeader);
633  void appHandler(Header *protocolHeader);
634  void broadcast(Header *protocolHeader);
635 
636  int sendInterface(Command *parameter);
637  int ackInterface(Ack *parameter);
638  void sendData(unsigned char *buf);
639  void setup(void);
640  void setupMMU(void);
641  void setupSession(void);
642 
643  MMU_Tab *allocMemory(unsigned short size);
644 
645  void freeSession(CMDSession *session);
646  CMDSession *allocSession(unsigned short session_id, unsigned short size);
647 
648  void freeACK(ACKSession *session);
649  ACKSession *allocACK(unsigned short session_id, unsigned short size);
650  MMU_Tab MMU[MMU_TABLE_NUM];
651  CMDSession CMDSessionTab[SESSION_TABLE_NUM];
652  ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
653  unsigned char memory[MEMORY_SIZE];
654  unsigned short encrypt(unsigned char *pdest, const unsigned char *psrc,
655  unsigned short w_len, unsigned char is_ack, unsigned char is_enc,
656  unsigned char session_id, unsigned short seq_num);
657 
658  void streamHandler(SDKFilter *p_filter, unsigned char in_data);
659  void checkStream(SDKFilter *p_filter);
660  void verifyHead(SDKFilter *p_filter);
661  void verifyData(SDKFilter *p_filter);
662  void callApp(SDKFilter *p_filter);
663  void storeData(SDKFilter *p_filter, unsigned char in_data);
664 public:
665  HardDriver *serialDevice;
666 private:
667  bool callbackThread;
668  bool hotPointData;
669  bool wayPointData;
670  bool followData;
671 
672 #ifdef API_BUFFER_DATA
673  public:
674  void setTotalRead(const size_t &value) { totalRead = value; }
675  void setOnceRead(const size_t &value) { onceRead = value; }
676 
677  size_t getTotalRead() const { return totalRead; }
678  size_t getOnceRead() const { return onceRead; }
679 
680  private:
681  size_t onceRead;
682  size_t totalRead;
683 #endif // API_BUFFER_DATA
684 };
685 
686 } // namespace onboardSDK
687 } // namespace DJI
688 
689 #endif // DJI_API_H
TimeStampData getTime() const
Definition: DJI_API.cpp:417
-
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:89
-
BroadcastData getBroadcastData() const
Definition: DJI_App.cpp:45
-
void getDroneVersion(CallBack callback=0, UserData userData=0)
Definition: DJI_API.cpp:156
-
HardDriver * getDriver() const
Definition: DJI_API.cpp:457
-
Definition: DJI_Type.h:604
-
ACK_ERROR_CODE
Definition: DJI_API.h:45
-
void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)
Definition: DJI_API.cpp:253
-
void(* CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData)
The CallBack function pointer is used as an argument in api->send calls.
Definition: DJI_Type.h:142
-
void setWayPointData(bool value)
WayPoint Mission Control.
Definition: DJI_API.cpp:431
-
Definition: DJI_Type.h:334
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
Definition: DJI_Type.h:468
-
Definition: DJI_HardDriver.h:24
-
Definition: DJI_Type.h:184
-
Definition: DJI_App.h:25
-
ActivateData getAccountData() const
Activation Control.
Definition: DJI_API.cpp:427
-
Definition: DJI_Type.h:198
-
void setHotPointData(bool value)
HotPoint Mission Control.
Definition: DJI_API.cpp:430
-
Type definition for DJI onboardSDK library. Officially Maintained.
-
bool getHotPointData() const
HotPoint Mission Control.
Definition: DJI_API.cpp:433
-
Definition: DJI_Type.h:176
-
uint32_t Version
Different version strings define SDK/Drone combination. Only the ones listed below are available...
Definition: DJI_Version.h:33
-
CMD_SET
Definition: DJI_API.h:101
-
void setBroadcastFreqDefaults()
Definition: DJI_API.cpp:311
-
Definition: DJI_Type.h:595
-
bool stopCond
Definition: DJI_API.h:502
-
Version getSDKVersion() const
Definition: DJI_API.cpp:726
-
uint32_t ack_data
Definition: DJI_API.h:508
-
Definition: DJI_Type.h:164
-
void setObtainControlMobileCallback(CallBackHandler callback)
Definition: DJI_API.h:477
-
void notifyCaller(Header *protocolHeader)
Notify caller ACK frame arrived.
Definition: DJI_Link.cpp:138
-
void activate(ActivateData *data, CallBack callback=0, UserData userData=0)
Activation Control.
Definition: DJI_API.cpp:205
-
void setFollowData(bool value)
Follow Me Mission Control.
Definition: DJI_API.cpp:432
-
void parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0)
Definition: DJI_API.cpp:562
+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
+
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
+
Definition: DJI_App.h:50
+
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
+
Definition: DJI_App.h:26
+
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 getSDKVersion() 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:159
-
Definition: DJI_Type.h:206
-
BatteryData getBatteryCapacity() const
Definition: DJI_App.cpp:47
-
Definition: DJI_Type.h:151
+
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 * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
-
void callbackPoll(void)
Definition: DJI_Link.cpp:222
-
Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for ind...
-
The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.
Definition: DJI_Type.h:145
-
The Header struct is meant to handle the open protocol header.
Definition: DJI_Type.h:122
-
FlightStatus getFlightStatus() const
Definition: DJI_API.cpp:419
+
void callbackPoll(void)
Definition: DJI_Link.cpp:194
+ +
Definition: DJI_Type.h:139
+
Definition: DJI_Type.h:118
+
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:730
-
Definition: DJI_Type.h:351
-
void setDriver(HardDriver *value)
Definition: DJI_API.cpp:459
+
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:434
-
Definition: DJI_Type.h:537
-
void setActivation(bool isActivated)
Activation Control.
Definition: DJI_Link.cpp:236
-
Application layer support functionality for DJI onboardSDK library.
-
Definition: DJI_Type.h:345
-
void setACKFrameStatus(uint32_t usageFlag)
Definition: DJI_Link.cpp:244
-
Definition: DJI_Type.h:458
-
bool getObtainControlMobileCMD()
Definition: DJI_API.h:550
-
void setAccountData(const ActivateData &value)
Activation Control.
Definition: DJI_API.cpp:429
-
SDKFilter getFilter() const
Open Protocol Control.
Definition: DJI_API.cpp:728
+
bool getWayPointData() const
WayPoint Mission Control.
Definition: DJI_API.cpp:235
+
Definition: DJI_App.h:59
+
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
diff --git a/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html index 6ea828ac..2e935b85 100644 --- a/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html @@ -92,9 +92,6 @@
DJI_App.cpp File Reference
- -

Application layer support functionality for DJI onboardSDK library. -More...

#include <string.h>
#include <stdio.h>
#include "DJI_App.h"
@@ -112,9 +109,9 @@
 

Detailed Description

-

Application layer support functionality for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
Jul 01 2016
+

Developer App support functionality for DJI onboardSDK library

Copyright 2016 DJI. All right reserved.

Function Documentation

@@ -179,7 +176,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__App_8h.html b/dji_sdk_doc/doxygen/html/DJI__App_8h.html index 8a11a5e1..cc65f8d5 100644 --- a/dji_sdk_doc/doxygen/html/DJI__App_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__App_8h.html @@ -88,14 +88,12 @@
DJI_App.h File Reference
- -

Application layer support functionality for DJI onboardSDK library. -More...

#include <stdint.h>
#include "DJI_Link.h"
#include "DJI_Type.h"
@@ -106,6 +104,10 @@ Classes struct  req_id_t   +struct  ActivateData +  +struct  VersionData +  @@ -136,16 +138,38 @@ +

Macros

#define STATUS_CMD_EXE_SUCCESS   0x0005
 
+ + + + +

+Typedefs

typedef struct ActivateData ActivateData
 
+typedef struct VersionData VersionData
 

Detailed Description

-

Application layer support functionality for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
Jul 1, 2016
+

Developer App support functionality for DJI onboardSDK library

Copyright 2016 DJI. All right reserved.

-
+

Typedef Documentation

+ +
+
+ + + + +
typedef struct ActivateData ActivateData
+
+
Todo:
move to type.h
+ +
+
+
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 36161fe0..7c488d82 100644 --- a/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html @@ -90,13 +90,17 @@
DJI_App.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_APP_H
13 #define DJI_APP_H
14 
15 #include <stdint.h>
16 
17 #include "DJI_Link.h"
18 #include "DJI_Type.h"
19 
20 #define MSG_ENABLE_FLAG_LEN 2
21 
22 //----------------------------------------------------------------------
23 // App layer function
24 //----------------------------------------------------------------------
25 typedef struct
26 {
27  unsigned short sequence_number;
28  unsigned char session_id : 5;
29  unsigned char need_encrypt : 1;
30  unsigned char reserve : 2;
31 } req_id_t;
32 
33 #define EXC_DATA_SIZE (16u)
34 #define SET_CMD_SIZE (2u)
35 
36 //----------------------------------------------------------------------
37 // for cmd agency
38 //----------------------------------------------------------------------
39 #define REQ_TIME_OUT 0x0000
40 #define REQ_REFUSE 0x0001
41 #define CMD_RECIEVE 0x0002
42 #define STATUS_CMD_EXECUTING 0x0003
43 #define STATUS_CMD_EXE_FAIL 0x0004
44 #define STATUS_CMD_EXE_SUCCESS 0x0005
45 
46 
47 #endif // DJI_APP_H
Definition: DJI_App.h:25
-
Type definition for DJI onboardSDK library. Officially Maintained.
- +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
+
Definition: DJI_App.h:26
+ +
uint32_t Version
Definition: DJI_Version.h:34
+ +
struct ActivateData ActivateData
+
Definition: DJI_App.h:59
diff --git a/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html index 4ad605e7..5efb64a8 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html @@ -90,19 +90,16 @@
DJI_Camera.cpp File Reference
- -

Camera/Gimbal API for DJI onboardSDK library. -More...

#include "DJI_Camera.h"

Detailed Description

-

Camera/Gimbal API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Camera/Gimbal API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html b/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html index cf811bf9..c13897c9 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html @@ -93,9 +93,6 @@
DJI_Camera.h File Reference
- -

Camera/Gimbal API for DJI onboardSDK library. -More...

#include "DJI_API.h"

Go to the source code of this file.

@@ -103,7 +100,6 @@

Classes

class  DJI::onboardSDK::CameraCamera class for controlling camera and gimbal-related functions available through open protocol. More...
 

@@ -112,14 +108,14 @@

 

Detailed Description

-

Camera/Gimbal API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Camera/Gimbal API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__Camera_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Camera_8h_source.html index 8695372e..e288ffe6 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Camera_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Camera_8h_source.html @@ -90,19 +90,19 @@
DJI_Camera.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_CAMERA_H
13 #define DJI_CAMERA_H
14 
15 #include "DJI_API.h"
16 
17 namespace DJI
18 {
19 namespace onboardSDK
20 {
22 class Camera
23 {
24  public:
25  enum CAMERA_CODE
26  {
27  CODE_GIMBAL_SPEED = 0x1A,
28  CODE_GIMBAL_ANGLE = 0x1B,
29  CODE_CAMERA_SHOT = 0x20,
30  CODE_CAMERA_VIDEO_START = 0x21,
31  CODE_CAMERA_VIDEO_STOP = 0x22
32  };
33 
34  public:
35  Camera(CoreAPI *ControlAPI = 0);
36 
39  void setCamera(CAMERA_CODE camera_cmd);
40  void setGimbalAngle(GimbalAngleData *data);
41  void setGimbalSpeed(GimbalSpeedData *data);
42 
43  GimbalData getGimbal() const;
44  float32_t getYaw() const;
45  float32_t getRoll() const;
46  float32_t getPitch() const;
47  bool isYawLimit() const;
48  bool isRollLimit() const;
49  bool isPitchLimit() const;
50 
51  public:
52  CoreAPI *getApi() const;
53  void setApi(CoreAPI *value);
54 
55  private:
56  CoreAPI *api;
57 };
58 } // namespace onboardSDK
59 } // namespace DJI
60 
61 #endif // DJI_CAMERA_H
Definition: DJI_Type.h:222
+Go to the documentation of this file.
1 
13 #ifndef DJI_CAMERA_H
14 #define DJI_CAMERA_H
15 
16 #include "DJI_API.h"
17 
18 namespace DJI
19 {
20 namespace onboardSDK
21 {
22 class Camera
23 {
24  public:
25  enum CAMERA_CODE
26  {
27  CODE_GIMBAL_SPEED = 0x1A,
28  CODE_GIMBAL_ANGLE = 0x1B,
29  CODE_CAMERA_SHOT = 0x20,
30  CODE_CAMERA_VIDEO_START = 0x21,
31  CODE_CAMERA_VIDEO_STOP = 0x22
32  };
33 
34  public:
35  Camera(CoreAPI *ControlAPI = 0);
36 
39  void setCamera(CAMERA_CODE camera_cmd);
40  void setGimbalAngle(GimbalAngleData *data);
41  void setGimbalSpeed(GimbalSpeedData *data);
42 
43  GimbalData getGimbal() const;
44  float32_t getYaw() const;
45  float32_t getRoll() const;
46  float32_t getPitch() const;
47  bool isYawLimit() const;
48  bool isRollLimit() const;
49  bool isPitchLimit() const;
50 
51  public:
52  CoreAPI *getApi() const;
53  void setApi(CoreAPI *value);
54 
55  private:
56  CoreAPI *api;
57 };
58 } // namespace onboardSDK
59 } // namespace DJI
60 
61 #endif // DJI_CAMERA_H
Definition: DJI_Type.h:214
Core API for DJI onboardSDK library.
-
Definition: DJI_Type.h:231
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
Definition: DJI_Type.h:476
-
Camera class for controlling camera and gimbal-related functions available through open protocol...
Definition: DJI_Camera.h:22
+
Definition: DJI_Type.h:223
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
+
Definition: DJI_Type.h:353
+
Definition: DJI_Camera.h:22
Definition: DJI_Mission.cpp:16
-
void setCamera(CAMERA_CODE camera_cmd)
Definition: DJI_Camera.cpp:18
-
CoreAPI * getApi() const
Definition: DJI_Camera.cpp:65
+
void setCamera(CAMERA_CODE camera_cmd)
Definition: DJI_Camera.cpp:19
+
CoreAPI * getApi() const
Definition: DJI_Camera.cpp:66
diff --git a/dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html index 29ef56a3..f2b3c559 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html @@ -317,7 +317,7 @@

Variable Documentation

diff --git a/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html b/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html index 7658fa42..db46184d 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html @@ -93,9 +93,6 @@
DJI_Codec.h File Reference
- -

Encoding/Message parsing features for DJI onboardSDK library. -More...

#include <stdlib.h>
#include <stdio.h>
#include <string.h>
@@ -144,14 +141,29 @@  

Detailed Description

-

Encoding/Message parsing features for DJI onboardSDK library.

-
Version
3.1.7
-
Date
July 1st, 2016
- +
Version
3.0
+
Date
Dec 16, 2015
+

Encode functions for DJI onboardSDK library

+
Attention
Project configuration:
+
Todo:
spilt this header into 4 header files
+
Version
features: -*
+
+V3.0 -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake -*
+
Date
Dec 16, 2015 -*
+
Author
william.wu
+
Version
3.0
+
Date
Dec 16, 2015
+

Mission framework for DJI onboardSDK library

+
Attention
Project configuration:
+
Version
features: -*
+
+V3.0 -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake -*
+
Date
Dec 16, 2015 -*
+
Author
william.wu
diff --git a/dji_sdk_doc/doxygen/html/DJI__Codec_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Codec_8h_source.html index 6e5c712d..ba6d0e8b 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Codec_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Codec_8h_source.html @@ -90,11 +90,11 @@
DJI_Codec.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_CODEC_H
13 #define DJI_CODEC_H
14 
15 #include <stdlib.h>
16 #include <stdio.h>
17 #include <string.h>
18 #include <memory>
19 #include "DJI_Type.h"
20 
21 #define _SDK_MAX_RECV_SIZE (BUFFER_SIZE)
22 #define _SDK_SOF ((unsigned char)(0xAA))
23 #define _SDK_CRC_HEAD_SIZE (2) // CRC16
24 #define _SDK_CRC_DATA_SIZE (4) // CRC32
25 #define _SDK_HEAD_DATA_LEN (sizeof(DJI::onboardSDK::Header) - 2)
26 #define _SDK_FULL_DATA_SIZE_MIN (sizeof(DJI::onboardSDK::Header) + _SDK_CRC_DATA_SIZE)
27 
28 #define _SDK_U32_SET(_addr, _val) (*((unsigned int *)(_addr)) = (_val))
29 #define _SDK_U16_SET(_addr, _val) (*((unsigned short *)(_addr)) = (_val))
30 
31 #define _SDK_CALC_CRC_HEAD(_msg, _len) \
32  sdk_stream_crc16_calc((const unsigned char *)(_msg), _len)
33 #define _SDK_CALC_CRC_TAIL(_msg, _len) \
34  sdk_stream_crc32_calc((const unsigned char *)(_msg), _len)
35 
36 
37 void transformTwoByte(const char *pstr, unsigned char *pdata);
38 
39 #endif // DJI_CODEC_H
Type definition for DJI onboardSDK library. Officially Maintained.
+Go to the documentation of this file.
1 
22 #ifndef DJI_CODEC_H
23 #define DJI_CODEC_H
24 
25 #include <stdlib.h>
26 #include <stdio.h>
27 #include <string.h>
28 #include <memory>
29 #include "DJI_Type.h"
30 
31 #define _SDK_MAX_RECV_SIZE (BUFFER_SIZE)
32 #define _SDK_SOF ((unsigned char)(0xAA))
33 #define _SDK_CRC_HEAD_SIZE (2) // CRC16
34 #define _SDK_CRC_DATA_SIZE (4) // CRC32
35 #define _SDK_HEAD_DATA_LEN (sizeof(DJI::onboardSDK::Header) - 2)
36 #define _SDK_FULL_DATA_SIZE_MIN (sizeof(DJI::onboardSDK::Header) + _SDK_CRC_DATA_SIZE)
37 
38 #define _SDK_U32_SET(_addr, _val) (*((unsigned int *)(_addr)) = (_val))
39 #define _SDK_U16_SET(_addr, _val) (*((unsigned short *)(_addr)) = (_val))
40 
41 #define _SDK_CALC_CRC_HEAD(_msg, _len) \
42  sdk_stream_crc16_calc((const unsigned char *)(_msg), _len)
43 #define _SDK_CALC_CRC_TAIL(_msg, _len) \
44  sdk_stream_crc32_calc((const unsigned char *)(_msg), _len)
45 
46 
47 void transformTwoByte(const char *pstr, unsigned char *pdata);
48 
49 #endif // DJI_CODEC_H
diff --git a/dji_sdk_doc/doxygen/html/DJI__Config_8h.html b/dji_sdk_doc/doxygen/html/DJI__Config_8h.html index 7b48ceb0..b0945ce4 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Config_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Config_8h.html @@ -92,9 +92,6 @@
DJI_Config.h File Reference
- -

Optional macro definitions for DJI Onboard SDK. Use for debugging. -More...

#include <stdint.h>
#include "DJI_Version.h"
@@ -112,7 +109,6 @@ #define ACK_SIZE   10   #define API_ERROR_DATA - Uncomment these macros to access various messages from the API. More...
  #define API_STATUS_DATA @@ -121,10 +117,15 @@  

Detailed Description

-

Optional macro definitions for DJI Onboard SDK. Use for debugging.

-
Version
3.1.7
-
Date
Jul 01 2016
- +
Version
3.0
+
Date
Dec 16, 2015
+

Configuration optional Micro definitions for DJI onboardSDK library.

+
Attention
Project configuration: None
+
Version
features: -*
+
+V3.0 -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake -*
+
Date
Dec 16, 2015 -*
+
Author
william.wu

Macro Definition Documentation

@@ -135,10 +136,8 @@
- -

Uncomment these macros to access various messages from the API.

-
Note
The static memory flag means DJI onboardSDK library will not alloc memory from heap.
-
Todo:
Not supported in this release.
+
Note
it means DJI onboardSDK library will not alloc memory from heap.
+
Todo:
not available yet, only affect WayPoint
@@ -151,14 +150,14 @@
-
Note
if you do NOT want to use AES encrypt, comment this macro below
+
Note
if you do not want to use AES encrypt, comment this micro below
diff --git a/dji_sdk_doc/doxygen/html/DJI__Config_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Config_8h_source.html index a4a18b0f..ccb101a8 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Config_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Config_8h_source.html @@ -90,11 +90,11 @@
DJI_Config.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_CONFIG_H
13 #define DJI_CONFIG_H
14 
15 #include <stdint.h>
16 #define MEMORY_SIZE 1024 // unit is byte
17 #define BUFFER_SIZE 1024
18 #define ACK_SIZE 10
19 
22 
23 //#define STATIC_MEMORY
24 
26 
27 //#define API_MISSION_DATA
28 //#define API_DEBUG_DATA
29 //#define API_BUFFER_DATA
30 //#define API_RTK_DEBUG
31 #define API_ERROR_DATA
32 #define API_STATUS_DATA
33 
35 #define USE_ENCRYPT
36 
38 //#define USE_SIMULATION
39 
40 #include "DJI_Version.h"
41 
42 #endif // DJI_CONFIG_H
Drone/SDK Version definition for DJI onboardSDK library Officially Maintained.
+Go to the documentation of this file.
1 
21 #ifndef DJI_CONFIG_H
22 #define DJI_CONFIG_H
23 
24 #include <stdint.h>
25 #define MEMORY_SIZE 1024 // unit is byte
26 #define BUFFER_SIZE 1024
27 #define ACK_SIZE 10
28 
31 //#define STATIC_MEMORY
32 
33 //#define API_MISSION_DATA
34 //#define API_DEBUG_DATA
35 //#define API_BUFFER_DATA
36 //#define API_RTK_DEBUG
37 #define API_ERROR_DATA
38 #define API_STATUS_DATA
39 
41 #define USE_ENCRYPT
42 //#define USE_SIMULATION
43 
44 #include "DJI_Version.h"
45 
46 #endif // DJI_CONFIG_H
diff --git a/dji_sdk_doc/doxygen/html/DJI__Flight_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Flight_8cpp.html index f68f3c5e..ef7a61b1 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Flight_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Flight_8cpp.html @@ -104,7 +104,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__Flight_8h.html b/dji_sdk_doc/doxygen/html/DJI__Flight_8h.html index c8fb7b98..bd5dcbb0 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Flight_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Flight_8h.html @@ -128,7 +128,7 @@ diff --git a/dji_sdk_doc/doxygen/html/DJI__Flight_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Flight_8h_source.html index 384bf13c..c5cb2eef 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Flight_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Flight_8h_source.html @@ -90,31 +90,29 @@
DJI_Flight.h
-Go to the documentation of this file.
1 
11 #ifndef DJI_FLIGHT_H
12 #define DJI_FLIGHT_H
13 
14 #include "DJI_API.h"
15 
16 namespace DJI
17 {
18 namespace onboardSDK
19 {
20 #pragma pack(1)
21 
22 typedef struct FlightData
23 {
24  uint8_t flag;
25  float32_t x;
26  float32_t y;
27  float32_t z;
28  float32_t yaw;
29 } FlightData;
30 
31 #pragma pack()
32 
34 class Flight
35 {
36  public:
37  enum TASK
38  {
39  TASK_GOHOME = 1,
40  TASK_TAKEOFF = 4,
41  TASK_LANDING = 6
42  };
43 
44  enum VerticalLogic
45  {
46  VERTICAL_VELOCITY = 0x00,
47  VERTICAL_POSITION = 0x10,
48  VERTICAL_THRUST = 0x20,
49  };
50 
51  enum HorizontalLogic
52  {
53  HORIZONTAL_ANGLE = 0x00,
54  HORIZONTAL_VELOCITY = 0x40,
55  HORIZONTAL_POSITION = 0X80,
56  };
57 
58  enum YawLogic
59  {
60  YAW_ANGLE = 0x00,
61  YAW_RATE = 0x08
62  };
63 
64  enum HorizontalCoordinate
65  {
66  HORIZONTAL_GROUND = 0x00,
67  HORIZONTAL_BODY = 0x02
68  };
69 
72  {
73  YAW_GROUND = 0x00,
74  YAW_BODY = 0X01
75  };
78  {
79  SMOOTH_DISABLE = 0x00,
80  SMOOTH_ENABLE = 0x01
81  };
82 
83  enum Status
84  {
85  STATUS_GROUND_STANDBY = 1,
86  STATUS_TAKE_OFF = 2,
87  STATUS_SKY_STANDBY = 3,
88  STATUS_LANDING = 4,
89  STATUS_FINISHING_LANDING = 5,
90  };
91 
92 
93  enum Device
94  {
95  DEVICE_RC = 0,
96  DEVICE_APP = 1,
97  DEVICE_SDK = 2,
98  };
99 
101  enum Mode
102  {
103  ATTI_STOP = 0,
104  HORIZ_ANG_VERT_VEL_YAW_ANG = 1,
105  HORIZ_ANG_VERT_VEL_YAW_RATE = 2,
106  HORIZ_VEL_VERT_VEL_YAW_ANG = 3,
107  HORIZ_VEL_VERT_VEL_YAW_RATE = 4,
108  HORIZ_POS_VERT_VEL_YAW_ANG = 5,
109  HORIZ_POS_VERT_VEL_YAW_RATE = 6,
110  HORIZ_ANG_VERT_POS_YAW_ANG = 7,
111  HORIZ_ANG_VERT_POS_YAW_RATE = 8,
112  HORIZ_VEL_VERT_POS_YAW_ANG = 9,
113  HORIZ_VEL_VERT_POS_YAW_RATE = 10,
114  HORIZ_POS_VERT_POS_YAW_ANG = 11,
115  HORIZ_POS_VERT_POS_YAW_RATE = 12,
116  HORIZ_ANG_VERT_THR_YAW_ANG = 13,
117  HORIZ_ANG_VERT_THR_YAW_RATE = 14,
118  HORIZ_VEL_VERT_THR_YAW_ANG = 15,
119  HORIZ_VEL_VERT_THR_YAW_RATE = 16,
120  HORIZ_POS_VERT_THR_YAW_ANG = 17,
121  HORIZ_POS_VERT_THR_YAW_RATE = 18,
122  GPS_ATII_CTRL_CL_YAW_RATE = 97,
123  GPS_ATTI_CTRL_YAW_RATE = 98,
124  ATTI_CTRL_YAW_RATE = 99,
125  ATTI_CTRL_STOP = 100,
126  MODE_NOT_SUPPORTED = 0xFF
127  };
128 
137  public:
138  Flight(CoreAPI *ControlAPI = 0);
139 
140  void task(TASK taskname, CallBack TaskCallback = 0, UserData userData = 0);
141  unsigned short task(TASK taskname, int timer);
142  void setArm(bool enable, CallBack ArmCallback = 0, UserData userData = 0);
143  unsigned short setArm(bool enable, int timer);
144  void control(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw);
145  void setMovementControl(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw);
146  void setFlight(FlightData *data);
147 
148  QuaternionData getQuaternion() const;
149 
150  EulerAngle getEulerAngle() const;
151 
152  PositionData getPosition() const;
153  VelocityData getVelocity() const;
155  CommonData getAcceleration() const;
156  CommonData getYawRate() const;
157 
159  MagnetData getMagnet() const;
160 
161  Device getControlDevice() const;
162  Status getStatus() const;
163  Mode getControlMode() const;
164 
165  Angle getYaw() const;
166  Angle getRoll() const;
167  Angle getPitch() const;
168 
169  public:
170  static void armCallback(CoreAPI *api, Header *protoclHeader, UserData userData = 0);
171  static void taskCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
172 
173  public:
174 
176  static EulerianAngle toEulerianAngle(QuaternionData data);
177  static EulerAngle toEulerAngle(QuaternionData quaternionData);
178  static QuaternionData toQuaternion(EulerianAngle eulerAngleData);
179 
180  public:
181  CoreAPI *getApi() const;
182  void setApi(CoreAPI *value);
183 
184  private:
185  CoreAPI *api;
186  TaskData taskData;
187 
194 #ifdef USE_SIMULATION
195  public:
196  bool isSimulating() const;
197  void setSimulating(bool value);
198 
199  private:
200  bool simulating;
201  Vector3dData position;
202  Vector3dData speed;
203  EulerAngle AngularSim;
204 #endif // USE_SIMULATION
205 };
206 
207 } //namespace OnboardSDK
208 } //namespace DJI
209 #endif // DJI_FLIGHT_H
Definition: DJICommonType.h:81
-
Definition: DJI_Type.h:432
-
void(* CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData)
The CallBack function pointer is used as an argument in api->send calls.
Definition: DJI_Type.h:142
+Go to the documentation of this file.
1 
11 #ifndef DJI_FLIGHT_H
12 #define DJI_FLIGHT_H
13 
14 #include "DJI_API.h"
15 
16 namespace DJI
17 {
18 namespace onboardSDK
19 {
20 #pragma pack(1)
21 
22 typedef struct FlightData
23 {
24  uint8_t flag;
25  float32_t x;
26  float32_t y;
27  float32_t z;
28  float32_t yaw;
29 } FlightData;
30 
31 #pragma pack()
32 
34 class Flight
35 {
36  public:
37  enum TASK
38  {
39  TASK_GOHOME = 1,
40  TASK_TAKEOFF = 4,
41  TASK_LANDING = 6
42  };
43 
44  enum VerticalLogic
45  {
46  VERTICAL_VELOCITY = 0x00,
47  VERTICAL_POSITION = 0x10,
48  VERTICAL_THRUST = 0x20,
49  };
50 
51  enum HorizontalLogic
52  {
53  HORIZONTAL_ANGLE = 0x00,
54  HORIZONTAL_VELOCITY = 0x40,
55  HORIZONTAL_POSITION = 0X80,
56  };
57 
58  enum YawLogic
59  {
60  YAW_ANGLE = 0x00,
61  YAW_RATE = 0x08
62  };
63 
64  enum HorizontalCoordinate
65  {
66  HORIZONTAL_GROUND = 0x00,
67  HORIZONTAL_BODY = 0x02
68  };
69 
72  {
73  YAW_GROUND = 0x00,
74  YAW_BODY = 0X01
75  };
78  {
79  SMOOTH_DISABLE = 0x00,
80  SMOOTH_ENABLE = 0x01
81  };
82 
83  enum Status
84  {
85  STATUS_GROUND_STANDBY = 1,
86  STATUS_TAKE_OFF = 2,
87  STATUS_SKY_STANDBY = 3,
88  STATUS_LANDING = 4,
89  STATUS_FINISHING_LANDING = 5,
90  };
91 
92  enum Device
93  {
94  DEVICE_RC = 0,
95  DEVICE_APP = 1,
96  DEVICE_SDK = 2,
97  };
98 
100  enum Mode
101  {
102  ATTI_STOP = 0,
103  HORIZ_ANG_VERT_VEL_YAW_ANG = 1,
104  HORIZ_ANG_VERT_VEL_YAW_RATE = 2,
105  HORIZ_VEL_VERT_VEL_YAW_ANG = 3,
106  HORIZ_VEL_VERT_VEL_YAW_RATE = 4,
107  HORIZ_POS_VERT_VEL_YAW_ANG = 5,
108  HORIZ_POS_VERT_VEL_YAW_RATE = 6,
109  HORIZ_ANG_VERT_POS_YAW_ANG = 7,
110  HORIZ_ANG_VERT_POS_YAW_RATE = 8,
111  HORIZ_VEL_VERT_POS_YAW_ANG = 9,
112  HORIZ_VEL_VERT_POS_YAW_RATE = 10,
113  HORIZ_POS_VERT_POS_YAW_ANG = 11,
114  HORIZ_POS_VERT_POS_YAW_RATE = 12,
115  HORIZ_ANG_VERT_THR_YAW_ANG = 13,
116  HORIZ_ANG_VERT_THR_YAW_RATE = 14,
117  HORIZ_VEL_VERT_THR_YAW_ANG = 15,
118  HORIZ_VEL_VERT_THR_YAW_RATE = 16,
119  HORIZ_POS_VERT_THR_YAW_ANG = 17,
120  HORIZ_POS_VERT_THR_YAW_RATE = 18,
121  GPS_ATII_CTRL_CL_YAW_RATE = 97,
122  GPS_ATTI_CTRL_YAW_RATE = 98,
123  ATTI_CTRL_YAW_RATE = 99,
124  ATTI_CTRL_STOP = 100,
125  MODE_NOT_SUPPORTED = 0xFF
126  };
127 
136  public:
137  Flight(CoreAPI *ControlAPI = 0);
138 
139  void task(TASK taskname, CallBack TaskCallback = 0, UserData userData = 0);
140  void setArm(bool enable, CallBack ArmCallback = 0, UserData userData = 0);
141  void control(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw);
142  void setMovementControl(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw);
143  void setFlight(FlightData *data);
144 
145  QuaternionData getQuaternion() const;
146 
147  EulerAngle getEulerAngle() const;
148 
149  PositionData getPosition() const;
150  VelocityData getVelocity() const;
152  CommonData getAcceleration() const;
153  CommonData getYawRate() const;
154 
156  MagnetData getMagnet() const;
157 
158  Device getControlDevice() const;
159  Status getStatus() const;
160  Mode getControlMode() const;
161 
162  Angle getYaw() const;
163  Angle getRoll() const;
164  Angle getPitch() const;
165 
166  public:
167  static void armCallback(CoreAPI *api, Header *protoclHeader, UserData userData = 0);
168  static void taskCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
169 
170  public:
171 
173  static EulerianAngle toEulerianAngle(QuaternionData data);
174  static EulerAngle toEulerAngle(QuaternionData quaternionData);
175  static QuaternionData toQuaternion(EulerianAngle eulerAngleData);
176 
177  public:
178  CoreAPI *getApi() const;
179  void setApi(CoreAPI *value);
180 
181  private:
182  CoreAPI *api;
183  TaskData taskData;
184 
191 #ifdef USE_SIMULATION
192  public:
193  bool isSimulating() const;
194  void setSimulating(bool value);
195 
196  private:
197  bool simulating;
198  Vector3dData position;
199  Vector3dData speed;
200  EulerAngle AngularSim;
201 #endif // USE_SIMULATION
202 };
203 
204 } //namespace OnboardSDK
205 } //namespace DJI
206 #endif // DJI_FLIGHT_H
Definition: DJICommonType.h:81
+
Definition: DJI_Type.h:309
Core API for DJI onboardSDK library.
YawCoordinate
Definition: DJI_Flight.h:71
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
Definition: DJICommonType.h:60
-
Definition: DJI_Type.h:489
-
Definition: DJI_Type.h:392
+
Definition: DJI_Type.h:366
+
Definition: DJI_Type.h:269
Definition: DJI_Flight.h:22
-
Mode
Definition: DJI_Flight.h:101
+
Mode
Definition: DJI_Flight.h:100
double Angle
Definition: DJICommonType.h:78
SmoothMode
Definition: DJI_Flight.h:77
-
Definition: DJI_Type.h:382
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
-
The Header struct is meant to handle the open protocol header.
Definition: DJI_Type.h:122
+
Definition: DJI_Type.h:259
+
Definition: DJI_Type.h:118
Flight class encapsulates all flight control related functions provided by the DJI OnboardSDK...
Definition: DJI_Flight.h:34
-
Definition: DJI_Type.h:357
+
Definition: DJI_Type.h:234
Definition: DJI_Mission.cpp:16
-
Definition: DJI_Type.h:366
+
Definition: DJI_Type.h:243
Definition: DJICommonType.h:89
diff --git a/dji_sdk_doc/doxygen/html/DJI__Follow_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Follow_8cpp.html index 5879865f..b991de94 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Follow_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Follow_8cpp.html @@ -90,19 +90,16 @@
DJI_Follow.cpp File Reference
- -

Follow API for DJI onboardSDK library. -More...

#include "DJI_Follow.h"

Detailed Description

-

Follow API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Follow API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html b/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html index 5cde6593..2e3b6251 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html @@ -94,10 +94,7 @@
DJI_Follow.h File Reference
- -

Follow API for DJI onboardSDK library. -More...

-
#include "DJI_Mission.h"
+
#include "DJI_Mission.h"

Go to the source code of this file.

@@ -126,14 +123,14 @@
 

Detailed Description

-

Follow API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Follow API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__Follow_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Follow_8h_source.html index 2377596e..dbbd0db9 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Follow_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Follow_8h_source.html @@ -90,20 +90,17 @@
DJI_Follow.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_FOLLOW_H
13 #define DJI_FOLLOW_H
14 
15 #include "DJI_Mission.h"
16 
17 namespace DJI
18 {
19 namespace onboardSDK
20 {
21 
22 #pragma pack(1)
23 
24 typedef struct FollowTarget
25 {
26  float64_t latitude;
27  float64_t longitude;
28  uint16_t height;
29  uint16_t angle;
30 } FollowTarget;
31 
32 typedef struct FollowData
33 {
34  uint8_t mode;
35  uint8_t yaw;
36  FollowTarget target;
37  uint8_t sensitivity;
38 } FollowData;
39 
40 #pragma pack()
41 
43 class Follow
44 {
45  public:
46  enum MODE
47  {
48  MODE_RELATIVE = 0,
49  MODE_ROUTE = 1,
50  MODE_SMART = 2
51  };
52 
53  enum YAW_TYPE
54  {
55  YAW_TOTARGET = 0,
56  YAW_CUSTOM = 1
57  };
58 
60  {
61  SENSE_LOW = 0,
62  SENSE_MID = 1,
63  SENSE_HIGH = 2
64  };
65 
66  public:
67  Follow(CoreAPI *ControlAPI = 0);
68  void resetData();
69  void start(FollowData *Data = 0, CallBack callback = 0, UserData userData = 0);
70  MissionACK start(FollowData *Data = 0, int timer = 0);
71  void stop(CallBack callback = 0, UserData userData = 0);
72  MissionACK stop(int timer);
74  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
75  MissionACK pause(bool isPause, int timer);
76  void updateTarget(FollowTarget target);
77  void updateTarget(float64_t latitude, float64_t longitude, uint16_t height,
78  uint16_t angle);
79 
80  public:
81  void setData(const FollowData &value);
82  void setMode(const MODE mode);
83  void setTarget(FollowTarget target);
84  void setYawType(const YAW_TYPE type);
85  void setSensitivity(const SENSITIVITY sense);
86 
87  FollowData getData() const;
88 
89  private:
90  CoreAPI *api;
91  FollowData followData;
92 };
93 
94 }
95 }
96 
97 #endif
MODE
Definition: DJI_Follow.h:46
-
Mission Framework for DJI onboardSDK library.
-
uint8_t MissionACK
Definition: DJI_Type.h:312
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
Definition: DJI_Follow.h:32
-
Definition: DJI_Follow.h:24
-
SENSITIVITY
Definition: DJI_Follow.h:59
-
Follow class encapsulates all follow control related functions provided by the DJI OnboardSDK...
Definition: DJI_Follow.h:43
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
+Go to the documentation of this file.
1 
13 #ifndef DJI_FOLLOW_H
14 #define DJI_FOLLOW_H
15 
16 #include "DJI_Mission.h"
17 
18 namespace DJI
19 {
20 namespace onboardSDK
21 {
22 
23 #pragma pack(1)
24 
25 typedef struct FollowTarget
26 {
27  float64_t latitude;
28  float64_t longitude;
29  uint16_t height;
30  uint16_t angle;
31 } FollowTarget;
32 
33 typedef struct FollowData
34 {
35  uint8_t mode;
36  uint8_t yaw;
37  FollowTarget target;
38  uint8_t sensitivity;
39 } FollowData;
40 
41 #pragma pack()
42 
44 class Follow
45 {
46  public:
47  enum MODE
48  {
49  MODE_RELATIVE = 0,
50  MODE_ROUTE = 1,
51  MODE_SMART = 2
52  };
53 
54  enum YAW_TYPE
55  {
56  YAW_TOTARGET = 0,
57  YAW_CUSTOM = 1
58  };
59 
61  {
62  SENSE_LOW = 0,
63  SENSE_MID = 1,
64  SENSE_HIGH = 2
65  };
66 
67  public:
68  Follow(CoreAPI *ControlAPI = 0);
69  void resetData();
70  void start(FollowData *Data = 0, CallBack callback = 0, UserData userData = 0);
71  void stop(CallBack callback = 0, UserData userData = 0);
73  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
74  void updateTarget(FollowTarget target);
75  void updateTarget(float64_t latitude, float64_t longitude, uint16_t height,
76  uint16_t angle);
77 
78  public:
79  void setData(const FollowData &value);
80  void setMode(const MODE mode);
81  void setTarget(FollowTarget target);
82  void setYawType(const YAW_TYPE type);
83  void setSensitivity(const SENSITIVITY sense);
84 
85  FollowData getData() const;
86 
87  private:
88  CoreAPI *api;
89  FollowData followData;
90 };
91 
92 }
93 }
94 
95 #endif
MODE
Definition: DJI_Follow.h:47
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
+
Definition: DJI_Follow.h:33
+
Definition: DJI_Follow.h:25
+
SENSITIVITY
Definition: DJI_Follow.h:60
+
Follow class encapsulates all follow control related functions provided by the DJI OnboardSDK...
Definition: DJI_Follow.h:44
Definition: DJI_Mission.cpp:16
diff --git a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8cpp.html deleted file mode 100644 index e7524b8e..00000000 --- a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8cpp.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - -Onboard-SDK-ROS: dji_sdk_lib/src/DJI_HardDriver.cpp File Reference - - - - - - - - - - -
-
- - - - - - -
-
Onboard-SDK-ROS -
-
-
- - - - - - -
-
- - -
- -
- - -
-
-
-
DJI_HardDriver.cpp File Reference
-
-
- -

Serial device driver abstraction. See DJI_HardDriver.h for more info. -More...

-
#include "DJI_HardDriver.h"
-

Detailed Description

-

Serial device driver abstraction. See DJI_HardDriver.h for more info.

-
Version
3.1.7
-
Date
Jul 01 2016
- -
- - - - diff --git a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html index fef3ade9..2b0c955b 100644 --- a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html @@ -93,9 +93,6 @@
DJI_HardDriver.h File Reference
- -

Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms. -More...

#include <stdint.h>
#include <time.h>
#include "DJI_Type.h"
@@ -113,14 +110,19 @@  

Detailed Description

-

Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms.

-
Version
3.1.7
-
Date
Jul 01 2016
- +
Version
3.0
+
Date
Dec 9, 2015
+

Hard ware level for DJI onboardSDK library

+
Attention
Project configuration:
+
Version
features: -*
+
+V3.0 -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake -*
+
Date
Dec 9, 2015 -*
+
Author
william.wu
diff --git a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h_source.html index ba243c11..fa638043 100644 --- a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h_source.html @@ -90,14 +90,14 @@
DJI_HardDriver.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_HARDDRIVER_H
13 #define DJI_HARDDRIVER_H
14 
15 #include <stdint.h>
16 #include <time.h>
17 #include "DJI_Type.h"
18 
19 namespace DJI
20 {
21 namespace onboardSDK
22 {
23 
25 {
26  public:
27  HardDriver() {}
28 
80  public:
81  virtual void init() = 0;
82  virtual time_ms getTimeStamp() = 0;
83  virtual size_t send(const uint8_t *buf, size_t len) = 0;
84  virtual size_t readall(uint8_t *buf, size_t maxlen) = 0;
85 
86  public:
87  virtual void lockMemory() = 0;
88  virtual void freeMemory() = 0;
89 
90  virtual void lockMSG() = 0;
91  virtual void freeMSG() = 0;
92 
93  virtual void lockACK() = 0;
94  virtual void freeACK() = 0;
95 
96  virtual void notify() = 0;
97  virtual void wait(int timeout) = 0;
98 
99  public:
100  virtual void displayLog(const char *buf = 0);
101 };
102 } // namespace onboardSDK
103 } // namespace DJI
104 
105 #endif // DJI_HARDDRIVER_H
virtual void init()=0
After calling this function, HardDriver should be able to read and send correctly, through a correct UART part.
-
Definition: DJI_HardDriver.h:24
-
Type definition for DJI onboardSDK library. Officially Maintained.
+Go to the documentation of this file.
1 
19 #ifndef DJI_HARDDRIVER_H
20 #define DJI_HARDDRIVER_H
21 
22 #include <stdint.h>
23 #include <time.h>
24 #include "DJI_Type.h"
25 
26 namespace DJI
27 {
28 namespace onboardSDK
29 {
30 
32 {
33  public:
34  HardDriver() {}
35 
83  public:
84  virtual void init() = 0;
85  virtual time_ms getTimeStamp() = 0;
86  virtual size_t send(const uint8_t *buf, size_t len) = 0;
87  virtual size_t readall(uint8_t *buf, size_t maxlen) = 0;
88 
89  public:
90  virtual void lockMemory() = 0;
91  virtual void freeMemory() = 0;
92 
93  virtual void lockMSG() = 0;
94  virtual void freeMSG() = 0;
95 
96  public:
97  virtual void displayLog(const char *buf = 0);
98 };
99 } // namespace onboardSDK
100 } // namespace DJI
101 
102 #endif // DJI_HARDDRIVER_H
virtual void init()=0
After calling this function, HardDriver should be able to read and send correctly, through a correct UART part.
+
Definition: DJI_HardDriver.h:31
+
Definition: DJI_Mission.cpp:16
diff --git a/dji_sdk_doc/doxygen/html/DJI__HotPoint_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__HotPoint_8cpp.html index 544e9eea..1cc81c2e 100644 --- a/dji_sdk_doc/doxygen/html/DJI__HotPoint_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__HotPoint_8cpp.html @@ -90,20 +90,17 @@
DJI_HotPoint.cpp File Reference
- -

Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library. -More...

-
#include "DJI_HotPoint.h"
+
#include "DJI_HotPoint.h"
#include <string.h>

Detailed Description

-

Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
- +

Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library

+
diff --git a/dji_sdk_doc/doxygen/html/DJI__HotPoint_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__HotPoint_8h_source.html index e17e98e8..b58c20d6 100644 --- a/dji_sdk_doc/doxygen/html/DJI__HotPoint_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__HotPoint_8h_source.html @@ -90,24 +90,19 @@
DJI_HotPoint.h
-
1 
12 #ifndef DJI_HOTPOINT_H
13 #define DJI_HOTPOINT_H
14 
15 #include "DJI_Mission.h"
16 
17 namespace DJI
18 {
19 namespace onboardSDK
20 {
21 
22 class HotPoint
23 {
24  public:
25 #pragma pack(1)
26  typedef struct YawRate
27  {
28  uint8_t clockwise;
29  float32_t yawRate;
30  } YawRate;
31 #pragma pack()
32 
33  enum View
34  {
35  VIEW_NORTH = 0,
36  VIEW_SOUTH = 1,
37  VIEW_WEST = 2,
38  VIEW_EAST = 3,
39  VIEW_NEARBY = 4
40  };
41 
42  enum YawMode
43  {
44  YAW_AUTO = 0,
45  YAW_INSIDE = 1,
46  YAW_OUTSIDE = 2,
47  YAW_CUSTOM = 3,
48  YAW_STATIC = 4,
49  };
50 
51  public:
52  HotPoint(CoreAPI *ControlAPI = 0);
53  void initData();
54 
62  void start(CallBack callback = 0, UserData userData = 0);
63  HotPointStartACK start(int timer);
64  void stop(CallBack callback = 0, UserData userData = 0);
65  MissionACK stop(int timer);
66  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
67  MissionACK pause(bool isPause, int timer);
68 
69  void updateYawRate(YawRate &Data, CallBack callback = 0, UserData userData = 0);
70  MissionACK updateYawRate(YawRate &Data, int timer);
71  void updateYawRate(float32_t yawRate, bool isClockwise, CallBack callback = 0,
72  UserData userData = 0);
73  void updateRadius(float32_t meter, CallBack callback = 0, UserData userData = 0);
74  MissionACK updateRadius(float32_t meter, int timer);
75  void resetYaw(CallBack callback = 0, UserData userData = 0);
76  MissionACK resetYaw(int timer);
77 
78  void readData(CallBack callback = 0, UserData userData = 0);
79  MissionACK readData(int timer);
80 
81  public:
83  void setData(const HotPointData &value);
84  void setHotPoint(float64_t longtitude, float64_t latitude, float64_t altitude);
85  void setHotPoint(GPSPositionData gps);
86  void setRadius(float64_t meter);
87  void setYawRate(float32_t defree);
88  void setClockwise(bool isClockwise);
89  void setCameraView(View view);
90  void setYawMode(YawMode mode);
91 
92  HotPointData getData() const;
93 
94  public:
95  static void startCallback(CoreAPI *api, Header *protocolHeader, UserData userdata = 0);
96  static void readCallback(CoreAPI *api, Header *protoclHeader, UserData userdata);
97 
98  private:
99  CoreAPI *api;
100  HotPointData hotPointData;
101 };
102 
103 } // namespace onboardSDK
104 } // namespace DJI
105 
106 #endif // DJI_HOTPOINT_H
Definition: DJI_Type.h:315
-
Mission Framework for DJI onboardSDK library.
-
uint8_t MissionACK
Definition: DJI_Type.h:312
-
Definition: DJI_HotPoint.h:22
-
void(* CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData)
The CallBack function pointer is used as an argument in api->send calls.
Definition: DJI_Type.h:142
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
void setData(const HotPointData &value)
Definition: DJI_HotPoint.cpp:180
-
Definition: DJI_HotPoint.h:26
-
Definition: DJI_Type.h:245
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
-
The Header struct is meant to handle the open protocol header.
Definition: DJI_Type.h:122
+Go to the documentation of this file.
1 
20 #ifndef DJI_HOTPOINT_H
21 #define DJI_HOTPOINT_H
22 
23 #include "DJI_Mission.h"
24 
25 namespace DJI
26 {
27 namespace onboardSDK
28 {
29 
30 #pragma pack(1)
31 
32 typedef struct HotPointData
33 {
34  uint8_t version;
35 
36  float64_t latitude;
37  float64_t longitude;
38  float64_t height;
39 
40  float64_t radius;
41  float32_t yawRate; // degree
42 
43  uint8_t clockwise;
44  uint8_t startPoint;
45  uint8_t yawMode;
46  uint8_t reserved[11];
47 } HotPointData;
48 
49 #pragma pack()
50 
51 class HotPoint
52 {
53  public:
54 #pragma pack(1)
55  typedef struct StartACK
56  {
57  uint8_t ack;
58  float32_t maxRadius;
59  } StartACK;
60 
61  typedef struct YawRate
62  {
63  uint8_t clockwise;
64  float32_t yawRate;
65  } YawRate;
66 
67  typedef struct ReadACK
68  {
69  MissionACK ack;
70  HotPointData data;
71  } ReadACK;
72 #pragma pack()
73 
74  enum View
75  {
76  VIEW_NORTH = 0,
77  VIEW_SOUTH = 1,
78  VIEW_WEST = 2,
79  VIEW_EAST = 3,
80  VIEW_NEARBY = 4
81  };
82 
83  enum YawMode
84  {
85  YAW_AUTO = 0,
86  YAW_INSIDE = 1,
87  YAW_OUTSIDE = 2,
88  YAW_CUSTOM = 3,
89  YAW_STATIC = 4,
90  };
91 
92  public:
93  HotPoint(CoreAPI *ControlAPI = 0);
94  void initData();
95 
103  void start(CallBack callback = 0, UserData userData = 0);
104  void stop(CallBack callback = 0, UserData userData = 0);
105  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
106 
107  void updateYawRate(YawRate &Data, CallBack callback = 0, UserData userData = 0);
108  void updateYawRate(float32_t yawRate, bool isClockwise, CallBack callback = 0,
109  UserData userData = 0);
110  void updateRadius(float32_t meter, CallBack callback = 0, UserData userData = 0);
111  void resetYaw(CallBack callback = 0, UserData userData = 0);
112 
113  void readData(CallBack callback = 0, UserData userData = 0);
114 
115  public:
117  void setData(const HotPointData &value);
118  void setHotPoint(float64_t longtitude, float64_t latitude, float64_t altitude);
119  void setHotPoint(GPSPositionData gps);
120  void setRadius(float64_t meter);
121  void setYawRate(float32_t defree);
122  void setClockwise(bool isClockwise);
123  void setCameraView(View view);
124  void setYawMode(YawMode mode);
125 
126  HotPointData getData() const;
127 
128  public:
129  static void startCallback(CoreAPI *api, Header *protocolHeader, UserData userdata = 0);
130  static void readCallback(CoreAPI *api, Header *protoclHeader, UserData userdata);
131 
132  private:
133  CoreAPI *api;
134  HotPointData hotPointData;
135 };
136 
137 } // namespace onboardSDK
138 } // namespace DJI
139 
140 #endif // DJI_HOTPOINT_H
Definition: DJI_HotPoint.h:55
+
Definition: DJI_HotPoint.h:51
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
+
Definition: DJI_HotPoint.h:61
+
Definition: DJI_HotPoint.h:32
+
Definition: DJI_Type.h:118
+
Definition: DJI_HotPoint.h:67
Definition: DJI_Mission.cpp:16
-
void start(CallBack callback=0, UserData userData=0)
Definition: DJI_HotPoint.cpp:40
-
Definition: DJI_Type.h:449
+
Definition: DJI_Type.h:326
diff --git a/dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html index 83c6689b..ecffde3d 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html @@ -116,7 +116,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__Link_8h.html b/dji_sdk_doc/doxygen/html/DJI__Link_8h.html index 3a110913..ff0ac69b 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Link_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Link_8h.html @@ -92,9 +92,6 @@
DJI_Link.h File Reference
- -

Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library. -More...

#include "DJI_Type.h"

Go to the source code of this file.

@@ -124,15 +121,21 @@  

Detailed Description

-

Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library.

-

Implement memory management for Core API of DJI onboardSDK library. See DJI_Memory.cpp for more.

-
Version
3.1.7
-
Date
July 1st, 2016
- +
Version
3.0
+
Date
Dec 4, 2015
+
Attention
Project configuration:
+
Version
features: -*
+
+V3.0 -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake -*
+
Date
Nov 15, 2015 -*
+
Author
william.wu -* -*
+
Version
V2.0 -* C-like DJI-onboard-SDK library -*
+
Date
Mar 12, 2015 -*
+
Author
wuyuwei
diff --git a/dji_sdk_doc/doxygen/html/DJI__Link_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Link_8h_source.html index 4a78a628..2534ff5c 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Link_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Link_8h_source.html @@ -90,11 +90,11 @@
DJI_Link.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_LINK_H
13 #define DJI_LINK_H
14 
15 #define ACK_SESSION_IDLE 0
16 #define ACK_SESSION_PROCESS 1
17 #define ACK_SESSION_USING 2
18 #define CMD_SESSION_0 0
19 #define CMD_SESSION_1 1
20 #define CMD_SESSION_AUTO 32
21 
22 
23 #define POLL_TICK 20 // unit is ms
24 
25 #include "DJI_Type.h"
26 
27 #endif // DJI_LINK_H
Type definition for DJI onboardSDK library. Officially Maintained.
+Go to the documentation of this file.
1 
23 #ifndef DJI_LINK_H
24 #define DJI_LINK_H
25 
26 #define ACK_SESSION_IDLE 0
27 #define ACK_SESSION_PROCESS 1
28 #define ACK_SESSION_USING 2
29 #define CMD_SESSION_0 0
30 #define CMD_SESSION_1 1
31 #define CMD_SESSION_AUTO 32
32 
33 
34 #define POLL_TICK 20 // unit is ms
35 
36 #include "DJI_Type.h"
37 
38 #endif // DJI_LINK_H
diff --git a/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html index 76841da3..46c1f4d5 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html @@ -92,9 +92,6 @@
DJI_Memory.cpp File Reference
- -

Implement memory management for Core API of DJI onboardSDK library. -More...

#include <stdio.h>
#include <string.h>
#include "DJI_Memory.h"
@@ -107,15 +104,16 @@  

Detailed Description

-

Implement memory management for Core API of DJI onboardSDK library.

-
Version
3.1.7
-
Date
July 1st, 2016
- -
Attention
It is not necessary to include DJI_Memory.h in any custom code file. The functions in this file are not API functions. Do not modify this file if you are unsure about it.
+
Version
V2.0
+
Date
Nov 11, 2015
+
Author
wuyunwei,william.wu
+

This file mainly implement fuctions in DJI_API.h

+

All Functions in this file is private function, which is used for memory and session management.

+
Attention
It is not necessary to include DJI_link.h in any custom code file. All functions in this file are not API function. Do not modify this file, if you are not sure about it. Created on: 24 Aug, 2015 Author: wuyuwei Modified on: Nov 11, 2015 by william.wu
diff --git a/dji_sdk_doc/doxygen/html/DJI__Memory_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Memory_8h_source.html index 61ef7355..af540f82 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Memory_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Memory_8h_source.html @@ -90,11 +90,11 @@
DJI_Memory.h
-
1 
12 #ifndef DJI_MEMORY_H
13 #define DJI_MEMORY_H
14 
15 #include "DJI_Type.h"
16 
17 #endif // DJI_MEMORY_H
Type definition for DJI onboardSDK library. Officially Maintained.
+
1 #ifndef DJI_MEMORY_H
2 #define DJI_MEMORY_H
3 
4 #include "DJI_Type.h"
5 
6 #endif // DJI_MEMORY_H
diff --git a/dji_sdk_doc/doxygen/html/DJI__Mission_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Mission_8cpp.html index 66f6f630..096f3469 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Mission_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__Mission_8cpp.html @@ -98,7 +98,7 @@

Mission Framework for DJI onboardSDK library. More...

#include "DJI_API.h"
-#include "DJI_Mission.h"
+#include "DJI_Mission.h"
#include <string.h>
+void 

@@ -109,14 +109,14 @@

Functions

-void DJI::onboardSDK::missionCallback (CoreAPI *api, Header *protocolHeader, UserData userdata __UNUSED)
DJI::onboardSDK::missionCallback (CoreAPI *api, Header *protocolHeader, UserData userdata __UNUSED)
 
- - + +

Variables

-MissionACKMap DJI::onboardSDK::missionACKMAP []
 
+MissionACKMap DJI::onboardSDK::missionACK []
 

Detailed Description

Mission Framework for DJI onboardSDK library.

@@ -126,7 +126,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__Mission_8h.html b/dji_sdk_doc/doxygen/html/DJI__Mission_8h.html deleted file mode 100644 index ebc9702a..00000000 --- a/dji_sdk_doc/doxygen/html/DJI__Mission_8h.html +++ /dev/null @@ -1,164 +0,0 @@ - - - - - - -Onboard-SDK-ROS: dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h File Reference - - - - - - - - - - -
-
- - - - - - -
-
Onboard-SDK-ROS -
-
-
- - - - - - -
-
- - -
- -
- - -
-
- -
-
DJI_Mission.h File Reference
-
-
- -

Mission Framework for DJI onboardSDK library. -More...

-
#include "DJI_Config.h"
-#include "DJI_API.h"
-
-

Go to the source code of this file.

- - - - - - - - -

-Classes

struct  DJI::onboardSDK::HotPointACKData
 
struct  DJI::onboardSDK::GSPushData
 
struct  DJI::onboardSDK::MissionACKMap
 
- - - -

-Namespaces

 DJI
 
- - - - - - - -

-Typedefs

-typedef struct DJI::onboardSDK::HotPointACKData DJI::onboardSDK::HotPointADKData
 
typedef struct DJI::onboardSDK::GSPushData DJI::onboardSDK::GSPushData
 
-typedef struct DJI::onboardSDK::MissionACKMap DJI::onboardSDK::MissionACKMap
 
- - - -

-Functions

-void DJI::onboardSDK::missionCallback (CoreAPI *api, Header *protocolHeader, UserData userdata __UNUSED)
 
-

Detailed Description

-

Mission Framework for DJI onboardSDK library.

-
Version
3.1.7
-
Date
July 1st, 2016
- -

Typedef Documentation

- -
-
-
Todo:
unify the naming style
- -
-
-
- - - - diff --git a/dji_sdk_doc/doxygen/html/DJI__Mission_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Mission_8h_source.html index 51b8b18f..af2eeae1 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Mission_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Mission_8h_source.html @@ -90,19 +90,18 @@
DJI_Mission.h
-Go to the documentation of this file.
1 
12 #ifndef DJI_MISSION_H
13 #define DJI_MISSION_H
14 
15 #include "DJI_Config.h"
16 #include "DJI_API.h"
17 
18 namespace DJI
19 {
20 namespace onboardSDK
21 {
22 #pragma pack(1)
23 
24 typedef struct HotPointACKData
25 {
26  uint8_t status;
27  uint16_t radius; // in cm
28  uint8_t failReasion;
29  uint8_t yawRate;
31 
33 typedef struct GSPushData
34 {
35  uint8_t type;
36  uint8_t data_1;
37  uint8_t data_2;
38  uint8_t data_3;
39  uint8_t data_4;
40  uint8_t data_5;
41 } GSPushData;
42 
43 #pragma pack()
44 
45 typedef struct MissionACKMap
46 {
47  uint8_t code;
48  const char *meaning;
50 
51 void missionCallback(CoreAPI *api, Header *protocolHeader, UserData userdata = 0);
52 
53 } // namespace onboardSDK
54 } // namespace DJI
55 
56 #endif // DJI_MISSION_H
Core API for DJI onboardSDK library.
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
Definition: DJI_Mission.h:45
-
Definition: DJI_Mission.h:33
-
Optional macro definitions for DJI Onboard SDK. Use for debugging.
-
Definition: DJI_Mission.h:24
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
-
The Header struct is meant to handle the open protocol header.
Definition: DJI_Type.h:122
+
1 
20 #ifndef DJI_MISSION_H
21 #define DJI_MISSION_H
22 
23 #include "DJI_Config.h"
24 #include "DJI_API.h"
25 
26 namespace DJI
27 {
28 namespace onboardSDK
29 {
30 #pragma pack(1)
31 
32 typedef struct HotPointACKData
33 {
34  uint8_t status;
35  uint16_t radius; // in cm
36  uint8_t failReasion;
37  uint8_t yawRate;
39 
41 typedef struct GSPushData
42 {
43  uint8_t type;
44  uint8_t data_1;
45  uint8_t data_2;
46  uint8_t data_3;
47  uint8_t data_4;
48  uint8_t data_5;
49 } GSPushData;
50 
51 #pragma pack()
52 
53 typedef struct MissionACKMap
54 {
55  uint8_t code;
56  const char *meaning;
58 
59 void missionCallback(CoreAPI *api, Header *protocolHeader, UserData userdata = 0);
60 
61 } // namespace onboardSDK
62 } // namespace DJI
63 
64 #endif // DJI_MISSION_H
Core API for DJI onboardSDK library.
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
+
Definition: DJI_Mission.h:53
+
Definition: DJI_Mission.h:41
+ +
Definition: DJI_Mission.h:32
+
Definition: DJI_Type.h:118
Definition: DJI_Mission.cpp:16
diff --git a/dji_sdk_doc/doxygen/html/DJI__Type_8h.html b/dji_sdk_doc/doxygen/html/DJI__Type_8h.html index fc1e02ad..2d294718 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Type_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Type_8h.html @@ -96,9 +96,6 @@
DJI_Type.h File Reference
- -

Type definition for DJI onboardSDK library. Officially Maintained. -More...

#include "DJI_Config.h"
#include "DJICommonType.h"
#include <stdio.h>
@@ -108,10 +105,8 @@

Classes

struct  DJI::onboardSDK::Header - The Header struct is meant to handle the open protocol header. More...
  struct  DJI::onboardSDK::CallBackHandler - The CallBackHandler struct allows users to encapsulate callbacks and data in one struct. More...
  struct  DJI::onboardSDK::Command   @@ -129,24 +124,6 @@   struct  DJI::onboardSDK::GimbalSpeedData   -struct  DJI::onboardSDK::HotPointData -  -struct  DJI::onboardSDK::WayPointInitData -  -struct  DJI::onboardSDK::WayPointData -  -struct  DJI::onboardSDK::HotPointStartACK -  -struct  DJI::onboardSDK::WayPointDataACK -  -struct  DJI::onboardSDK::WayPointVelocityACK -  -union  DJI::onboardSDK::MissionACKUnion -  -struct  DJI::onboardSDK::HotPointReadACK -  -struct  DJI::onboardSDK::WayPointInitACK -  struct  DJI::onboardSDK::QuaternionData   struct  DJI::onboardSDK::CommonData @@ -185,10 +162,6 @@   struct  DJI::onboardSDK::VirtualRCData   -struct  DJI::onboardSDK::ActivateData -  -struct  DJI::onboardSDK::VersionData -  @@ -200,14 +173,12 @@ - +#define  - @@ -234,16 +205,13 @@ - +typedef struct DJI::onboardSDK::Header  - +typedef void(*  - +typedef struct DJI::onboardSDK::CallBackHandler  @@ -264,7 +232,11 @@ - + + + @@ -275,36 +247,6 @@ - - - - - - - - - - - - - - - - - - - - - - @@ -355,12 +297,6 @@ - - - -

Namespaces

#define NAME(x)   #x
 
-#define __UNUSED
 Define the UNUSED macro to suppress compiler warnings about unused arguments.
__UNUSED
 
#define __DELETE(x)   delete x
 
#define API_LOG(driver, title, fmt, ...)
 This is the default status printing mechanism. More...
 
#define DEBUG_LOG   0

Typedefs

-typedef struct DJI::onboardSDK::Header DJI::onboardSDK::Header
 The Header struct is meant to handle the open protocol header.
DJI::onboardSDK::Header
 
-typedef void(* DJI::onboardSDK::CallBack) (DJI::onboardSDK::CoreAPI *, Header *, UserData)
 The CallBack function pointer is used as an argument in api->send calls.
DJI::onboardSDK::CallBack) (DJI::onboardSDK::CoreAPI *, Header *, UserData)
 
-typedef struct DJI::onboardSDK::CallBackHandler DJI::onboardSDK::CallBackHandler
 The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.
DJI::onboardSDK::CallBackHandler
 
typedef struct DJI::onboardSDK::Command DJI::onboardSDK::Command
typedef uint8_t DJI::onboardSDK::BatteryData
 
typedef struct DJI::onboardSDK::GimbalAngleData DJI::onboardSDK::GimbalAngleData
+typedef uint8_t DJI::onboardSDK::MissionACK
 
+typedef struct DJI::onboardSDK::GimbalAngleData DJI::onboardSDK::GimbalAngleData
 
typedef struct DJI::onboardSDK::GimbalSpeedData DJI::onboardSDK::GimbalSpeedData
typedef double DJI::onboardSDK::float64_t
 
typedef struct DJI::onboardSDK::HotPointData DJI::onboardSDK::HotPointData
 
typedef struct DJI::onboardSDK::WayPointInitData DJI::onboardSDK::WayPointInitData
 
-typedef struct DJI::onboardSDK::WayPointData DJI::onboardSDK::WayPointData
 
typedef uint8_t DJI::onboardSDK::MissionACK
 
-typedef uint32_t DJI::onboardSDK::SimpleACK
 
-typedef struct DJI::onboardSDK::HotPointStartACK DJI::onboardSDK::HotpointStartACK
 
-typedef struct DJI::onboardSDK::WayPointDataACK DJI::onboardSDK::WayPointDataACK
 
-typedef struct DJI::onboardSDK::WayPointVelocityACK DJI::onboardSDK::WayPointVelocityACK
 
-typedef union DJI::onboardSDK::MissionACKUnion DJI::onboardSDK::MissionACKUnion
 
-typedef struct DJI::onboardSDK::HotPointReadACK DJI::onboardSDK::HotpointReadACK
 
-typedef struct DJI::onboardSDK::WayPointInitACK DJI::onboardSDK::WayPointInitACK
 
typedef struct DJI::onboardSDK::QuaternionData DJI::onboardSDK::QuaternionData
 
typedef struct DJI::onboardSDK::VirtualRCData DJI::onboardSDK::VirtualRCData
 
-typedef struct DJI::onboardSDK::ActivateData DJI::onboardSDK::ActivateData
 
-typedef struct DJI::onboardSDK::VersionData DJI::onboardSDK::VersionData
 
@@ -384,9 +320,9 @@

Variables

 

Detailed Description

-

Type definition for DJI onboardSDK library. Officially Maintained.

-
Version
3.1.7
+
Version
3.1.7
Date
Jul 01 2016
+

Type definition for DJI onboardSDK library Officially Maintained

Macro Definition Documentation

@@ -424,9 +360,7 @@
-Value:
if ((title)) \
{ \
int len = (sprintf(DJI::onboardSDK::buffer, "%s %s,line %d: " fmt, \
(title) ? (title) : "NONE", __func__, __LINE__, ##__VA_ARGS__)); \
if ((len != -1) && (len < 1024)) \
(driver)->displayLog(); \
else \
(driver)->displayLog("ERROR: log printer inner fault\n"); \
}
-

This is the default status printing mechanism.

-
Todo:
fix warning.
+Value:
if ((title)) \
{ \
int len = (sprintf(DJI::onboardSDK::buffer, "%s %s,line %d: " fmt, \
(title) ? (title) : "NONE", __func__, __LINE__, ##__VA_ARGS__)); \
if ((len != -1) && (len < 1024)) \
(driver)->displayLog(); \
else \
(driver)->displayLog("ERROR: log printer inner fault\n"); \
}
Todo:
fix warning.
@@ -443,7 +377,7 @@
-
Attention
Do not modify any definition in this file if you are unsure about what are you doing. DJI will not provide any support for changes made to this file.
+
Attention
Do not modify any definition in this file if you are not sure what are you doing. DJI will not provide any support for changes made to this file.
@@ -457,7 +391,7 @@

Typedef Documentation

@@ -472,19 +406,6 @@

Typedef Documentation

Warning
this struct will be deprecated in the next release and renamed to Vector3fData. Use Vector3fData instead.
-
- - -
-
-

Gimbal Data

-
@@ -496,7 +417,7 @@

Typedef Documentation

-
Todo:
rename to a final version Detailed GPSData from the A3. This is not available on the M100.
+
Todo:
rename to a final version
@@ -511,19 +432,6 @@

Typedef Documentation

Note
This struct is provided as a means for users to provide sigle GPS points to the SDK. It does not follow standard SDK GPS datatypes. This may change in a future release.
-
- - - @@ -550,19 +458,6 @@

Typedef Documentation

Warning
the 'MagnetData' struct will be deprecated in the next release and renamed to MagData. Use MagData instead.
-
- - -
-
- - - - -
typedef uint8_t DJI::onboardSDK::MissionACK
-
-

ACK Data

-
@@ -613,7 +508,7 @@

Typedef Documentation

-
Todo:
rename to a final version RTKData from the A3. This is not available on the M100.
+
Todo:
rename to a final version
@@ -641,25 +536,12 @@

Typedef Documentation

Note
this struct will replace CommonData in the next release. Eigen-like naming convention
-
- - - diff --git a/dji_sdk_doc/doxygen/html/DJI__Type_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Type_8h_source.html index b075a79b..d143b4cb 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Type_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Type_8h_source.html @@ -90,77 +90,60 @@
DJI_Type.h
-Go to the documentation of this file.
1 
19 #ifndef DJI_TYPE
20 #define DJI_TYPE
21 
22 #include "DJI_Config.h"
23 #include "DJICommonType.h"
24 #include <stdio.h>
25 
26 #define NAME(x) #x
27 
29 #ifdef __GNUC__
30 #define __UNUSED __attribute__((__unused__))
31 #define __DELETE(x) delete (char *) x
32 #else
33 #define __UNUSED
34 #define __DELETE(x) delete x
35 
36 
38 #ifndef STM32
39 #pragma warning(disable : 4100)
40 #pragma warning(disable : 4800)
41 #pragma warning(disable : 4996)
42 #pragma warning(disable : 4244)
43 #pragma warning(disable : 4267)
44 #pragma warning(disable : 4700)
45 #pragma warning(disable : 4101)
46 #endif // STM32
47 #endif //__GNUC__
48 
49 #ifdef WIN32
50 #define __func__ __FUNCTION__
51 #endif // WIN32
52 
53 
55 #define API_LOG(driver, title, fmt, ...) \
56  if ((title)) \
57  { \
58  int len = (sprintf(DJI::onboardSDK::buffer, "%s %s,line %d: " fmt, \
59  (title) ? (title) : "NONE", __func__, __LINE__, ##__VA_ARGS__)); \
60  if ((len != -1) && (len < 1024)) \
61  (driver)->displayLog(); \
62  else \
63  (driver)->displayLog("ERROR: log printer inner fault\n"); \
64  }
65 #ifdef API_DEBUG_DATA
66 #define DEBUG_LOG "DEBUG"
67 #else
68 #define DEBUG_LOG 0
69 #endif
70 
71 #ifdef API_ERROR_DATA
72 #define ERROR_LOG "ERROR"
73 #else
74 #define ERROR_LOG 0
75 #endif
76 
77 #ifdef API_BUFFER_DATA
78 #define BUFFER_LOG "BUFFER"
79 #else
80 #define BUFFER_LOG 0
81 #endif
82 
83 #ifdef API_STATUS_DATA
84 #define STATUS_LOG "STATUS"
85 #else
86 #define STATUS_LOG 0
87 #endif
88 
89 #ifdef API_MISSION_DATA
90 #define MISSION_LOG "MISSION"
91 #else
92 #define MISSION_LOG 0
93 #endif
94 
95 #ifdef API_RTK_DEBUG
96 #define RTK_LOG "MISSION"
97 #else
98 #define RTK_LOG 0
99 #endif
100 
102 #ifdef ARMCC
103 #pragma anon_unions
104 #endif
105 
106 namespace DJI
107 {
108 namespace onboardSDK
109 {
110 
111 const size_t bufsize = 1024;
112 extern char buffer[];
113 extern uint8_t encrypt;
114 
115 const size_t SESSION_TABLE_NUM = 32;
116 const size_t CALLBACK_LIST_NUM = 10;
117 
119 class CoreAPI;
120 
122 typedef struct Header
123 {
124  unsigned int sof : 8;
125  unsigned int length : 10;
126  unsigned int version : 6;
127  unsigned int sessionID : 5;
128  unsigned int isAck : 1;
130  unsigned int reversed0 : 2; // always 0
131 
132  unsigned int padding : 5;
133  unsigned int enc : 3;
135  unsigned int reversed1 : 24;
136 
137  unsigned int sequenceNumber : 16;
138  unsigned int crc : 16;
139 } Header;
140 
142 typedef void (*CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData);
143 
145 typedef struct CallBackHandler
146 {
147  CallBack callback;
148  UserData userData;
150 
151 typedef struct Command
152 {
153  unsigned short sessionMode : 2;
154  unsigned short encrypt : 1;
155  unsigned short retry : 13;
156  unsigned short timeout; // unit is ms
157  size_t length;
158  uint8_t *buf;
159  CallBack handler;
160  UserData userData;
161 } Command;
162 
164 typedef struct SDKFilter
165 {
166  unsigned short reuseIndex;
167  unsigned short reuseCount;
168  unsigned short recvIndex;
169  unsigned char recvBuf[BUFFER_SIZE];
170  // for encrypt
171  unsigned char sdkKey[32];
172  unsigned char encode;
173 } SDKFilter;
174 
176 typedef struct MMU_Tab
177 {
178  unsigned int tabIndex : 8;
179  unsigned int usageFlag : 8;
180  unsigned int memSize : 16;
181  unsigned char *pmem;
182 } MMU_Tab;
183 
184 typedef struct CMDSession
185 {
186  uint32_t sessionID : 5;
187  uint32_t usageFlag : 1;
188  uint32_t sent : 5;
189  uint32_t retry : 5;
190  uint32_t timeout : 16;
191  MMU_Tab *mmu;
192  CallBack handler;
193  UserData userData;
194  uint32_t preSeqNum;
195  time_ms preTimestamp;
196 } CMDSession;
197 
198 typedef struct ACKSession
199 {
200  uint32_t sessionID : 5;
201  uint32_t sessionStatus : 2;
202  uint32_t res : 25;
203  MMU_Tab *mmu;
204 } ACKSession;
205 
206 typedef struct Ack
207 {
208  uint16_t sessionID : 8;
209  uint16_t encrypt : 8;
210  uint16_t seqNum;
211  uint32_t length;
212  uint8_t *buf;
213 } Ack;
214 
215 #pragma pack(1)
216 
217 typedef uint8_t BatteryData;
218 
222 typedef struct GimbalAngleData
223 {
224  int16_t yaw;
225  int16_t roll;
226  int16_t pitch;
227  uint8_t mode;
228  uint8_t duration;
230 
231 typedef struct GimbalSpeedData
232 {
233  int16_t yaw;
234  int16_t roll;
235  int16_t pitch;
236  uint8_t reserved; // always 0x80;
238 
239 typedef float float32_t;
240 typedef double float64_t;
241 
245 typedef struct HotPointData
246 {
247  uint8_t version;
248 
249  float64_t latitude;
250  float64_t longitude;
251  float64_t height;
252 
253  float64_t radius;
254  float32_t yawRate; // degree
255 
256  uint8_t clockwise;
257  uint8_t startPoint;
258  uint8_t yawMode;
259  uint8_t reserved[11];
260 } HotPointData;
261 
265 typedef struct WayPointInitData
266 {
267  uint8_t indexNumber;
268  float32_t maxVelocity;
269  float32_t idleVelocity;
270 
271  uint8_t finishAction;
272  uint8_t executiveTimes;
273  uint8_t yawMode;
274  uint8_t traceMode;
275  uint8_t RCLostAction;
276  uint8_t gimbalPitch;
277  float64_t latitude;
278  float64_t longitude;
279  float32_t altitude;
280 
281  uint8_t reserved[16];
283 
284 typedef struct WayPointData
285 {
286  uint8_t index;
287 
288  float64_t latitude;
289  float64_t longitude;
290  float32_t altitude;
291  float32_t damping;
292 
293  int16_t yaw;
294  int16_t gimbalPitch;
295  uint8_t turnMode;
296 
297  uint8_t reserved[8];
298  uint8_t hasAction;
299  uint16_t actionTimeLimit;
300 
301  uint8_t actionNumber : 4;
302  uint8_t actionRepeat : 4;
303 
304  uint8_t commandList[16];
305  int16_t commandParameter[16];
306 } WayPointData;
307 
312 typedef uint8_t MissionACK;
313 typedef uint32_t SimpleACK;
314 
315 typedef struct HotPointStartACK
316 {
317  uint8_t ack;
318  float32_t maxRadius;
320 
321 typedef struct WayPointDataACK
322 {
323  uint8_t ack;
324  uint8_t index;
326 
327 typedef struct WayPointVelocityACK
328 {
329  uint8_t ack;
330  float32_t idleVelocity;
332 
333 
334 typedef union MissionACKUnion
335 {
336  uint8_t raw_ack_array[5];
337  MissionACK missionACK;
338  SimpleACK simpleACK;
339  HotPointStartACK hotpointStartACK;
340  WayPointDataACK waypointDataACK;
341  WayPointVelocityACK waypointVelocityACK;
342 } MissionACKUnion;
343 
344 // These big structs have structs within and don't seem to be used
345 typedef struct HotPointReadACK
346 {
347  MissionACK ack;
348  HotPointData data;
350 
351 typedef struct WayPointInitACK
352 {
353  uint8_t ack;
354  WayPointInitData data;
356 
357 typedef struct QuaternionData
358 {
359  float32_t q0;
360  float32_t q1;
361  float32_t q2;
362  float32_t q3;
364 
366 typedef struct CommonData
367 {
368  float32_t x;
369  float32_t y;
370  float32_t z;
371 } CommonData;
372 
375 typedef struct Vector3fData
376 {
377  float32_t x;
378  float32_t y;
379  float32_t z;
380 } Vector3fData;
381 
382 typedef struct VelocityData
383 {
384  float32_t x;
385  float32_t y;
386  float32_t z;
387  uint8_t health : 1;
388  uint8_t sensorID : 4;
389  uint8_t reserve : 3;
390 } VelocityData;
391 
392 typedef struct PositionData
393 {
394  float64_t latitude;
395  float64_t longitude;
399  float32_t altitude;
400 
404  float32_t height;
405 
406  uint8_t health;
407 } PositionData;
408 
410 typedef struct RadioData
411 {
412  int16_t roll;
413  int16_t pitch;
414  int16_t yaw;
415  int16_t throttle;
416  int16_t mode;
417  int16_t gear;
418 } RadioData;
419 
421 typedef struct RCData
422 {
423  int16_t roll;
424  int16_t pitch;
425  int16_t yaw;
426  int16_t throttle;
427  int16_t mode;
428  int16_t gear;
429 } RCData;
430 
432 typedef struct MagnetData
433 {
434  int16_t x;
435  int16_t y;
436  int16_t z;
437 } MagnetData;
438 
440 typedef struct MagData
441 {
442  int16_t x;
443  int16_t y;
444  int16_t z;
445 } MagData;
446 
449 typedef struct GPSPositionData
450 {
451  float64_t latitude;
452  float64_t longitude;
454  float64_t altitude;
455 
457 
458 typedef struct CtrlInfoData
459 {
460  uint8_t mode;
462  uint8_t deviceStatus : 3; /*0->rc 1->app 2->serial*/
463  uint8_t flightStatus : 1; /*1->opensd 0->close*/
464  uint8_t vrcStatus : 1;
465  uint8_t reserved : 3;
466 } CtrlInfoData;
467 
468 typedef struct TimeStampData
469 {
471  uint32_t time;
472  uint32_t nanoTime;
473  uint8_t syncFlag;
474 } TimeStampData;
475 
476 typedef struct GimbalData
477 {
478  float32_t roll;
479  float32_t pitch;
480  float32_t yaw;
481  uint8_t pitchLimit : 1;
482  uint8_t rollLimit : 1;
483  uint8_t yawLimit : 1;
484  uint8_t reserved : 5;
485 } GimbalData;
486 
487 typedef uint8_t FlightStatus;
488 
489 typedef struct TaskData
490 {
491  unsigned char cmdSequence;
492  unsigned char cmdData;
493 } TaskData;
494 
497 typedef struct RTKData
498 {
499  uint32_t date;
500  uint32_t time;
501  float64_t longitude;
502  float64_t latitude;
504  float32_t Hmsl;
505 
506  float32_t velocityNorth;
507  float32_t velocityEast;
509  float32_t velocityGround;
510 
511  int16_t yaw;
512  uint8_t posFlag;
513  uint8_t yawFlag;
514 
515 } RTKData;
516 
519 typedef struct GPSData
520 {
521  uint32_t date;
522  uint32_t time;
523  int32_t longitude;
524  int32_t latitude;
526  int32_t Hmsl;
527 
528  float32_t velocityNorth;
529  float32_t velocityEast;
531  float32_t velocityGround;
532 
533 } GPSData;
534 
535 #ifndef SDK_DEV
536 typedef struct BroadcastData
538 {
539  unsigned short dataFlag;
540  TimeStampData timeStamp;
541  QuaternionData q;
544  VelocityData v;
547  PositionData pos;
550  GPSData gps;
551  RTKData rtk;
554  GimbalData gimbal;
555  FlightStatus status;
556  BatteryData battery;
557  CtrlInfoData ctrlInfo;
558 
561  uint8_t activation;
562 } BroadcastData;
563 #endif // SDK_DEV
564 
565 typedef struct VirtualRCSetting
566 {
567  uint8_t enable : 1;
568  uint8_t cutoff : 1;
569  uint8_t reserved : 6;
571 
572 typedef struct VirtualRCData
573 {
577  uint32_t roll;
578  uint32_t pitch;
579  uint32_t throttle;
580  uint32_t yaw;
581  uint32_t gear;
582  uint32_t reserved;
583  uint32_t mode;
584  uint32_t Channel_07;
585  uint32_t Channel_08;
586  uint32_t Channel_09;
587  uint32_t Channel_10;
588  uint32_t Channel_11;
589  uint32_t Channel_12;
590  uint32_t Channel_13;
591  uint32_t Channel_14;
592  uint32_t Channel_15;
593 } VirtualRCData;
594 
595 typedef struct ActivateData
596 {
597  unsigned int ID;
598  unsigned int reserved;
599  unsigned int version;
600  unsigned char iosID[32];
601  char *encKey;
602 } ActivateData;
603 
604 typedef struct VersionData
605 {
606  unsigned short version_ack;
607  unsigned int version_crc;
608  char version_ID[11];
609  char version_name[32];
610  DJI::onboardSDK::Version version;
611 } VersionData;
612 
613 #pragma pack()
614 #ifdef SDK_DEV
615 #include "devtype.h"
616 #endif // SDK_DEV
617 } // namespace onboardSDK
618 } // namespace DJI
619 
620 #define PRO_PURE_DATA_MAX_SIZE 1007 // 2^10 - header size
621 const size_t MMU_TABLE_NUM = 32;
622 
623 
624 #endif // DJI_TYPE
unsigned int reversed1
Definition: DJI_Type.h:135
-
Definition: DJI_Type.h:440
-
Definition: DJI_Type.h:315
-
Definition: DJI_Type.h:222
-
uint8_t MissionACK
Definition: DJI_Type.h:312
-
Definition: DJI_Type.h:519
-
Definition: DJI_Type.h:604
-
Definition: DJI_Type.h:432
-
uint32_t time
Definition: DJI_Type.h:471
-
Definition: DJI_Type.h:572
-
void(* CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData)
The CallBack function pointer is used as an argument in api->send calls.
Definition: DJI_Type.h:142
-
Definition: DJI_Type.h:565
-
uint8_t activation
Definition: DJI_Type.h:561
-
MagnetData mag
Definition: DJI_Type.h:549
-
Definition: DJI_Type.h:231
-
float32_t Hmsl
Definition: DJI_Type.h:504
-
Definition: DJI_Type.h:334
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
Definition: DJI_Type.h:468
-
Definition: DJI_Type.h:184
-
Definition: DJI_Type.h:198
-
Definition: DJI_Type.h:489
-
Definition: DJI_Type.h:375
-
CommonData w
Definition: DJI_Type.h:546
-
unsigned int reversed0
Definition: DJI_Type.h:130
-
CommonData a
Definition: DJI_Type.h:543
-
Definition: DJI_Type.h:176
-
Definition: DJI_Type.h:392
-
uint32_t Version
Different version strings define SDK/Drone combination. Only the ones listed below are available...
Definition: DJI_Version.h:33
-
Definition: DJI_Type.h:421
-
Definition: DJI_Type.h:595
-
Definition: DJI_Type.h:164
-
Definition: DJI_Type.h:284
-
RadioData rc
Definition: DJI_Type.h:553
-
Optional macro definitions for DJI Onboard SDK. Use for debugging.
-
Definition: DJI_Type.h:410
-
Definition: DJI_Type.h:321
-
Definition: DJI_Type.h:476
-
Definition: DJI_Type.h:206
-
Definition: DJI_Type.h:382
-
Definition: DJI_Type.h:151
-
Definition: DJI_Type.h:245
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
-
BatteryData battery
Definition: DJI_Type.h:556
-
The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.
Definition: DJI_Type.h:145
-
float32_t velocityGround
Definition: DJI_Type.h:531
-
The Header struct is meant to handle the open protocol header.
Definition: DJI_Type.h:122
-
Definition: DJI_Type.h:351
-
Definition: DJI_Type.h:497
-
Definition: DJI_Type.h:327
-
Definition: DJI_Type.h:357
+Go to the documentation of this file.
1 
20 #ifndef DJI_TYPE
21 #define DJI_TYPE
22 
23 #include "DJI_Config.h"
24 #include "DJICommonType.h"
25 #include <stdio.h>
26 
27 #define NAME(x) #x
28 
29 #ifdef __GNUC__
30 #define __UNUSED __attribute__((__unused__))
31 #define __DELETE(x) delete (char *) x
32 #else
33 #define __UNUSED
34 #define __DELETE(x) delete x
35 
36 
38 #ifndef STM32
39 #pragma warning(disable : 4100)
40 #pragma warning(disable : 4800)
41 #pragma warning(disable : 4996)
42 #pragma warning(disable : 4244)
43 #pragma warning(disable : 4267)
44 #pragma warning(disable : 4700)
45 #pragma warning(disable : 4101)
46 #endif // STM32
47 #endif //__GNUC__
48 
49 #ifdef WIN32
50 #define __func__ __FUNCTION__
51 #endif // WIN32
52 
53 #define API_LOG(driver, title, fmt, ...) \
54  if ((title)) \
55  { \
56  int len = (sprintf(DJI::onboardSDK::buffer, "%s %s,line %d: " fmt, \
57  (title) ? (title) : "NONE", __func__, __LINE__, ##__VA_ARGS__)); \
58  if ((len != -1) && (len < 1024)) \
59  (driver)->displayLog(); \
60  else \
61  (driver)->displayLog("ERROR: log printer inner fault\n"); \
62  }
63 #ifdef API_DEBUG_DATA
64 #define DEBUG_LOG "DEBUG"
65 #else
66 #define DEBUG_LOG 0
67 #endif
68 
69 #ifdef API_ERROR_DATA
70 #define ERROR_LOG "ERROR"
71 #else
72 #define ERROR_LOG 0
73 #endif
74 
75 #ifdef API_BUFFER_DATA
76 #define BUFFER_LOG "BUFFER"
77 #else
78 #define BUFFER_LOG 0
79 #endif
80 
81 #ifdef API_STATUS_DATA
82 #define STATUS_LOG "STATUS"
83 #else
84 #define STATUS_LOG 0
85 #endif
86 
87 #ifdef API_MISSION_DATA
88 #define MISSION_LOG "MISSION"
89 #else
90 #define MISSION_LOG 0
91 #endif
92 
93 #ifdef API_RTK_DEBUG
94 #define RTK_LOG "MISSION"
95 #else
96 #define RTK_LOG 0
97 #endif
98 
100 #ifdef ARMCC
101 #pragma anon_unions
102 #endif
103 
104 namespace DJI
105 {
106 namespace onboardSDK
107 {
108 
109 const size_t bufsize = 1024;
110 extern char buffer[];
111 extern uint8_t encrypt;
112 
113 const size_t SESSION_TABLE_NUM = 32;
114 const size_t CALLBACK_LIST_NUM = 10;
115 
116 class CoreAPI;
117 
118 typedef struct Header
119 {
120  unsigned int sof : 8;
121  unsigned int length : 10;
122  unsigned int version : 6;
123  unsigned int sessionID : 5;
124  unsigned int isAck : 1;
126  unsigned int reversed0 : 2; // always 0
127 
128  unsigned int padding : 5;
129  unsigned int enc : 3;
131  unsigned int reversed1 : 24;
132 
133  unsigned int sequenceNumber : 16;
134  unsigned int crc : 16;
135 } Header;
136 
137 typedef void (*CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData);
138 
139 typedef struct CallBackHandler
140 {
141  CallBack callback;
142  UserData userData;
144 
145 typedef struct Command
146 {
147  unsigned short sessionMode : 2;
148  unsigned short encrypt : 1;
149  unsigned short retry : 13;
150  unsigned short timeout; // unit is ms
151  size_t length;
152  uint8_t *buf;
153  CallBack handler;
154  UserData userData;
155 } Command;
156 
158 typedef struct SDKFilter
159 {
160  unsigned short reuseIndex;
161  unsigned short reuseCount;
162  unsigned short recvIndex;
163  unsigned char recvBuf[BUFFER_SIZE];
164  // for encrypt
165  unsigned char sdkKey[32];
166  unsigned char encode;
167 } SDKFilter;
168 
170 typedef struct MMU_Tab
171 {
172  unsigned int tabIndex : 8;
173  unsigned int usageFlag : 8;
174  unsigned int memSize : 16;
175  unsigned char *pmem;
176 } MMU_Tab;
177 
178 typedef struct CMDSession
179 {
180  uint32_t sessionID : 5;
181  uint32_t usageFlag : 1;
182  uint32_t sent : 5;
183  uint32_t retry : 5;
184  uint32_t timeout : 16;
185  MMU_Tab *mmu;
186  CallBack handler;
187  UserData userData;
188  uint32_t preSeqNum;
189  time_ms preTimestamp;
190 } CMDSession;
191 
192 typedef struct ACKSession
193 {
194  uint32_t sessionID : 5;
195  uint32_t sessionStatus : 2;
196  uint32_t res : 25;
197  MMU_Tab *mmu;
198 } ACKSession;
199 
200 typedef struct Ack
201 {
202  uint16_t sessionID : 8;
203  uint16_t encrypt : 8;
204  uint16_t seqNum;
205  uint32_t length;
206  uint8_t *buf;
207 } Ack;
208 
209 #pragma pack(1)
210 
211 typedef uint8_t BatteryData;
212 typedef uint8_t MissionACK;
213 
214 typedef struct GimbalAngleData
215 {
216  int16_t yaw;
217  int16_t roll;
218  int16_t pitch;
219  uint8_t mode;
220  uint8_t duration;
222 
223 typedef struct GimbalSpeedData
224 {
225  int16_t yaw;
226  int16_t roll;
227  int16_t pitch;
228  uint8_t reserved; // always 0x80;
230 
231 typedef float float32_t;
232 typedef double float64_t;
233 
234 typedef struct QuaternionData
235 {
236  float32_t q0;
237  float32_t q1;
238  float32_t q2;
239  float32_t q3;
241 
243 typedef struct CommonData
244 {
245  float32_t x;
246  float32_t y;
247  float32_t z;
248 } CommonData;
249 
252 typedef struct Vector3fData
253 {
254  float32_t x;
255  float32_t y;
256  float32_t z;
257 } Vector3fData;
258 
259 typedef struct VelocityData
260 {
261  float32_t x;
262  float32_t y;
263  float32_t z;
264  uint8_t health : 1;
265  uint8_t sensorID : 4;
266  uint8_t reserve : 3;
267 } VelocityData;
268 
269 typedef struct PositionData
270 {
271  float64_t latitude;
272  float64_t longitude;
276  float32_t altitude;
277 
281  float32_t height;
282 
283  uint8_t health;
284 } PositionData;
285 
287 typedef struct RadioData
288 {
289  int16_t roll;
290  int16_t pitch;
291  int16_t yaw;
292  int16_t throttle;
293  int16_t mode;
294  int16_t gear;
295 } RadioData;
296 
298 typedef struct RCData
299 {
300  int16_t roll;
301  int16_t pitch;
302  int16_t yaw;
303  int16_t throttle;
304  int16_t mode;
305  int16_t gear;
306 } RCData;
307 
309 typedef struct MagnetData
310 {
311  int16_t x;
312  int16_t y;
313  int16_t z;
314 } MagnetData;
315 
317 typedef struct MagData
318 {
319  int16_t x;
320  int16_t y;
321  int16_t z;
322 } MagData;
323 
326 typedef struct GPSPositionData
327 {
328  float64_t latitude;
329  float64_t longitude;
331  float64_t altitude;
332 
334 
335 typedef struct CtrlInfoData
336 {
337  uint8_t mode;
339  uint8_t deviceStatus : 3; /*0->rc 1->app 2->serial*/
340  uint8_t flightStatus : 1; /*1->opensd 0->close*/
341  uint8_t vrcStatus : 1;
342  uint8_t reserved : 3;
343 } CtrlInfoData;
344 
345 typedef struct TimeStampData
346 {
348  uint32_t time;
349  uint32_t nanoTime;
350  uint8_t syncFlag;
351 } TimeStampData;
352 
353 typedef struct GimbalData
354 {
355  float32_t roll;
356  float32_t pitch;
357  float32_t yaw;
358  uint8_t pitchLimit : 1;
359  uint8_t rollLimit : 1;
360  uint8_t yawLimit : 1;
361  uint8_t reserved : 5;
362 } GimbalData;
363 
364 typedef uint8_t FlightStatus;
365 
366 typedef struct TaskData
367 {
368  unsigned char cmdSequence;
369  unsigned char cmdData;
370 } TaskData;
371 
373 typedef struct RTKData
374 {
375  uint32_t date;
376  uint32_t time;
377  float64_t longitude;
378  float64_t latitude;
380  float32_t Hmsl;
381 
382  float32_t velocityNorth;
383  float32_t velocityEast;
385  float32_t velocityGround;
386 
387  int16_t yaw;
388  uint8_t posFlag;
389  uint8_t yawFlag;
390 
391 } RTKData;
392 
394 typedef struct GPSData
395 {
396  uint32_t date;
397  uint32_t time;
398  int32_t longitude;
399  int32_t latitude;
401  int32_t Hmsl;
402 
403  float32_t velocityNorth;
404  float32_t velocityEast;
406  float32_t velocityGround;
407 
408 } GPSData;
409 
410 #ifndef SDK_DEV
411 typedef struct BroadcastData
413 {
414  unsigned short dataFlag;
415  TimeStampData timeStamp;
416  QuaternionData q;
419  VelocityData v;
422  PositionData pos;
425  GPSData gps;
426  RTKData rtk;
429  GimbalData gimbal;
430  FlightStatus status;
431  BatteryData battery;
432  CtrlInfoData ctrlInfo;
433 
436  uint8_t activation;
437 } BroadcastData;
438 #endif // SDK_DEV
439 
440 typedef struct VirtualRCSetting
441 {
442  uint8_t enable : 1;
443  uint8_t cutoff : 1;
444  uint8_t reserved : 6;
446 
447 typedef struct VirtualRCData
448 {
452  uint32_t roll;
453  uint32_t pitch;
454  uint32_t throttle;
455  uint32_t yaw;
456  uint32_t gear;
457  uint32_t reserved;
458  uint32_t mode;
459  uint32_t Channel_07;
460  uint32_t Channel_08;
461  uint32_t Channel_09;
462  uint32_t Channel_10;
463  uint32_t Channel_11;
464  uint32_t Channel_12;
465  uint32_t Channel_13;
466  uint32_t Channel_14;
467  uint32_t Channel_15;
468 } VirtualRCData;
469 
470 #pragma pack()
471 #ifdef SDK_DEV
472 #include "devtype.h"
473 #endif // SDK_DEV
474 } // namespace onboardSDK
475 } // namespace DJI
476 
477 #define PRO_PURE_DATA_MAX_SIZE 1007 // 2^10 - header size
478 const size_t MMU_TABLE_NUM = 32;
479 
480 
481 #endif // DJI_TYPE
unsigned int reversed1
Definition: DJI_Type.h:131
+
Definition: DJI_Type.h:317
+
Definition: DJI_Type.h:214
+
Definition: DJI_Type.h:394
+
Definition: DJI_Type.h:309
+
uint32_t time
Definition: DJI_Type.h:348
+
Definition: DJI_Type.h:447
+
Definition: DJI_Type.h:440
+
uint8_t activation
Definition: DJI_Type.h:436
+
MagnetData mag
Definition: DJI_Type.h:424
+
Definition: DJI_Type.h:223
+
float32_t Hmsl
Definition: DJI_Type.h:380
+
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_Type.h:178
+
Definition: DJI_Type.h:192
+
Definition: DJI_Type.h:366
+
Definition: DJI_Type.h:252
+
CommonData w
Definition: DJI_Type.h:421
+
unsigned int reversed0
Definition: DJI_Type.h:126
+
CommonData a
Definition: DJI_Type.h:418
+
Definition: DJI_Type.h:170
+
Definition: DJI_Type.h:269
+
Definition: DJI_Type.h:298
+
Definition: DJI_Type.h:158
+
RadioData rc
Definition: DJI_Type.h:428
+ +
Definition: DJI_Type.h:287
+
Definition: DJI_Type.h:353
+
Definition: DJI_Type.h:200
+
Definition: DJI_Type.h:259
+
Definition: DJI_Type.h:145
+
BatteryData battery
Definition: DJI_Type.h:431
+
Definition: DJI_Type.h:139
+
float32_t velocityGround
Definition: DJI_Type.h:406
+
Definition: DJI_Type.h:118
+
Definition: DJI_Type.h:373
+
Definition: DJI_Type.h:234
Definition: DJI_Mission.cpp:16
-
float32_t altitude
not supported yet
Definition: DJI_Type.h:279
-
float32_t height
Definition: DJI_Type.h:404
-
uint32_t roll
Definition: DJI_Type.h:577
-
int32_t Hmsl
Definition: DJI_Type.h:526
-
Definition: DJI_Type.h:449
-
Definition: DJI_Type.h:537
-
float64_t longitude
Definition: DJI_Type.h:278
-
float32_t velocityGround
Definition: DJI_Type.h:509
-
Definition: DJI_Type.h:366
-
float32_t altitude
Definition: DJI_Type.h:399
-
Definition: DJI_Type.h:265
-
Definition: DJI_Type.h:345
-
float64_t altitude
Definition: DJI_Type.h:454
-
Definition: DJI_Type.h:458
-
Common Type definition for DJI onboardSDK library. Officially Maintained.
+
float32_t height
Definition: DJI_Type.h:281
+
uint32_t roll
Definition: DJI_Type.h:452
+
int32_t Hmsl
Definition: DJI_Type.h:401
+
Definition: DJI_Type.h:326
+
Definition: DJI_Type.h:412
+
float32_t velocityGround
Definition: DJI_Type.h:385
+
Definition: DJI_Type.h:243
+
float32_t altitude
Definition: DJI_Type.h:276
+
float64_t altitude
Definition: DJI_Type.h:331
+
Definition: DJI_Type.h:335
+
diff --git a/dji_sdk_doc/doxygen/html/DJI__Version_8h.html b/dji_sdk_doc/doxygen/html/DJI__Version_8h.html index d08eab02..499fd6d5 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Version_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__Version_8h.html @@ -95,9 +95,6 @@
DJI_Version.h File Reference
- -

Drone/SDK Version definition for DJI onboardSDK library Officially Maintained. -More...

#include <stdint.h>

Go to the source code of this file.

@@ -114,9 +111,7 @@ - - +

Typedefs

-typedef uint32_t DJI::onboardSDK::Version
 Different version strings define SDK/Drone combination. Only the ones listed below are available.
typedef uint32_t DJI::onboardSDK::Version
 

@@ -135,9 +130,9 @@

 

Detailed Description

-

Drone/SDK Version definition for DJI onboardSDK library Officially Maintained.

-
Version
3.1.7
+
Version
3.1.7
Date
Jul 01 2016
+

Drone/SDK Version definition for DJI onboardSDK library Officially Maintained

Macro Definition Documentation

@@ -177,12 +172,26 @@
Value:
(((a << 24) & 0xff000000) | ((b << 16) & 0x00ff0000) | ((c << 8) & 0x0000ff00) | \
(d & 0x000000ff))
Attention
Do not modify any definition in this file if you are not sure what are you doing. DJI will not provide any support for changes made to this file.
+
+
+

Typedef Documentation

+ +
+
+ + + + +
typedef uint32_t DJI::onboardSDK::Version
+
+
Todo:
better version control structure
+
diff --git a/dji_sdk_doc/doxygen/html/DJI__Version_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__Version_8h_source.html index 615b3e8b..4b103d52 100644 --- a/dji_sdk_doc/doxygen/html/DJI__Version_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__Version_8h_source.html @@ -90,13 +90,13 @@
DJI_Version.h
-Go to the documentation of this file.
1 
19 #ifndef DJI_VERSION_H
20 #define DJI_VERSION_H
21 
22 #include <stdint.h>
23 
24 #define MAKE_VERSION(a, b, c, d) \
25  (((a << 24) & 0xff000000) | ((b << 16) & 0x00ff0000) | ((c << 8) & 0x0000ff00) | \
26  (d & 0x000000ff))
27 
28 namespace DJI
29 {
30 namespace onboardSDK
31 {
33 typedef uint32_t Version;
34 
35 const Version versionM100_23 = (MAKE_VERSION(2, 3, 10, 0));
36 const Version versionM100_31 = (MAKE_VERSION(3, 1, 10, 0));
37 const Version versionA3_31 = (MAKE_VERSION(3, 1, 100, 0));
38 const Version SDK_VERSION = versionM100_31;
39 
40 #ifdef SDK_DEV
41 #include "dev.h"
42 #endif // SDK_DEV
43 
44 } // namespace DJI
45 } // namespace onboardSDK
46 
47 #endif // DJI_VERSION_H
uint32_t Version
Different version strings define SDK/Drone combination. Only the ones listed below are available...
Definition: DJI_Version.h:33
-
#define MAKE_VERSION(a, b, c, d)
Definition: DJI_Version.h:24
+Go to the documentation of this file.
1 
20 #ifndef DJI_VERSION_H
21 #define DJI_VERSION_H
22 
23 #include <stdint.h>
24 
25 #define MAKE_VERSION(a, b, c, d) \
26  (((a << 24) & 0xff000000) | ((b << 16) & 0x00ff0000) | ((c << 8) & 0x0000ff00) | \
27  (d & 0x000000ff))
28 
29 namespace DJI
30 {
31 namespace onboardSDK
32 {
34 typedef uint32_t Version;
35 
36 const Version versionM100_23 = (MAKE_VERSION(2, 3, 10, 0));
37 const Version versionM100_31 = (MAKE_VERSION(3, 1, 10, 0));
38 const Version versionA3_31 = (MAKE_VERSION(3, 1, 100, 0));
39 const Version SDK_VERSION = versionM100_31;
40 
41 #ifdef SDK_DEV
42 #include "dev.h"
43 #endif // SDK_DEV
44 
45 } // namespace DJI
46 } // namespace onboardSDK
47 
48 #endif // DJI_VERSION_H
uint32_t Version
Definition: DJI_Version.h:34
+
#define MAKE_VERSION(a, b, c, d)
Definition: DJI_Version.h:25
Definition: DJI_Mission.cpp:16
diff --git a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8cpp.html index bbd03977..616a9910 100644 --- a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8cpp.html @@ -90,19 +90,16 @@
DJI_VirtualRC.cpp File Reference
- -

Virtual Radio Control API for DJI onboardSDK library. -More...

#include "DJI_VirtualRC.h"

Detailed Description

-

Virtual Radio Control API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Virtual Radio Control API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html index 610f0b14..6e52ea6e 100644 --- a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html @@ -93,9 +93,6 @@
DJI_VirtualRC.h File Reference
- -

Virtual Radio Control API for DJI onboardSDK library. -More...

#include "DJI_API.h"

Go to the source code of this file.

@@ -112,14 +109,14 @@  

Detailed Description

-

Virtual Radio Control API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Virtual Radio Control API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h_source.html index d2b3b3ca..336537d1 100644 --- a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h_source.html @@ -90,25 +90,25 @@
DJI_VirtualRC.h
-Go to the documentation of this file.
1 
13 #ifndef DJI_VIRTUALRC_H
14 #define DJI_VIRTUALRC_H
15 
16 #include "DJI_API.h"
17 
18 namespace DJI
19 {
20 namespace onboardSDK
21 {
22 
24 class VirtualRC
25 {
26  public:
27  enum CutOff
28  {
29  CutOff_ToLogic = 0,
30  CutOff_ToRealRC = 1
31  };
32 
33  public:
34  VirtualRC(CoreAPI *ControlAPI = 0);
35 
82  void setControl(bool enable, CutOff cutoffType);
83  void sendData(VirtualRCData Data);
84 
85  void sendData();
86  void resetData();
87 
88  void sendSafeModeData();
89  void neutralVRCSticks();
90 
91  VirtualRCData getVRCData() const;
93  RadioData getRCData() const;
94 
95  void setVRCData(const VirtualRCData &value);
96 
97  bool isVirtualRC() const;
98 
99  public:
101  static RadioData toRadioData(VirtualRCData &vData);
102  static RCData toRCData(VirtualRCData &vData);
103 
104  static VirtualRCData toVirtualRCData(RadioData &rData);
105 
106  public:
107  CoreAPI *getApi() const;
108  void setApi(CoreAPI *value);
109 
110  private:
111  CoreAPI *api;
112  VirtualRCData vrcData;
113 };
114 
115 }
116 }
117 
118 #endif
void resetData()
This function will not be maintained and will be deprecated in a future release. Please use resetVRCD...
Definition: DJI_VirtualRC.cpp:45
-
static RadioData toRadioData(VirtualRCData &vData)
Definition: DJI_VirtualRC.cpp:96
-
Definition: DJI_Type.h:572
+Go to the documentation of this file.
1 
14 #ifndef DJI_VIRTUALRC_H
15 #define DJI_VIRTUALRC_H
16 
17 #include "DJI_API.h"
18 
19 namespace DJI
20 {
21 namespace onboardSDK
22 {
23 
25 class VirtualRC
26 {
27  public:
28  enum CutOff
29  {
30  CutOff_ToLogic = 0,
31  CutOff_ToRealRC = 1
32  };
33 
34  public:
35  VirtualRC(CoreAPI *ControlAPI = 0);
36 
83  void setControl(bool enable, CutOff cutoffType);
84  void sendData(VirtualRCData Data);
85 
86  void sendData();
87  void resetData();
88 
89  void sendSafeModeData();
90  void neutralVRCSticks();
91 
92  VirtualRCData getVRCData() const;
94  RadioData getRCData() const;
95 
96  void setVRCData(const VirtualRCData &value);
97 
98  bool isVirtualRC() const;
99 
100  public:
102  static RadioData toRadioData(VirtualRCData &vData);
103  static RCData toRCData(VirtualRCData &vData);
104 
105  static VirtualRCData toVirtualRCData(RadioData &rData);
106 
107  public:
108  CoreAPI *getApi() const;
109  void setApi(CoreAPI *value);
110 
111  private:
112  CoreAPI *api;
113  VirtualRCData vrcData;
114 };
115 
116 }
117 }
118 
119 #endif
void resetData()
This function will not be maintained and will be deprecated in a future release. Please use resetVRCD...
Definition: DJI_VirtualRC.cpp:46
+
static RadioData toRadioData(VirtualRCData &vData)
Definition: DJI_VirtualRC.cpp:97
+
Definition: DJI_Type.h:447
Core API for DJI onboardSDK library.
-
VirtualRC class has all the methods to mimic the RC functionality via OnboardSDK. ...
Definition: DJI_VirtualRC.h:24
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
RadioData getRCData() const
Definition: DJI_VirtualRC.cpp:79
-
Definition: DJI_Type.h:421
-
void setControl(bool enable, CutOff cutoffType)
Definition: DJI_VirtualRC.cpp:23
-
Definition: DJI_Type.h:410
-
void neutralVRCSticks()
Definition: DJI_VirtualRC.cpp:72
-
void sendData()
This function will be deprecated in a future release. Please use sendData(VirtualRCData Data) instead...
Definition: DJI_VirtualRC.cpp:39
-
VirtualRCData getVRCData() const
New function - this will replace sendSafeModeData() in a future release.
Definition: DJI_VirtualRC.cpp:84
+
VirtualRC class has all the methods to mimic the RC functionality via OnboardSDK. ...
Definition: DJI_VirtualRC.h:25
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
+
RadioData getRCData() const
Definition: DJI_VirtualRC.cpp:80
+
Definition: DJI_Type.h:298
+
void setControl(bool enable, CutOff cutoffType)
Definition: DJI_VirtualRC.cpp:24
+
Definition: DJI_Type.h:287
+
void neutralVRCSticks()
Definition: DJI_VirtualRC.cpp:73
+
void sendData()
This function will be deprecated in a future release. Please use sendData(VirtualRCData Data) instead...
Definition: DJI_VirtualRC.cpp:40
+
VirtualRCData getVRCData() const
New function - this will replace sendSafeModeData() in a future release.
Definition: DJI_VirtualRC.cpp:85
Definition: DJI_Mission.cpp:16
-
void sendSafeModeData()
This function will be deprecated in the future. Please use neutralVRCSticks() instead.
Definition: DJI_VirtualRC.cpp:66
+
void sendSafeModeData()
This function will be deprecated in the future. Please use neutralVRCSticks() instead.
Definition: DJI_VirtualRC.cpp:67
diff --git a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html index c099ebb8..5cf446d7 100644 --- a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html +++ b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html @@ -90,20 +90,17 @@
DJI_WayPoint.cpp File Reference
- -

Waypoint flight API for DJI onboardSDK library. -More...

#include "DJI_WayPoint.h"
#include <string.h>

Detailed Description

-

Waypoint flight API for DJI onboardSDK library.

-
Version
3.1.7
+
Version
3.1.7
Date
July 1st, 2016
+

Waypoint flight API for DJI onboardSDK library

diff --git a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html index 566e1a06..ce321659 100644 --- a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html +++ b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html @@ -88,21 +88,28 @@
DJI_WayPoint.h File Reference
- -

Waypoint flight API for DJI onboardSDK library. -More...

-
#include "DJI_Mission.h"
-#include <stdexcept>
+
#include "DJI_Mission.h"

Go to the source code of this file.

+ + + + + + + + + +

Classes

struct  DJI::onboardSDK::WayPointInitData
 
struct  DJI::onboardSDK::WayPointData
 
struct  DJI::onboardSDK::WayPointVelocityACK
 
struct  DJI::onboardSDK::WayPointInitACK
 
struct  DJI::onboardSDK::WayPointDataACK
 
class  DJI::onboardSDK::WayPoint
 
@@ -110,16 +117,39 @@ Namespaces +
 DJI
 
+ + + + + + + + + + +

+Typedefs

+typedef struct DJI::onboardSDK::WayPointInitData DJI::onboardSDK::WayPointInitData
 
+typedef struct DJI::onboardSDK::WayPointData DJI::onboardSDK::WayPointData
 
+typedef struct DJI::onboardSDK::WayPointVelocityACK DJI::onboardSDK::WayPointVelocityACK
 
+typedef struct DJI::onboardSDK::WayPointInitACK DJI::onboardSDK::WayPointInitACK
 
+typedef struct DJI::onboardSDK::WayPointDataACK DJI::onboardSDK::WayPointDataACK
 

Detailed Description

-

Waypoint flight API for DJI onboardSDK library.

-
Version
3.1.7
-
Date
July 1st, 2016
- +
Version
3.0
+
Date
Dec 22, 2015
+

WayPoint API for DJI onboardSDK library

+
Attention
Project configuration:
+
Version
features: -*
+
+V3.0 -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake -*
+
Date
Dec 16, 2015 -*
+
Author
william.wu
diff --git a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h_source.html index 1ac4f95b..4c9b11e2 100644 --- a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h_source.html +++ b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h_source.html @@ -90,26 +90,21 @@
DJI_WayPoint.h
-Go to the documentation of this file.
1 
13 #include "DJI_Mission.h"
14 #include <stdexcept>
15 
16 #ifndef DJI_WAYPOINT_H
17 #define DJI_WAYPOINT_H
18 
19 namespace DJI
20 {
21 namespace onboardSDK
22 {
23 
24 class WayPoint
25 {
26  public:
27 #ifndef STATIC_MEMORY
28  WayPoint(CoreAPI *ControlAPI = 0);
29 #else
30  WayPoint(WayPointData *list, uint8_t len, CoreAPI *ControlAPI = 0);
31 #endif // STATIC_MEMORY
32  void init(WayPointInitData *Info = 0, CallBack callback = 0, UserData userData = 0);
33  MissionACK init(WayPointInitData *Info, int timer);
34  void start(CallBack callback = 0, UserData userData = 0);
35  MissionACK start(int timer);
36  void stop(CallBack callback = 0, UserData userData = 0);
37  MissionACK stop(int timer);
39  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
40  MissionACK pause(bool isPause, int timer);
41  void readInitData(CallBack callback = 0, UserData userData = 0);
42  void readIndexData(uint8_t index, CallBack callback = 0, UserData userData = 0);
43  void readIdleVelocity(CallBack callback = 0, UserData userData = 0);
45  //void uploadAll(CallBack callback = 0, UserData userData = 0);
46  bool uploadIndexData(WayPointData *data, CallBack callback = 0, UserData userData = 0);
48  bool uploadIndexData(uint8_t pos, CallBack callback = 0, UserData userData = 0);
49  void updateIdleVelocity(float32_t meterPreSecond, CallBack callback = 0,
50  UserData userData = 0);
51 
52  void setInfo(const WayPointInitData &value);
53  void setIndex(WayPointData *value, size_t pos);
54  WayPointInitData getInfo() const;
55  WayPointData *getIndex() const;
56  WayPointData *getIndex(size_t pos) const;
57 
58  public:
59  static void idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
60  static void readInitDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
61  static void uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
64 
65  private:
66  CoreAPI *api;
67  WayPointInitData info;
68  WayPointData *index;
69 #ifdef STATIC_MEMORY
70  uint8_t maxIndex;
71 #endif // STATIC_MEMORY
72 };
73 
74 } // namespace onboardSDK
75 } // namespace DJI
76 
77 #endif // DJI_WAYPOINT_H
Mission Framework for DJI onboardSDK library.
-
uint8_t MissionACK
Definition: DJI_Type.h:312
-
void(* CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData)
The CallBack function pointer is used as an argument in api->send calls.
Definition: DJI_Type.h:142
-
Definition: DJI_WayPoint.h:24
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
-
void pause(bool isPause, CallBack callback=0, UserData userData=0)
Definition: DJI_WayPoint.cpp:99
-
void setInfo(const WayPointInitData &value)
Definition: DJI_WayPoint.cpp:181
-
void readIndexData(uint8_t index, CallBack callback=0, UserData userData=0)
-
Definition: DJI_Type.h:284
-
Definition: DJI_Type.h:321
-
void readIdleVelocity(CallBack callback=0, UserData userData=0)
Definition: DJI_WayPoint.cpp:120
-
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
-
The Header struct is meant to handle the open protocol header.
Definition: DJI_Type.h:122
+Go to the documentation of this file.
1 
19 #include "DJI_Mission.h"
20 
21 #ifndef DJI_WAYPOINT_H
22 #define DJI_WAYPOINT_H
23 
24 namespace DJI
25 {
26 namespace onboardSDK
27 {
28 
29 class WayPoint;
30 
31 #pragma pack(1)
32 typedef struct WayPointInitData
33 {
34  uint8_t indexNumber;
35  float32_t maxVelocity;
36  float32_t idleVelocity;
37 
38  uint8_t finishAction;
39  uint8_t executiveTimes;
40  uint8_t yawMode;
41  uint8_t traceMode;
42  uint8_t RCLostAction;
43  uint8_t gimbalPitch;
44  float64_t latitude;
45  float64_t longitude;
46  float32_t altitude;
47 
48  uint8_t reserved[16];
50 
51 typedef struct WayPointData
52 {
53  uint8_t index;
54 
55  float64_t latitude;
56  float64_t longitude;
57  float32_t altitude;
58  float32_t damping;
59 
60  int16_t yaw;
61  int16_t gimbalPitch;
62  uint8_t turnMode;
63 
64  uint8_t reserved[8];
65  uint8_t hasAction;
66  uint16_t actionTimeLimit;
67 
68  uint8_t actionNumber : 4;
69  uint8_t actionRepeat : 4;
70 
71  uint8_t commandList[16];
72  int16_t commandParameter[16];
73 } WayPointData;
74 
75 typedef struct WayPointVelocityACK
76 {
77  uint8_t ack;
78  float32_t idleVelocity;
80 
81 typedef struct WayPointInitACK
82 {
83  uint8_t ack;
84  WayPointInitData data;
86 
87 typedef struct WayPointDataACK
88 {
89  uint8_t ack;
90  uint8_t index;
92 
93 #pragma pack()
94 
95 class WayPoint
96 {
97  public:
98 #ifndef STATIC_MEMORY
99  WayPoint(CoreAPI *ControlAPI = 0);
100 #else
101  WayPoint(WayPointData *list, uint8_t len, CoreAPI *ControlAPI = 0);
102 #endif // STATIC_MEMORY
103  void init(WayPointInitData *Info = 0, CallBack callback = 0, UserData userData = 0);
104  void start(CallBack callback = 0, UserData userData = 0);
105  void stop(CallBack callback = 0, UserData userData = 0);
107  void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
108  void readInitData(CallBack callback = 0, UserData userData = 0);
109  void readIndexData(uint8_t index, CallBack callback = 0, UserData userData = 0);
110  void readIdleVelocity(CallBack callback = 0, UserData userData = 0);
112  //void uploadAll(CallBack callback = 0, UserData userData = 0);
113  bool uploadIndexData(WayPointData *data, CallBack callback = 0, UserData userData = 0);
114  bool uploadIndexData(uint8_t pos, CallBack callback = 0, UserData userData = 0);
115  void updateIdleVelocity(float32_t meterPreSecond, CallBack callback = 0,
116  UserData userData = 0);
117 
118  void setInfo(const WayPointInitData &value);
119  void setIndex(WayPointData *value, size_t pos);
120  WayPointInitData getInfo() const;
121  WayPointData *getIndex() const;
122  WayPointData *getIndex(size_t pos) const;
123 
124  public:
125  static void idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
126  static void readInitDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
127  static void uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi);
130 
131  private:
132  CoreAPI *api;
133  WayPointInitData info;
134  WayPointData *index;
135 #ifdef STATIC_MEMORY
136  uint8_t maxIndex;
137 #endif // STATIC_MEMORY
138 };
139 
140 } // namespace onboardSDK
141 } // namespace DJI
142 
143 #endif // DJI_WAYPOINT_H
Definition: DJI_WayPoint.h:95
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
+
Definition: DJI_WayPoint.h:51
+
Definition: DJI_WayPoint.h:87
+
Definition: DJI_Type.h:118
+
Definition: DJI_WayPoint.h:81
+
Definition: DJI_WayPoint.h:75
Definition: DJI_Mission.cpp:16
-
bool uploadIndexData(WayPointData *data, CallBack callback=0, UserData userData=0)
Definition: DJI_WayPoint.cpp:128
-
Definition: DJI_Type.h:265
+
float32_t altitude
not supported yet
Definition: DJI_WayPoint.h:46
+
float64_t longitude
Definition: DJI_WayPoint.h:45
+
Definition: DJI_WayPoint.h:32
diff --git a/dji_sdk_doc/doxygen/html/annotated.html b/dji_sdk_doc/doxygen/html/annotated.html index 1bb546d8..9b7f8912 100644 --- a/dji_sdk_doc/doxygen/html/annotated.html +++ b/dji_sdk_doc/doxygen/html/annotated.html @@ -93,73 +93,72 @@  NonboardSDK  CAck  CACKSession - CActivateData - CBroadcastData - CCallBackHandlerThe CallBackHandler struct allows users to encapsulate callbacks and data in one struct - CCameraCamera class for controlling camera and gimbal-related functions available through open protocol - CCMDSession - CCommand - CCommonData - CCoreAPICoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform - CCtrlInfoData - CFlightFlight class encapsulates all flight control related functions provided by the DJI OnboardSDK - CFlightData - CFollowFollow class encapsulates all follow control related functions provided by the DJI OnboardSDK - CFollowData - CFollowTarget - CGimbalAngleData - CGimbalData - CGimbalSpeedData - CGPSData - CGPSPositionData - CGSPushData - CHardDriver - CHeaderThe Header struct is meant to handle the open protocol header - CHotPoint - CYawRate - CHotPointACKData - CHotPointData - CHotPointReadACK - CHotPointStartACK - CMagData - CMagnetData - CMissionACKMap - CMissionACKUnion - CMMU_Tab - CPositionData - CQuaternionData - CRadioData - CRCData - CRTKData - CSDKFilter - CTaskData - CTimeStampData - CVector3fData - CVelocityData - CVersionData - CVirtualRCVirtualRC class has all the methods to mimic the RC functionality via OnboardSDK - CVirtualRCData - CVirtualRCSetting - CWayPoint - CWayPointData - CWayPointDataACK - CWayPointInitACK - CWayPointInitData - CWayPointVelocityACK - CEulerAngle - CEulerianAngle - CMeasure - CMeasurement - CSpaceVector - CVector3dData - Creq_id_t - CtagAES256Context + CBroadcastData + CCallBackHandler + CCamera + CCMDSession + CCommand + CCommonData + CCoreAPICoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform + CCtrlInfoData + CFlightFlight class encapsulates all flight control related functions provided by the DJI OnboardSDK + CFlightData + CFollowFollow class encapsulates all follow control related functions provided by the DJI OnboardSDK + CFollowData + CFollowTarget + CGimbalAngleData + CGimbalData + CGimbalSpeedData + CGPSData + CGPSPositionData + CGSPushData + CHardDriver + CHeader + CHotPoint + CReadACK + CStartACK + CYawRate + CHotPointACKData + CHotPointData + CMagData + CMagnetData + CMissionACKMap + CMMU_Tab + CPositionData + CQuaternionData + CRadioData + CRCData + CRTKData + CSDKFilter + CTaskData + CTimeStampData + CVector3fData + CVelocityData + CVirtualRCVirtualRC class has all the methods to mimic the RC functionality via OnboardSDK + CVirtualRCData + CVirtualRCSetting + CWayPoint + CWayPointData + CWayPointDataACK + CWayPointInitACK + CWayPointInitData + CWayPointVelocityACK + CEulerAngle + CEulerianAngle + CMeasure + CMeasurement + CSpaceVector + CVector3dData + CActivateData + Creq_id_t + CtagAES256Context + CVersionData
diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera-members.html index 1b77f12d..4a1dda19 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera-members.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera.html index 921f5938..ca703835 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Camera.html @@ -95,11 +95,6 @@
DJI::onboardSDK::Camera Class Reference
- -

Camera class for controlling camera and gimbal-related functions available through open protocol. - More...

- -

#include <DJI_Camera.h>

@@ -154,9 +149,7 @@ void 

Public Types

setApi (CoreAPI *value)
 
-

Detailed Description

-

Camera class for controlling camera and gimbal-related functions available through open protocol.

-

Member Function Documentation

+

Member Function Documentation

@@ -197,7 +190,7 @@
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 8c8fcbce..0a0758fb 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 @@ -95,9 +95,7 @@

This is the complete list of members for DJI::onboardSDK::CoreAPI, including all inherited members.

- - - + @@ -107,38 +105,20 @@ - - - - - - + + - - - - + + - - - - - - - - - - + + - - - - @@ -146,70 +126,38 @@ - - - - - + - - - - - - - - - - + + - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + - - - - - -
ack(req_id_t req_id, unsigned char *ackdata, int len) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
ack_dataDJI::onboardSDK::CoreAPI
activate(ActivateData *data, CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
activate(ActivateData *data, int timeout)DJI::onboardSDK::CoreAPI
activate(ActivateData *data, CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
activateCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIstatic
byteHandler(const uint8_t in_data)DJI::onboardSDK::CoreAPI
byteStreamHandler(uint8_t *buffer, size_t size)DJI::onboardSDK::CoreAPI
decodeACKStatus(unsigned short ack)DJI::onboardSDK::CoreAPI
decodeMissionStatus(uint8_t ack)DJI::onboardSDK::CoreAPI
getAccountData() const DJI::onboardSDK::CoreAPI
getACKFrameStatus() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
getActivateMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getArmMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getBatteryCapacity() const DJI::onboardSDK::CoreAPI
getBroadcastData() const DJI::onboardSDK::CoreAPI
getBroadcastFrameStatus() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
getBatteryCapacity() const DJI::onboardSDK::CoreAPI
getBroadcastData() const DJI::onboardSDK::CoreAPI
getCtrlInfo() const (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
getDisArmMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getDriver() const DJI::onboardSDK::CoreAPI
getDroneVersion(CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
getDroneVersion(int timeout)DJI::onboardSDK::CoreAPI
getDriver() const DJI::onboardSDK::CoreAPI
getDroneVersion(CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
getDroneVersionCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIstatic
getFilter() const DJI::onboardSDK::CoreAPI
getFlightStatus() const DJI::onboardSDK::CoreAPI
getFollowData() const (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
getFollowMeMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getGoHomeMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getHotPointData() const DJI::onboardSDK::CoreAPI
getLandingMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getObtainControlMobileCMD()DJI::onboardSDK::CoreAPIinline
getReleaseControlMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getSDKVersion() const DJI::onboardSDK::CoreAPI
getStartVideoMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getStopVideoMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getTakeOffMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getTakePhotoMobileCMD() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
getSDKVersion() const DJI::onboardSDK::CoreAPI
getSessionStatus() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
getTime() const DJI::onboardSDK::CoreAPI
getWayPointData() const DJI::onboardSDK::CoreAPI
hotpointReadACK (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
missionACKUnion (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
notifyCaller(Header *protocolHeader)DJI::onboardSDK::CoreAPI
parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0)DJI::onboardSDK::CoreAPI
readPoll(void) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
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)DJI::onboardSDK::CoreAPI
send(unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, size_t len, int timeout=0, int retry_time=1, CallBack ack_handler=0, UserData userData=0)DJI::onboardSDK::CoreAPI
sendPoll(void)DJI::onboardSDK::CoreAPI
sendToMobile(uint8_t *data, uint8_t len, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIstatic
serialDevice (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setAccountData(const ActivateData &value)DJI::onboardSDK::CoreAPI
setACKFrameStatus(uint32_t usageFlag)DJI::onboardSDK::CoreAPI
setActivateMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setActivateMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setAccountData(const ActivateData &value)DJI::onboardSDK::CoreAPI
setActivation(bool isActivated)DJI::onboardSDK::CoreAPI
setArmMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setArmMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setBroadcastCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setBroadcastCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setBroadcastFrameStatus(bool isFrame) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
setBroadcastFreq(uint8_t *dataLenIs16, int timeout)DJI::onboardSDK::CoreAPI
setBroadcastFreqDefaults()DJI::onboardSDK::CoreAPI
setBroadcastFreqDefaults(int timeout)DJI::onboardSDK::CoreAPI
setBroadcastFreqToZero() (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setControl(bool enable, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setControl(bool enable, int timeout)DJI::onboardSDK::CoreAPI
setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
setControl(bool enable, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setControlCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIstatic
setDisArmMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setDisArmMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setDriver(HardDriver *value)DJI::onboardSDK::CoreAPI
setFollowCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setFollowCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setFollowData(bool value)DJI::onboardSDK::CoreAPI
setFollowMeMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setFrequencyCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIstatic
setFromMobileCallback(CallBackHandler FromMobileEntrance) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setFromMobileCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setGoHomeMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setGoHomeMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setHotPointCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setHotPointCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setHotPointData(bool value)DJI::onboardSDK::CoreAPI
setKey(const char *key) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setLandingMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setLandingMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setMisssionCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setMisssionCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setObtainControlMobileCallback(CallBackHandler callback)DJI::onboardSDK::CoreAPIinline
setObtainControlMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setReleaseControlMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setReleaseControlMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setStartVideoMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setStartVideoMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setStopVideoMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setStopVideoMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setFrequencyCallback(CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIstatic
setFromMobileCallback(CallBackHandler FromMobileEntrance) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setFromMobileCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setHotPointCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setHotPointCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setHotPointData(bool value)DJI::onboardSDK::CoreAPI
setKey(const char *key) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setMisssionCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setMisssionCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setSessionStatus(uint32_t usageFlag) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setSyncFreq(uint32_t freqInHz) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setTakeOffMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setTakeOffMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setTakePhotoMobileCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setTakePhotoMobileCMD(bool userInput) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setVersion(const Version &value)DJI::onboardSDK::CoreAPI
setWayPointCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPIinline
setWayPointCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setWayPointData(bool value)DJI::onboardSDK::CoreAPI
setWayPointEventCallback(CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
setWayPointEventCallback(CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI)DJI::onboardSDK::CoreAPI
stopCondDJI::onboardSDK::CoreAPI
waypointInitACK (defined in DJI::onboardSDK::CoreAPI)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 496e6a52..9e0c68d7 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 @@ -90,7 +90,6 @@
DJI::onboardSDK::CoreAPI Class Reference
@@ -104,12 +103,6 @@ - - - - + + + + - - - - + - - - +void  - - - - + +void  +void  - + - - - - - - - - - - - - - - - - - + + + + @@ -193,10 +167,10 @@ void  +void  +void  @@ -214,54 +188,20 @@ void  +void  +void  +void  +void  +void  - - - - - - - - - - - - - - - - - - - - - - - - @@ -296,90 +236,16 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + - + - - - @@ -395,39 +261,20 @@ +static void  +static void  +static void  +static void  +static void  -

Public Member Functions

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)
 
void sendPoll (void)
 
@@ -121,61 +114,42 @@
 
void byteStreamHandler (uint8_t *buffer, size_t size)
 
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)
 
void ack (req_id_t req_id, unsigned char *ackdata, int len)
 
-void notifyCaller (Header *protocolHeader)
 Notify caller ACK frame arrived.
 
void activate (ActivateData *data, CallBack callback=0, UserData userData=0)
void activate (ActivateData *data, CallBack callback=0, UserData userData=0)
 Activation Control. More...
 
unsigned short activate (ActivateData *data, int timeout)
 Blocking API Control. More...
 
-void setControl (bool enable, CallBack callback=0, UserData userData=0)
setControl (bool enable, CallBack callback=0, UserData userData=0)
 
unsigned short setControl (bool enable, int timeout)
 Blocking API Control. More...
 
void setActivation (bool isActivated)
 Activation Control. More...
 
ActivateData getAccountData () const
ActivateData getAccountData () const
 Activation Control. More...
 
-void setAccountData (const ActivateData &value)
setAccountData (const ActivateData &value)
 Activation Control.
 
-void sendToMobile (uint8_t *data, uint8_t len, CallBack callback=0, UserData userData=0)
sendToMobile (uint8_t *data, uint8_t len, CallBack callback=0, UserData userData=0)
 
void setBroadcastFreq (uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)
void setBroadcastFreq (uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)
 
unsigned short setBroadcastFreq (uint8_t *dataLenIs16, int timeout)
 
void setBroadcastFreqDefaults ()
 
unsigned short setBroadcastFreqDefaults (int timeout)
 Set broadcast frequencies to their default values and block until ACK arrives from flight controller. More...
 
-void setBroadcastFreqToZero ()
 
void setACKFrameStatus (uint32_t usageFlag)
 
-uint32_t getACKFrameStatus ()
 
-void setBroadcastFrameStatus (bool isFrame)
 
-bool getBroadcastFrameStatus ()
 
+void setSessionStatus (uint32_t usageFlag)
 
+uint32_t getSessionStatus ()
 
void setSyncFreq (uint32_t freqInHz)
 
setFromMobileCallback (CallBackHandler FromMobileEntrance)
 
-void setBroadcastCallback (CallBack handler, UserData userData=0)
setBroadcastCallback (CallBack handler, UserData userData=0)
 
-void setFromMobileCallback (CallBack handler, UserData userData=0)
setFromMobileCallback (CallBack handler, UserData userData=0)
 
void setMisssionCallback (CallBackHandler callback)
setWayPointEventCallback (CallBackHandler callback)
 
-void setMisssionCallback (CallBack handler, UserData userData=0)
setMisssionCallback (CallBack handler, UserData userData=0)
 
-void setHotPointCallback (CallBack handler, UserData userData=0)
setHotPointCallback (CallBack handler, UserData userData=0)
 
-void setWayPointCallback (CallBack handler, UserData userData=0)
setWayPointCallback (CallBack handler, UserData userData=0)
 
-void setFollowCallback (CallBack handler, UserData userData=0)
setFollowCallback (CallBack handler, UserData userData=0)
 
-void setWayPointEventCallback (CallBack handler, UserData userData=0)
setWayPointEventCallback (CallBack handler, UserData userData=0)
 
void parseFromMobileCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
 
void setObtainControlMobileCallback (CallBackHandler callback)
 
-void setReleaseControlMobileCallback (CallBackHandler callback)
 
-void setActivateMobileCallback (CallBackHandler callback)
 
-void setArmMobileCallback (CallBackHandler callback)
 
-void setDisArmMobileCallback (CallBackHandler callback)
 
-void setTakeOffMobileCallback (CallBackHandler callback)
 
-void setLandingMobileCallback (CallBackHandler callback)
 
-void setGoHomeMobileCallback (CallBackHandler callback)
 
-void setTakePhotoMobileCallback (CallBackHandler callback)
 
-void setStartVideoMobileCallback (CallBackHandler callback)
 
-void setStopVideoMobileCallback (CallBackHandler callback)
 
bool decodeACKStatus (unsigned short ack)
 
bool decodeMissionStatus (uint8_t ack)
 
void setVersion (const Version &value)
 
bool getObtainControlMobileCMD ()
 
-bool getReleaseControlMobileCMD ()
 
-bool getActivateMobileCMD ()
 
-bool getArmMobileCMD ()
 
-bool getDisArmMobileCMD ()
 
-bool getTakeOffMobileCMD ()
 
-bool getLandingMobileCMD ()
 
-bool getGoHomeMobileCMD ()
 
-bool getTakePhotoMobileCMD ()
 
-bool getStartVideoMobileCMD ()
 
-bool getStopVideoMobileCMD ()
 
-bool getFollowMeMobileCMD ()
 
-void setObtainControlMobileCMD (bool userInput)
 
-void setReleaseControlMobileCMD (bool userInput)
 
-void setActivateMobileCMD (bool userInput)
 
-void setArmMobileCMD (bool userInput)
 
-void setDisArmMobileCMD (bool userInput)
 
-void setTakeOffMobileCMD (bool userInput)
 
-void setLandingMobileCMD (bool userInput)
 
-void setGoHomeMobileCMD (bool userInput)
 
-void setTakePhotoMobileCMD (bool userInput)
 
-void setStartVideoMobileCMD (bool userInput)
 
-void setStopVideoMobileCMD (bool userInput)
 
-void setFollowMeMobileCMD (bool userInput)
 
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)
 
void send (unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, size_t len, int timeout=0, int retry_time=1, CallBack ack_handler=0, UserData userData=0)
void send (unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, size_t len, int timeout=0, int retry_time=1, CallBack ack_handler=0, UserData userData=0)
 
void send (Command *parameter)
 
void getDroneVersion (CallBack callback=0, UserData userData=0)
void getDroneVersion (CallBack callback=0, UserData userData=0)
 
VersionData getDroneVersion (int timeout)
 Get drone version from flight controller block until ACK arrives from flight controller. More...
 
BroadcastData getBroadcastData () const
 
TimeStampData getTime () const

Static Public Member Functions

-static void activateCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
activateCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
 
-static void getDroneVersionCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
getDroneVersionCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
 
-static void setControlCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
setControlCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
 
-static void sendToMobileCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
sendToMobileCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
 
-static void setFrequencyCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
setFrequencyCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
 
- - - - - - - - - - - - -

-Public Attributes

bool stopCond
 
uint32_t ack_data
 
-HotPointReadACK hotpointReadACK
 
-WayPointInitACK waypointInitACK
 
-MissionACKUnion missionACKUnion
 
-HardDriverserialDevice
 

Detailed Description

CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform.

@@ -449,7 +296,7 @@ void CoreAPI::activate ( - ActivateData *  + ActivateDatadata, @@ -461,7 +308,7 @@ - UserData  + UserData  userData = 0  @@ -480,43 +327,6 @@ Proceed to programming if activation successful.

Note
for ios verification
-
-
- -
-
- - - - - - - - - - - - - - - - - - -
unsigned short CoreAPI::activate (ActivateDatadata,
int timeout 
)
-
- -

Blocking API Control.

-
Remarks
Blocks until ACK frame arrives or timeout occurs
-

Send activation control to your flight controller to check if:
- a) your application registered in your developer account
- b) API Control enabled in the Assistant software
-
-Proceed to programming if activation successful.

-
Returns
ACK from flight controller
-
Todo:
Implement high resolution timer to catch ACK timeout
-
Note
for ios verification
-
@@ -532,7 +342,7 @@
-
Todo:
Pipeline refactoring
+
Todo:
Pipeline refactoring
Note
Just think a command as below

[123456HHD1234567===HHHH------------——] — is buf un-used part

if after recv full of above, but crc failed, we throw all data? NO! Just throw ONE BYTE, we move like below

@@ -570,7 +380,7 @@
-
Todo:
Implement stream handler
+
Todo:
Implement stream handler
@@ -587,8 +397,8 @@
-
Todo:
Implement callback poll handler
-
Todo:
Implement callback poll here
+
Todo:
Implement callback poll handler
+
Todo:
Implement callback poll here
@@ -623,7 +433,7 @@

Flight mission decoder.

-
Todo:
Fix memory leak issue
+
Todo:
Fix memory leak issue
@@ -632,7 +442,7 @@
- + @@ -707,7 +517,7 @@ - + @@ -720,27 +530,6 @@

Get aircraft version.

Note
You can query your flight controller prior to activation.
- - - -
-
-
ActivateData CoreAPI::getAccountData ActivateData CoreAPI::getAccountData ( ) const
UserData UserData  userData = 0 
- - - - - - - -
VersionData CoreAPI::getDroneVersion (int timeout)
-
- -

Get drone version from flight controller block until ACK arrives from flight controller.

-

Blocking API Control

-
Returns
VersionData containing ACK value, CRC of the protocol version and protocol version itself
-
Todo:
Implement high resolution timer to catch ACK timeout
-
@@ -775,30 +564,6 @@

Get flight status at any time during a flight mission.

-
- - -
-
- - - - - -
- - - - - - - -
bool DJI::onboardSDK::CoreAPI::getObtainControlMobileCMD ()
-
-inline
-
-

Setters and getters for Mobile CMD variables

-
@@ -833,39 +598,6 @@
Note
Make sure you are using appropriate timestamp broadcast frequency. See setBroadcastFreq
function for more details.
- - - -
-
- - - - - - - - - - - - - - - - - - - - - - - - -
void CoreAPI::parseFromMobileCallback (CoreAPIapi,
HeaderprotocolHeader,
UserData userData __UNUSED = 0 
)
-
-

MOS Protocol parsing lirbary functions. Default MOS Protocol Parser. Calls other callback functions based on data

-
@@ -1010,7 +742,7 @@ - UserData  + UserData  userData = 0  @@ -1062,23 +794,6 @@
Note
Add auto resendpoll
-
- - -
-
- - - - - - - - -
void DJI::onboardSDK::CoreAPI::setACKFrameStatus (uint32_t usageFlag)
-
-

Let user know when ACK and Broadcast messages processed

-
@@ -1119,7 +834,7 @@ - UserData  + UserData  userData = 0  @@ -1147,102 +862,6 @@
Note
see also enum BROADCAST_FREQ in DJI_API.h
- - - -
-
- - - - - - - - - - - - - - - - - - -
unsigned short CoreAPI::setBroadcastFreq (uint8_t * dataLenIs16,
int timeout 
)
-
-
Note
see also enum BROADCAST_FREQ in DJI_API.h
- -
-
- -
-
- - - - - - - -
void CoreAPI::setBroadcastFreqDefaults ()
-
-

Reset all broadcast frequencies to their default values

- -
-
- -
-
- - - - - - - - -
unsigned short CoreAPI::setBroadcastFreqDefaults (int timeout)
-
- -

Set broadcast frequencies to their default values and block until ACK arrives from flight controller.

-

Blocking API Control

-
Returns
ACK from flight controller
-
Todo:
Implement high resolution timer to catch ACK timeout
- -
-
- -
-
- - - - - - - - - - - - - - - - - - -
unsigned short CoreAPI::setControl (bool enable,
int timeout 
)
-
- -

Blocking API Control.

-
Remarks
Blocks until ACK frame arrives or timeout occurs
-

Obtain control

-
Returns
ACK from flight controller
-
Todo:
Implement high resolution timer to catch ACK timeout
-
@@ -1260,31 +879,6 @@

Initialize serial device

-
- - -
-
- - - - - -
- - - - - - - - -
void DJI::onboardSDK::CoreAPI::setObtainControlMobileCallback (CallBackHandler callback)
-
-inline
-
-

Mobile Callback handler functions

-
@@ -1302,33 +896,6 @@

Set SDK version.

-
- -

Member Data Documentation

- -
-
- - - - -
uint32_t DJI::onboardSDK::CoreAPI::ack_data
-
-
Note
Thread data
- -
-
- -
-
- - - - -
bool DJI::onboardSDK::CoreAPI::stopCond
-
-
Note
Thread data
-

The documentation for this class was generated from the following files:
    @@ -1343,7 +910,7 @@

    Member Data Documentation

    diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight-members.html index b018f5db..76b4a4cb 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight-members.html @@ -149,21 +149,19 @@ MODE_NOT_SUPPORTED enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight setApi(CoreAPI *value) (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight setArm(bool enable, CallBack ArmCallback=0, UserData userData=0) (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - setArm(bool enable, int timer) (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - setFlight(FlightData *data) (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - setMovementControl(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw)DJI::onboardSDK::Flight - SMOOTH_DISABLE enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - SMOOTH_ENABLE enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - SmoothMode enum nameDJI::onboardSDK::Flight - Status enum name (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - STATUS_FINISHING_LANDING enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - STATUS_GROUND_STANDBY enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - STATUS_LANDING enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - STATUS_SKY_STANDBY enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - STATUS_TAKE_OFF enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - TASK enum name (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight - task(TASK taskname, CallBack TaskCallback=0, UserData userData=0)DJI::onboardSDK::Flight - task(TASK taskname, int timer) (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + setFlight(FlightData *data) (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + setMovementControl(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw)DJI::onboardSDK::Flight + SMOOTH_DISABLE enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + SMOOTH_ENABLE enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + SmoothMode enum nameDJI::onboardSDK::Flight + Status enum name (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + STATUS_FINISHING_LANDING enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + STATUS_GROUND_STANDBY enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + STATUS_LANDING enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + STATUS_SKY_STANDBY enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + STATUS_TAKE_OFF enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + TASK enum name (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight + task(TASK taskname, CallBack TaskCallback=0, UserData userData=0)DJI::onboardSDK::Flight TASK_GOHOME enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight TASK_LANDING enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight TASK_TAKEOFF enum value (defined in DJI::onboardSDK::Flight)DJI::onboardSDK::Flight @@ -184,7 +182,7 @@ diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight.html index dd30c22d..d603f344 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Flight.html @@ -188,17 +188,11 @@ Public Member Functions  Flight (CoreAPI *ControlAPI=0)   -void task (TASK taskname, CallBack TaskCallback=0, UserData userData=0) +void task (TASK taskname, CallBack TaskCallback=0, UserData userData=0)   - -unsigned short task (TASK taskname, int timer) -  -void setArm (bool enable, CallBack ArmCallback=0, UserData userData=0) +void setArm (bool enable, CallBack ArmCallback=0, UserData userData=0)   - -unsigned short setArm (bool enable, int timer) -  void control (uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw)   @@ -250,10 +244,10 @@ - + +static void  @@ -277,7 +271,7 @@

    Static Public Member Functions

    static void armCallback (CoreAPI *api, Header *protoclHeader, UserData userData=0)
    static void armCallback (CoreAPI *api, Header *protoclHeader, UserData userData=0)
     
    -static void taskCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
    taskCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
     
    static EulerianAngle toEulerianAngle (QuaternionData data)
     @ deprecated Use toEulerAngle instead. More...
    -
    Todo:
    rename
    +
    Todo:
    rename
    @@ -350,7 +344,7 @@

    Member Function Documentation

    - UserData userData  + UserData userData  __UNUSED = 0  @@ -517,7 +511,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -566,7 +560,7 @@

    Member Function Documentation

    diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow-members.html index 6f7cf06e..d2a50c0e 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow-members.html @@ -101,30 +101,27 @@ MODE_ROUTE enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow MODE_SMART enum valueDJI::onboardSDK::Follow pause(bool isPause, CallBack callback=0, UserData userData=0)DJI::onboardSDK::Follow - pause(bool isPause, int timer) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - resetData() (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - SENSE_HIGH enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - SENSE_LOW enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - SENSE_MID enum valueDJI::onboardSDK::Follow - SENSITIVITY enum nameDJI::onboardSDK::Follow - setData(const FollowData &value)DJI::onboardSDK::Follow - setMode(const MODE mode) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - setSensitivity(const SENSITIVITY sense) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - setTarget(FollowTarget target) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - setYawType(const YAW_TYPE type) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - start(FollowData *Data=0, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - start(FollowData *Data=0, int timer=0) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + resetData() (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + SENSE_HIGH enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + SENSE_LOW enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + SENSE_MID enum valueDJI::onboardSDK::Follow + SENSITIVITY enum nameDJI::onboardSDK::Follow + setData(const FollowData &value)DJI::onboardSDK::Follow + setMode(const MODE mode) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + setSensitivity(const SENSITIVITY sense) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + setTarget(FollowTarget target) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + setYawType(const YAW_TYPE type) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + start(FollowData *Data=0, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow stop(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - stop(int timer) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - updateTarget(FollowTarget target) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - updateTarget(float64_t latitude, float64_t longitude, uint16_t height, uint16_t angle)DJI::onboardSDK::Follow - YAW_CUSTOM enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - YAW_TOTARGET enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow - YAW_TYPE enum name (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + updateTarget(FollowTarget target) (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + updateTarget(float64_t latitude, float64_t longitude, uint16_t height, uint16_t angle)DJI::onboardSDK::Follow + YAW_CUSTOM enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + YAW_TOTARGET enum value (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow + YAW_TYPE enum name (defined in DJI::onboardSDK::Follow)DJI::onboardSDK::Follow diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow.html index e98d2896..feed470a 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1Follow.html @@ -127,22 +127,13 @@ void resetData ()   -void start (FollowData *Data=0, CallBack callback=0, UserData userData=0) +void start (FollowData *Data=0, CallBack callback=0, UserData userData=0)   - -MissionACK start (FollowData *Data=0, int timer=0) -  -void stop (CallBack callback=0, UserData userData=0) +void stop (CallBack callback=0, UserData userData=0)   - -MissionACK stop (int timer) -  -void pause (bool isPause, CallBack callback=0, UserData userData=0) +void pause (bool isPause, CallBack callback=0, UserData userData=0)   - -MissionACK pause (bool isPause, int timer) -  void updateTarget (FollowTarget target)   @@ -223,7 +214,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -300,7 +291,7 @@

    Member Function Documentation

    diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver-members.html index 7500f1d8..eb7b3512 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver-members.html @@ -95,23 +95,19 @@

    This is the complete list of members for DJI::onboardSDK::HardDriver, including all inherited members.

    - - - - - - - + + + + + - - - - + +
    displayLog(const char *buf=0) (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDrivervirtual
    freeACK()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    freeMemory()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    freeMSG()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    getTimeStamp()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    HardDriver() (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverinline
    init()=0DJI::onboardSDK::HardDriverpure virtual
    lockACK()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    freeMemory()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    freeMSG()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    getTimeStamp()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    HardDriver() (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverinline
    init()=0DJI::onboardSDK::HardDriverpure virtual
    lockMemory()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    lockMSG()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    notify()=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    readall(uint8_t *buf, size_t maxlen)=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    send(const uint8_t *buf, size_t len)=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    wait(int timeout)=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    readall(uint8_t *buf, size_t maxlen)=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    send(const uint8_t *buf, size_t len)=0 (defined in DJI::onboardSDK::HardDriver)DJI::onboardSDK::HardDriverpure virtual
    diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver.html index d3fcf7de..f43b7e11 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HardDriver.html @@ -121,18 +121,6 @@ virtual void freeMSG ()=0   - -virtual void lockACK ()=0 -  - -virtual void freeACK ()=0 -  - -virtual void notify ()=0 -  - -virtual void wait (int timeout)=0 -  virtual void displayLog (const char *buf=0)   @@ -168,21 +156,20 @@

    Member Function Documentation

    size_t readall(uint8_t *buf, size_t maxlen) = 0; return read data length.

    void lockMemory();/ void freeMemory(); provide a mutex for multi-thread. when operating memory.

    void lockMSG();/ void freeMSG(); provide a mutex for multi-thread. when operating messages.

    -

    void notify();/ void wait(); use conditional variable to signal controller thread about arrival of ACK frame.

    void displayLog(char *buf); Micro "API_LOG" invoked this function, to pass datalog. In order to pass data through different stream or channel. We abstract this virtual function for user. And different from others, this interface is not a pure virtual funcion. The default data-passing channel is stdout (printf). See also "DJI_HardDriver.cpp".

    Attention
    when writting and reading data, there might have multi-thread problems. Abstract class HardDriver did not consider these issue. Please be careful when you are going to implement send and readall funtions.
    -
    Note
    we strongly suggest you to inherit this class in your own file, not just implement it in DJI_HardDriver.cpp or inside this class
    +
    Note
    we strongly suggest you to inherit this class in your own file, not just implement it in DJI_HardDriver.cpp or inside this class

    The documentation for this class was generated from the following files: diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint-members.html index 32617086..2d805291 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint-members.html @@ -98,12 +98,10 @@ HotPoint(CoreAPI *ControlAPI=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint initData() (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint pause(bool isPause, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - pause(bool isPause, int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + ReadACK typedef (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint readCallback(CoreAPI *api, Header *protoclHeader, UserData userdata) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPointstatic readData(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - readData(int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - resetYaw(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - resetYaw(int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + resetYaw(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint setCameraView(View view) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint setClockwise(bool isClockwise) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint setData(const HotPointData &value)DJI::onboardSDK::HotPoint @@ -113,32 +111,29 @@ setYawMode(YawMode mode) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint setYawRate(float32_t defree) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint start(CallBack callback=0, UserData userData=0)DJI::onboardSDK::HotPoint - start(int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + StartACK typedef (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint startCallback(CoreAPI *api, Header *protocolHeader, UserData userdata=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPointstatic stop(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - stop(int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - updateRadius(float32_t meter, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - updateRadius(float32_t meter, int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + updateRadius(float32_t meter, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint updateYawRate(YawRate &Data, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - updateYawRate(YawRate &Data, int timer) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - updateYawRate(float32_t yawRate, bool isClockwise, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - View enum name (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - VIEW_EAST enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - VIEW_NEARBY enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - VIEW_NORTH enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - VIEW_SOUTH enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - VIEW_WEST enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YAW_AUTO enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YAW_CUSTOM enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YAW_INSIDE enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YAW_OUTSIDE enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YAW_STATIC enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YawMode enum name (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint - YawRate typedef (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + updateYawRate(float32_t yawRate, bool isClockwise, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + View enum name (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + VIEW_EAST enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + VIEW_NEARBY enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + VIEW_NORTH enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + VIEW_SOUTH enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + VIEW_WEST enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YAW_AUTO enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YAW_CUSTOM enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YAW_INSIDE enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YAW_OUTSIDE enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YAW_STATIC enum value (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YawMode enum name (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint + YawRate typedef (defined in DJI::onboardSDK::HotPoint)DJI::onboardSDK::HotPoint diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint.html index a3c225fe..5c2f229f 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1HotPoint.html @@ -100,6 +100,10 @@ + + + +

    Classes

    struct  ReadACK
     
    struct  StartACK
     
    struct  YawRate
     
    @@ -125,9 +129,15 @@
    } + + + +
     
    +typedef struct DJI::onboardSDK::HotPoint::StartACK StartACK
     
    typedef struct DJI::onboardSDK::HotPoint::YawRate YawRate
     
    +typedef struct DJI::onboardSDK::HotPoint::ReadACK ReadACK
     
    @@ -137,50 +147,29 @@ - + - - +void  - - +void  - - +void  - - +void  +void  - - +void  - - +void  - - +static void  +static void 

    Public Member Functions

    void initData ()
     
    void start (CallBack callback=0, UserData userData=0)
    void start (CallBack callback=0, UserData userData=0)
     
    -HotPointStartACK start (int timer)
     
    -void stop (CallBack callback=0, UserData userData=0)
    stop (CallBack callback=0, UserData userData=0)
     
    -MissionACK stop (int timer)
     
    -void pause (bool isPause, CallBack callback=0, UserData userData=0)
    pause (bool isPause, CallBack callback=0, UserData userData=0)
     
    -MissionACK pause (bool isPause, int timer)
     
    -void updateYawRate (YawRate &Data, CallBack callback=0, UserData userData=0)
    updateYawRate (YawRate &Data, CallBack callback=0, UserData userData=0)
     
    -MissionACK updateYawRate (YawRate &Data, int timer)
     
    -void updateYawRate (float32_t yawRate, bool isClockwise, CallBack callback=0, UserData userData=0)
    updateYawRate (float32_t yawRate, bool isClockwise, CallBack callback=0, UserData userData=0)
     
    -void updateRadius (float32_t meter, CallBack callback=0, UserData userData=0)
    updateRadius (float32_t meter, CallBack callback=0, UserData userData=0)
     
    -MissionACK updateRadius (float32_t meter, int timer)
     
    -void resetYaw (CallBack callback=0, UserData userData=0)
    resetYaw (CallBack callback=0, UserData userData=0)
     
    -MissionACK resetYaw (int timer)
     
    -void readData (CallBack callback=0, UserData userData=0)
    readData (CallBack callback=0, UserData userData=0)
     
    -MissionACK readData (int timer)
     
    void setData (const HotPointData &value)
     
    @@ -211,10 +200,10 @@

    Static Public Member Functions

    -static void startCallback (CoreAPI *api, Header *protocolHeader, UserData userdata=0)
    startCallback (CoreAPI *api, Header *protocolHeader, UserData userdata=0)
     
    -static void readCallback (CoreAPI *api, Header *protoclHeader, UserData userdata)
    readCallback (CoreAPI *api, Header *protoclHeader, UserData userdata)
     

    Member Function Documentation

    @@ -248,7 +237,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -270,7 +259,7 @@

    Member Function Documentation

    diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC-members.html index d5477332..30b307be 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC-members.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC.html index 1049da76..ede7131a 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1VirtualRC.html @@ -268,7 +268,7 @@

    Global: VirtualRCData myData;

    Thread 1: while(1) { myData = myAPIToSetupDataFromGroundStation(); }

    Thread 2: while(1) { sendData(myData); msleep(200); }

    -

    When your drone lose signal, it will keep the recent command sent by your API: myAPIToSetupDataFromGroundStation(); This may result in a catastrophic crash.

    +

    When your drone lose signal, it will keep the recent command sent by your API: myAPIToSetupDataFromGroundStation(); Somehow, you will never get your drone back in one pice, if this tragedy happend.

    Note
    API "sendData();" need to be called above 2Hz, and not greater than 25hz.
    API "sendSafeModeData();" will lead your drone hover;
    @@ -309,7 +309,7 @@ diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint-members.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint-members.html index 16580443..42913ad0 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint-members.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint-members.html @@ -99,9 +99,7 @@ getInfo() const (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint idleVelocityCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPointstatic init(WayPointInitData *Info=0, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint - init(WayPointInitData *Info, int timer) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint - pause(bool isPause, CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint - pause(bool isPause, int timer) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint + pause(bool isPause, CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint readIdleVelocity(CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint readIndexData(uint8_t index, CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint readInitData(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint @@ -109,19 +107,16 @@ setIndex(WayPointData *value, size_t pos) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint setInfo(const WayPointInitData &value)DJI::onboardSDK::WayPoint start(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint - start(int timer) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint - stop(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint - stop(int timer) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint + stop(CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint updateIdleVelocity(float32_t meterPreSecond, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint uploadIndexData(WayPointData *data, CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint - uploadIndexData(WayPointData *data, int timer) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint - uploadIndexData(uint8_t pos, CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint - uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPointstatic - WayPoint(CoreAPI *ControlAPI=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint + uploadIndexData(uint8_t pos, CallBack callback=0, UserData userData=0)DJI::onboardSDK::WayPoint + uploadIndexDataCallback(CoreAPI *api, Header *protocolHeader, UserData wpapi) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPointstatic + WayPoint(CoreAPI *ControlAPI=0) (defined in DJI::onboardSDK::WayPoint)DJI::onboardSDK::WayPoint diff --git a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint.html b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint.html index 48402654..62ac6ff3 100644 --- a/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint.html +++ b/dji_sdk_doc/doxygen/html/classDJI_1_1onboardSDK_1_1WayPoint.html @@ -102,44 +102,29 @@  WayPoint (CoreAPI *ControlAPI=0)   -void init (WayPointInitData *Info=0, CallBack callback=0, UserData userData=0) +void init (WayPointInitData *Info=0, CallBack callback=0, UserData userData=0)   - -MissionACK init (WayPointInitData *Info, int timer) -  -void start (CallBack callback=0, UserData userData=0) +void start (CallBack callback=0, UserData userData=0)   - -MissionACK start (int timer) -  -void stop (CallBack callback=0, UserData userData=0) +void stop (CallBack callback=0, UserData userData=0)   - -MissionACK stop (int timer) -  -void pause (bool isPause, CallBack callback=0, UserData userData=0) +void pause (bool isPause, CallBack callback=0, UserData userData=0)   - -MissionACK pause (bool isPause, int timer) -  -void readInitData (CallBack callback=0, UserData userData=0) +void readInitData (CallBack callback=0, UserData userData=0)   -void readIndexData (uint8_t index, CallBack callback=0, UserData userData=0) +void readIndexData (uint8_t index, CallBack callback=0, UserData userData=0)   -void readIdleVelocity (CallBack callback=0, UserData userData=0) +void readIdleVelocity (CallBack callback=0, UserData userData=0)   -bool uploadIndexData (WayPointData *data, CallBack callback=0, UserData userData=0) +bool uploadIndexData (WayPointData *data, CallBack callback=0, UserData userData=0)   - -WayPointDataACK uploadIndexData (WayPointData *data, int timer) -  -bool uploadIndexData (uint8_t pos, CallBack callback=0, UserData userData=0) +bool uploadIndexData (uint8_t pos, CallBack callback=0, UserData userData=0)   -void updateIdleVelocity (float32_t meterPreSecond, CallBack callback=0, UserData userData=0) +void updateIdleVelocity (float32_t meterPreSecond, CallBack callback=0, UserData userData=0)   void setInfo (const WayPointInitData &value)   @@ -159,13 +144,13 @@

    Static Public Member Functions

    -static void idleVelocityCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi) +static void idleVelocityCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi)   -static void readInitDataCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi) +static void readInitDataCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi)   -static void uploadIndexDataCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi) +static void uploadIndexDataCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi)  

    Member Function Documentation

    @@ -188,7 +173,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -215,7 +200,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -225,7 +210,7 @@

    Member Function Documentation

    -
    Todo:
    implement
    +
    Todo:
    implement
    @@ -248,7 +233,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -258,7 +243,7 @@

    Member Function Documentation

    -
    Todo:
    implement
    +
    Todo:
    implement
    @@ -275,7 +260,7 @@

    Member Function Documentation

    -
    Todo:
    set information for way point
    +
    Todo:
    set information for way point
    @@ -298,7 +283,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -308,7 +293,7 @@

    Member Function Documentation

    -
    Todo:
    uploadAll
    +
    Todo:
    uploadAll
    @@ -331,7 +316,7 @@

    Member Function Documentation

    - UserData  + UserData  userData = 0  @@ -352,7 +337,7 @@

    Member Function Documentation

    diff --git a/dji_sdk_doc/doxygen/html/classes.html b/dji_sdk_doc/doxygen/html/classes.html index 3c4c6e8e..1320ff5f 100644 --- a/dji_sdk_doc/doxygen/html/classes.html +++ b/dji_sdk_doc/doxygen/html/classes.html @@ -90,51 +90,51 @@
    A | B | C | E | F | G | H | M | P | Q | R | S | T | V | W | Y
    + - - + - - + - - + + + - - - + - - + - - - + - - - - + + + +
      A  
    -
    EulerianAngle (DJI)   Header (DJI::onboardSDK)   
      R  
    -
    VirtualRC (DJI::onboardSDK)   
    EulerianAngle (DJI)   Header (DJI::onboardSDK)   RCData (DJI::onboardSDK)   VirtualRCData (DJI::onboardSDK)   
      F  
    -
    HotPoint (DJI::onboardSDK)   VirtualRCData (DJI::onboardSDK)   
    Ack (DJI::onboardSDK)   HotPointACKData (DJI::onboardSDK)   RadioData (DJI::onboardSDK)   VirtualRCSetting (DJI::onboardSDK)   
    ACKSession (DJI::onboardSDK)   Flight (DJI::onboardSDK)   HotPointData (DJI::onboardSDK)   RCData (DJI::onboardSDK)   
      W  
    +
    HotPoint (DJI::onboardSDK)   HotPoint::ReadACK (DJI::onboardSDK)   VirtualRCSetting (DJI::onboardSDK)   
    Ack (DJI::onboardSDK)   HotPointACKData (DJI::onboardSDK)   RTKData (DJI::onboardSDK)   
      W  
    ActivateData (DJI::onboardSDK)   FlightData (DJI::onboardSDK)   HotPointReadACK (DJI::onboardSDK)   RTKData (DJI::onboardSDK)   
      B  
    -
    Follow (DJI::onboardSDK)   HotPointStartACK (DJI::onboardSDK)   
      S  
    +
    ACKSession (DJI::onboardSDK)   Flight (DJI::onboardSDK)   HotPointData (DJI::onboardSDK)   
      S  
    +
    ActivateData   FlightData (DJI::onboardSDK)   
      M  
    WayPoint (DJI::onboardSDK)   
    FollowData (DJI::onboardSDK)   
      M  
    -
    WayPointData (DJI::onboardSDK)   
    BroadcastData (DJI::onboardSDK)   FollowTarget (DJI::onboardSDK)   SDKFilter (DJI::onboardSDK)   WayPointDataACK (DJI::onboardSDK)   
      B  
    +
    Follow (DJI::onboardSDK)   SDKFilter (DJI::onboardSDK)   WayPointData (DJI::onboardSDK)   
    FollowData (DJI::onboardSDK)   MagData (DJI::onboardSDK)   SpaceVector (DJI)   WayPointDataACK (DJI::onboardSDK)   
    BroadcastData (DJI::onboardSDK)   FollowTarget (DJI::onboardSDK)   MagnetData (DJI::onboardSDK)   HotPoint::StartACK (DJI::onboardSDK)   WayPointInitACK (DJI::onboardSDK)   
      C  
      G  
    -
    MagData (DJI::onboardSDK)   SpaceVector (DJI)   WayPointInitACK (DJI::onboardSDK)   
    MagnetData (DJI::onboardSDK)   
      T  
    +
    Measure (DJI)   
      T  
    WayPointInitData (DJI::onboardSDK)   
    CallBackHandler (DJI::onboardSDK)   GimbalAngleData (DJI::onboardSDK)   Measure (DJI)   WayPointVelocityACK (DJI::onboardSDK)   
    Camera (DJI::onboardSDK)   GimbalData (DJI::onboardSDK)   Measurement (DJI)   TaskData (DJI::onboardSDK)   
      Y  
    +
    Measurement (DJI)   WayPointVelocityACK (DJI::onboardSDK)   
    CallBackHandler (DJI::onboardSDK)   GimbalAngleData (DJI::onboardSDK)   MissionACKMap (DJI::onboardSDK)   TaskData (DJI::onboardSDK)   
      Y  
    CMDSession (DJI::onboardSDK)   GimbalSpeedData (DJI::onboardSDK)   MissionACKMap (DJI::onboardSDK)   TimeStampData (DJI::onboardSDK)   
    Command (DJI::onboardSDK)   GPSData (DJI::onboardSDK)   MissionACKUnion (DJI::onboardSDK)   
      V  
    +
    Camera (DJI::onboardSDK)   GimbalData (DJI::onboardSDK)   MMU_Tab (DJI::onboardSDK)   TimeStampData (DJI::onboardSDK)   
    CMDSession (DJI::onboardSDK)   GimbalSpeedData (DJI::onboardSDK)   
      P  
    +
      V  
    HotPoint::YawRate (DJI::onboardSDK)   
    CommonData (DJI::onboardSDK)   GPSPositionData (DJI::onboardSDK)   MMU_Tab (DJI::onboardSDK)   
      r  
    +
    Command (DJI::onboardSDK)   GPSData (DJI::onboardSDK)   
      r  
    CoreAPI (DJI::onboardSDK)   GSPushData (DJI::onboardSDK)   
      P  
    -
    Vector3dData (DJI)   
    CtrlInfoData (DJI::onboardSDK)   
      H  
    +
    CommonData (DJI::onboardSDK)   GPSPositionData (DJI::onboardSDK)   PositionData (DJI::onboardSDK)   Vector3dData (DJI)   
    CoreAPI (DJI::onboardSDK)   GSPushData (DJI::onboardSDK)   
      Q  
    Vector3fData (DJI::onboardSDK)   req_id_t   
      E  
    -
    PositionData (DJI::onboardSDK)   VelocityData (DJI::onboardSDK)   
      t  
    +
    CtrlInfoData (DJI::onboardSDK)   
      H  
    +
    VelocityData (DJI::onboardSDK)   
      t  
    HardDriver (DJI::onboardSDK)   
      Q  
    -
    VersionData (DJI::onboardSDK)   
    EulerAngle (DJI)   tagAES256Context   
    QuaternionData (DJI::onboardSDK)   
      E  
    +
    QuaternionData (DJI::onboardSDK)   VersionData   
    HardDriver (DJI::onboardSDK)   
      R  
    +
    VirtualRC (DJI::onboardSDK)   tagAES256Context   
    EulerAngle (DJI)   
    RadioData (DJI::onboardSDK)   
    A | B | C | E | F | G | H | M | P | Q | R | S | T | V | W | Y
    diff --git a/dji_sdk_doc/doxygen/html/deprecated.html b/dji_sdk_doc/doxygen/html/deprecated.html index 1cb1d531..d79fae51 100644 --- a/dji_sdk_doc/doxygen/html/deprecated.html +++ b/dji_sdk_doc/doxygen/html/deprecated.html @@ -93,7 +93,7 @@ diff --git a/dji_sdk_doc/doxygen/html/dir_4858fddfe5c24bcac01c3c8697387c37.html b/dji_sdk_doc/doxygen/html/dir_4858fddfe5c24bcac01c3c8697387c37.html index 2e2f6bac..2851f2ca 100644 --- a/dji_sdk_doc/doxygen/html/dir_4858fddfe5c24bcac01c3c8697387c37.html +++ b/dji_sdk_doc/doxygen/html/dir_4858fddfe5c24bcac01c3c8697387c37.html @@ -97,7 +97,7 @@ diff --git a/dji_sdk_doc/doxygen/html/dir_7d5f782014efafaf8289e99742765d5b.html b/dji_sdk_doc/doxygen/html/dir_7d5f782014efafaf8289e99742765d5b.html index 8811acb9..0e451296 100644 --- a/dji_sdk_doc/doxygen/html/dir_7d5f782014efafaf8289e99742765d5b.html +++ b/dji_sdk_doc/doxygen/html/dir_7d5f782014efafaf8289e99742765d5b.html @@ -97,7 +97,7 @@ diff --git a/dji_sdk_doc/doxygen/html/dir_d6adb40f961893fe77ad1c93ece9fa6b.html b/dji_sdk_doc/doxygen/html/dir_d6adb40f961893fe77ad1c93ece9fa6b.html index 4ce87506..e71f967e 100644 --- a/dji_sdk_doc/doxygen/html/dir_d6adb40f961893fe77ad1c93ece9fa6b.html +++ b/dji_sdk_doc/doxygen/html/dir_d6adb40f961893fe77ad1c93ece9fa6b.html @@ -97,10 +97,8 @@  Core API for DJI onboardSDK library.
      file  DJI_App.cpp - Application layer support functionality for DJI onboardSDK library.
      file  DJI_Camera.cpp - Camera/Gimbal API for DJI onboardSDK library.
      file  DJI_Codec.cpp  Encoding/Message parsing features for DJI onboardSDK library.
    @@ -109,34 +107,26 @@  Flight Control API for DJI onboardSDK library.
      file  DJI_Follow.cpp - Follow API for DJI onboardSDK library.
    -  -file  DJI_HardDriver.cpp - Serial device driver abstraction. See DJI_HardDriver.h for more info.
      file  DJI_HotPoint.cpp - Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library.
      file  DJI_Link.cpp  Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library.
      file  DJI_Memory.cpp - Implement memory management for Core API of DJI onboardSDK library.
      file  DJI_Mission.cpp  Mission Framework for DJI onboardSDK library.
      file  DJI_VirtualRC.cpp - Virtual Radio Control API for DJI onboardSDK library.
      file  DJI_WayPoint.cpp - Waypoint flight API for DJI onboardSDK library.
      diff --git a/dji_sdk_doc/doxygen/html/dir_df193617b4317ea26407acd6acb5749e.html b/dji_sdk_doc/doxygen/html/dir_df193617b4317ea26407acd6acb5749e.html index 20e2967a..b262cb55 100644 --- a/dji_sdk_doc/doxygen/html/dir_df193617b4317ea26407acd6acb5749e.html +++ b/dji_sdk_doc/doxygen/html/dir_df193617b4317ea26407acd6acb5749e.html @@ -97,52 +97,39 @@  Core API for DJI onboardSDK library.
      file  DJI_App.h [code] - Application layer support functionality for DJI onboardSDK library.
      file  DJI_Camera.h [code] - Camera/Gimbal API for DJI onboardSDK library.
      file  DJI_Codec.h [code] - Encoding/Message parsing features for DJI onboardSDK library.
      file  DJI_Config.h [code] - Optional macro definitions for DJI Onboard SDK. Use for debugging.
      file  DJI_Flight.h [code]  Flight Control API for DJI onboardSDK library.
      file  DJI_Follow.h [code] - Follow API for DJI onboardSDK library.
      file  DJI_HardDriver.h [code] - Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms.
      -file  DJI_Link.h [code] - Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library.
    +file  DJI_HotPoint.h [code]   -file  DJI_Mission.h [code] - Mission Framework for DJI onboardSDK library.
    +file  DJI_Link.h [code]   file  DJI_Type.h [code] - Type definition for DJI onboardSDK library. Officially Maintained.
      file  DJI_Version.h [code] - Drone/SDK Version definition for DJI onboardSDK library Officially Maintained.
      file  DJI_VirtualRC.h [code] - Virtual Radio Control API for DJI onboardSDK library.
      file  DJI_WayPoint.h [code] - Waypoint flight API for DJI onboardSDK library.
      file  DJICommonType.h [code] - Common Type definition for DJI onboardSDK library. Officially Maintained.
      diff --git a/dji_sdk_doc/doxygen/html/files.html b/dji_sdk_doc/doxygen/html/files.html index 07b4a0f9..d1f56fef 100644 --- a/dji_sdk_doc/doxygen/html/files.html +++ b/dji_sdk_doc/doxygen/html/files.html @@ -92,42 +92,41 @@   include   dji_sdk_lib  DJI_API.hCore API for DJI onboardSDK library - DJI_App.hApplication layer support functionality for DJI onboardSDK library - DJI_Camera.hCamera/Gimbal API for DJI onboardSDK library - DJI_Codec.hEncoding/Message parsing features for DJI onboardSDK library - DJI_Config.hOptional macro definitions for DJI Onboard SDK. Use for debugging + DJI_App.h + DJI_Camera.h + DJI_Codec.h + DJI_Config.h  DJI_Flight.hFlight Control API for DJI onboardSDK library - DJI_Follow.hFollow API for DJI onboardSDK library - DJI_HardDriver.hSerial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms - DJI_HotPoint.h - DJI_Link.hImplement send/read, app handling and data link layer for Core API of DJI onboardSDK library + DJI_Follow.h + DJI_HardDriver.h + DJI_HotPoint.h + DJI_Link.h  DJI_Memory.h - DJI_Mission.hMission Framework for DJI onboardSDK library - DJI_Type.hType definition for DJI onboardSDK library. Officially Maintained - DJI_Version.hDrone/SDK Version definition for DJI onboardSDK library Officially Maintained - DJI_VirtualRC.hVirtual Radio Control API for DJI onboardSDK library - DJI_WayPoint.hWaypoint flight API for DJI onboardSDK library - DJICommonType.hCommon Type definition for DJI onboardSDK library. Officially Maintained + DJI_Mission.h + DJI_Type.h + DJI_Version.h + DJI_VirtualRC.h + DJI_WayPoint.h + DJICommonType.h   src  DJI_API.cppCore API for DJI onboardSDK library - DJI_App.cppApplication layer support functionality for DJI onboardSDK library - DJI_Camera.cppCamera/Gimbal API for DJI onboardSDK library + DJI_App.cpp + DJI_Camera.cpp  DJI_Codec.cppEncoding/Message parsing features for DJI onboardSDK library  DJI_Flight.cppFlight Control API for DJI onboardSDK library - DJI_Follow.cppFollow API for DJI onboardSDK library - DJI_HardDriver.cppSerial device driver abstraction. See DJI_HardDriver.h for more info - DJI_HotPoint.cppHotpoint (Point of Interest) flight Control API for DJI onboardSDK library - DJI_Link.cppImplement send/read, app handling and data link layer for Core API of DJI onboardSDK library - DJI_Memory.cppImplement memory management for Core API of DJI onboardSDK library - DJI_Mission.cppMission Framework for DJI onboardSDK library - DJI_VirtualRC.cppVirtual Radio Control API for DJI onboardSDK library - DJI_WayPoint.cppWaypoint flight API for DJI onboardSDK library + DJI_Follow.cpp + DJI_HotPoint.cpp + DJI_Link.cppImplement send/read, app handling and data link layer for Core API of DJI onboardSDK library + DJI_Memory.cpp + DJI_Mission.cppMission Framework for DJI onboardSDK library + DJI_VirtualRC.cpp + DJI_WayPoint.cpp diff --git a/dji_sdk_doc/doxygen/html/functions.html b/dji_sdk_doc/doxygen/html/functions.html index 6b346d2e..d8fcb06a 100644 --- a/dji_sdk_doc/doxygen/html/functions.html +++ b/dji_sdk_doc/doxygen/html/functions.html @@ -121,11 +121,8 @@

    - a -

    • a : DJI::onboardSDK::BroadcastData
    • -
    • ack_data -: DJI::onboardSDK::CoreAPI -
    • activate() -: DJI::onboardSDK::CoreAPI +: DJI::onboardSDK::CoreAPI
    • activation : DJI::onboardSDK::BroadcastData @@ -219,9 +216,6 @@

      - g -

      • getMagnet() : DJI::onboardSDK::Flight
      • -
      • getObtainControlMobileCMD() -: DJI::onboardSDK::CoreAPI -
      • getQuaternion() : DJI::onboardSDK::Flight
      • @@ -291,16 +285,10 @@

        - n -

        - p -

          -
        • parseFromMobileCallback() -: DJI::onboardSDK::CoreAPI -
        • pause() : DJI::onboardSDK::Follow , DJI::onboardSDK::WayPoint @@ -355,24 +343,17 @@

          - s -

          • setAccountData() : DJI::onboardSDK::CoreAPI
          • -
          • setACKFrameStatus() -: DJI::onboardSDK::CoreAPI -
          • setActivation() : DJI::onboardSDK::CoreAPI
          • setBroadcastFreq() : DJI::onboardSDK::CoreAPI
          • -
          • setBroadcastFreqDefaults() -: DJI::onboardSDK::CoreAPI -
          • setCamera() : DJI::onboardSDK::Camera
          • setControl() -: DJI::onboardSDK::CoreAPI -, DJI::onboardSDK::VirtualRC +: DJI::onboardSDK::VirtualRC
          • setData() : DJI::onboardSDK::Follow @@ -393,9 +374,6 @@

            - s -

            • setMovementControl() : DJI::onboardSDK::Flight
            • -
            • setObtainControlMobileCallback() -: DJI::onboardSDK::CoreAPI -
            • setVersion() : DJI::onboardSDK::CoreAPI
            • @@ -408,9 +386,6 @@

              - s -

              @@ -463,7 +438,7 @@

              - y -

                diff --git a/dji_sdk_doc/doxygen/html/functions_enum.html b/dji_sdk_doc/doxygen/html/functions_enum.html index e97b23a9..5d4025b1 100644 --- a/dji_sdk_doc/doxygen/html/functions_enum.html +++ b/dji_sdk_doc/doxygen/html/functions_enum.html @@ -112,7 +112,7 @@ diff --git a/dji_sdk_doc/doxygen/html/functions_eval.html b/dji_sdk_doc/doxygen/html/functions_eval.html index 436ad99a..f0697e5c 100644 --- a/dji_sdk_doc/doxygen/html/functions_eval.html +++ b/dji_sdk_doc/doxygen/html/functions_eval.html @@ -103,7 +103,7 @@ diff --git a/dji_sdk_doc/doxygen/html/functions_func.html b/dji_sdk_doc/doxygen/html/functions_func.html index d7c758e1..e67a0fe8 100644 --- a/dji_sdk_doc/doxygen/html/functions_func.html +++ b/dji_sdk_doc/doxygen/html/functions_func.html @@ -190,9 +190,6 @@

                - g -

                • getMagnet() : DJI::onboardSDK::Flight
                • -
                • getObtainControlMobileCMD() -: DJI::onboardSDK::CoreAPI -
                • getQuaternion() : DJI::onboardSDK::Flight
                • @@ -228,16 +225,10 @@

                  - n -

                  - p -

                    -
                  • parseFromMobileCallback() -: DJI::onboardSDK::CoreAPI -
                  • pause() : DJI::onboardSDK::Follow , DJI::onboardSDK::WayPoint @@ -274,24 +265,17 @@

                    - s -

                    • setAccountData() : DJI::onboardSDK::CoreAPI
                    • -
                    • setACKFrameStatus() -: DJI::onboardSDK::CoreAPI -
                    • setActivation() : DJI::onboardSDK::CoreAPI
                    • setBroadcastFreq() : DJI::onboardSDK::CoreAPI
                    • -
                    • setBroadcastFreqDefaults() -: DJI::onboardSDK::CoreAPI -
                    • setCamera() : DJI::onboardSDK::Camera
                    • setControl() -: DJI::onboardSDK::CoreAPI -, DJI::onboardSDK::VirtualRC +: DJI::onboardSDK::VirtualRC
                    • setData() : DJI::onboardSDK::Follow @@ -312,9 +296,6 @@

                      - s -

                      • setMovementControl() : DJI::onboardSDK::Flight
                      • -
                      • setObtainControlMobileCallback() -: DJI::onboardSDK::CoreAPI -
                      • setVersion() : DJI::onboardSDK::CoreAPI
                      • @@ -351,7 +332,7 @@

                        - u -

                          diff --git a/dji_sdk_doc/doxygen/html/functions_vars.html b/dji_sdk_doc/doxygen/html/functions_vars.html index 1912c424..a601e973 100644 --- a/dji_sdk_doc/doxygen/html/functions_vars.html +++ b/dji_sdk_doc/doxygen/html/functions_vars.html @@ -96,9 +96,6 @@
                        • a : DJI::onboardSDK::BroadcastData
                        • -
                        • ack_data -: DJI::onboardSDK::CoreAPI -
                        • activation : DJI::onboardSDK::BroadcastData
                        • @@ -141,9 +138,6 @@
                        • roll : DJI::onboardSDK::VirtualRCData
                        • -
                        • stopCond -: DJI::onboardSDK::CoreAPI -
                        • time : DJI::onboardSDK::TimeStampData
                        • @@ -158,7 +152,7 @@ diff --git a/dji_sdk_doc/doxygen/html/globals.html b/dji_sdk_doc/doxygen/html/globals.html index 81862241..6ee76ce3 100644 --- a/dji_sdk_doc/doxygen/html/globals.html +++ b/dji_sdk_doc/doxygen/html/globals.html @@ -91,8 +91,8 @@
                          Here is a list of all documented file members with links to the documentation:
                          diff --git a/dji_sdk_doc/doxygen/html/globals_defs.html b/dji_sdk_doc/doxygen/html/globals_defs.html index 13b6a5c9..19383554 100644 --- a/dji_sdk_doc/doxygen/html/globals_defs.html +++ b/dji_sdk_doc/doxygen/html/globals_defs.html @@ -91,9 +91,6 @@
                           
                          diff --git a/dji_sdk_doc/doxygen/html/globals_func.html b/dji_sdk_doc/doxygen/html/globals_func.html index b30de915..de671ae7 100644 --- a/dji_sdk_doc/doxygen/html/globals_func.html +++ b/dji_sdk_doc/doxygen/html/globals_func.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/globals_type.html b/dji_sdk_doc/doxygen/html/globals_type.html index e8f82329..65d7c677 100644 --- a/dji_sdk_doc/doxygen/html/globals_type.html +++ b/dji_sdk_doc/doxygen/html/globals_type.html @@ -91,6 +91,9 @@
                           
                          diff --git a/dji_sdk_doc/doxygen/html/index.html b/dji_sdk_doc/doxygen/html/index.html index dc38b7a0..ec83477b 100644 --- a/dji_sdk_doc/doxygen/html/index.html +++ b/dji_sdk_doc/doxygen/html/index.html @@ -84,11 +84,11 @@

                          Introduction

                          API class documentation is available here. Click on the Files/Classes/Namespaces tabs above to see more information about the library.
                          - Documentation for the SDK has moved to the DJI Developer Website. Please refer to the Programming Guide for more information.

                          +Documentation for the SDK has moved to the DJI Developer Website. Please refer to the Programming Guide for more information.

                          diff --git a/dji_sdk_doc/doxygen/html/namespaceDJI.html b/dji_sdk_doc/doxygen/html/namespaceDJI.html index 6a9a9902..a5cf239a 100644 --- a/dji_sdk_doc/doxygen/html/namespaceDJI.html +++ b/dji_sdk_doc/doxygen/html/namespaceDJI.html @@ -114,11 +114,11 @@ typedef uint64_t time_us   -typedef void * UserData - This is used as the datatype for all data arguments in callbacks.
                          +typedef void * UserData   -typedef uint32_t Flag +typedef uint32_t Flag + This is used as the datatype for all data arguments in callbacks.
                            typedef uint8_t size8_t @@ -143,7 +143,7 @@

                          Detailed Description

                          Note
                          for ARMCC-5.0 compiler
                          -
                          Attention
                          Do not modify any definition in this file if you are unsure of what are you doing. DJI will not provide any support for changes made to this file.
                          +
                          Attention
                          Do not modify any definition in this file if you are not sure what are you doing. DJI will not provide any support for changes made to this file.

                          Typedef Documentation

                          @@ -154,7 +154,7 @@
                          -
                          Todo:
                          range mathematial class class Angle { public: Angle(double degree = 0);
                          +
                          Todo:
                          range mathematial class class Angle { public: Angle(double degree = 0);

                          private: double degree; };

                          @@ -220,7 +220,7 @@
                          -
                          Warning
                          This struct will be replaced by Vector3dData (similar to Vector3fData in DJI_Type.h) in a future release.
                          +
                          Warning
                          This struct will be replaced by Vector3dData (similar to Vector3fData in DJI_Type.h) in a future release.
                          @@ -240,7 +240,7 @@ diff --git a/dji_sdk_doc/doxygen/html/namespacemembers.html b/dji_sdk_doc/doxygen/html/namespacemembers.html index 226b8488..d1f42a44 100644 --- a/dji_sdk_doc/doxygen/html/namespacemembers.html +++ b/dji_sdk_doc/doxygen/html/namespacemembers.html @@ -98,6 +98,9 @@
                        • EulerianAngle : DJI
                        • +
                        • Flag +: DJI +
                        • Measure : DJI
                        • @@ -107,9 +110,6 @@
                        • SpaceVector : DJI
                        • -
                        • UserData -: DJI -
                        • Vector3dData : DJI
                        • @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/namespacemembers_type.html b/dji_sdk_doc/doxygen/html/namespacemembers_type.html index 41cbeb70..af44311c 100644 --- a/dji_sdk_doc/doxygen/html/namespacemembers_type.html +++ b/dji_sdk_doc/doxygen/html/namespacemembers_type.html @@ -98,6 +98,9 @@
                        • EulerianAngle : DJI
                        • +
                        • Flag +: DJI +
                        • Measure : DJI
                        • @@ -107,9 +110,6 @@
                        • SpaceVector : DJI
                        • -
                        • UserData -: DJI -
                        • Vector3dData : DJI
                        • @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/namespaces.html b/dji_sdk_doc/doxygen/html/namespaces.html index 4dad3dcc..bd716650 100644 --- a/dji_sdk_doc/doxygen/html/namespaces.html +++ b/dji_sdk_doc/doxygen/html/namespaces.html @@ -94,7 +94,7 @@ diff --git a/dji_sdk_doc/doxygen/html/pages.html b/dji_sdk_doc/doxygen/html/pages.html index 0d4c67db..c2f4aeb2 100644 --- a/dji_sdk_doc/doxygen/html/pages.html +++ b/dji_sdk_doc/doxygen/html/pages.html @@ -89,7 +89,7 @@ diff --git a/dji_sdk_doc/doxygen/html/search/all_0.js b/dji_sdk_doc/doxygen/html/search/all_0.js index 660e9976..f7f3e011 100644 --- a/dji_sdk_doc/doxygen/html/search/all_0.js +++ b/dji_sdk_doc/doxygen/html/search/all_0.js @@ -1,4 +1,16 @@ var searchData= [ - ['_5f_5funused',['__UNUSED',['../DJI__Type_8h.html#a6c30d490cd2302ff05d355f3ec844c1f',1,'DJI_Type.h']]] + ['a',['a',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#ae0abd37507060ab7d48d158abd409d25',1,'DJI::onboardSDK::BroadcastData']]], + ['ack',['Ack',['../structDJI_1_1onboardSDK_1_1Ack.html',1,'DJI::onboardSDK']]], + ['ack_5fcommon_5fcode',['ACK_COMMON_CODE',['../DJI__API_8h.html#aec259c8a8cf384789e0726ecf0773cbd',1,'DJI::onboardSDK']]], + ['acksession',['ACKSession',['../structDJI_1_1onboardSDK_1_1ACKSession.html',1,'DJI::onboardSDK']]], + ['activate',['activate',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a8466a9e84832b06f529b5a8c4add13c2',1,'DJI::onboardSDK::CoreAPI']]], + ['activatedata',['ActivateData',['../structActivateData.html',1,'ActivateData'],['../DJI__App_8h.html#a173a3ff7edd0475f8e6ac7060bec5058',1,'ActivateData(): DJI_App.h']]], + ['activation',['activation',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#adcc7240b20c1e562808cbbe815f9dcf7',1,'DJI::onboardSDK::BroadcastData']]], + ['aes256_5fdecrypt_5fecb',['aes256_decrypt_ecb',['../DJI__Codec_8cpp.html#a34034040728c3dc9f29845ac7fb8fe31',1,'DJI_Codec.cpp']]], + ['altitude',['altitude',['../structDJI_1_1onboardSDK_1_1PositionData.html#ac006d44f830b1493da4f672bf25b2ad1',1,'DJI::onboardSDK::PositionData::altitude()'],['../structDJI_1_1onboardSDK_1_1GPSPositionData.html#acd215ea39f8ef93865d200fc8b2c3b0a',1,'DJI::onboardSDK::GPSPositionData::altitude()'],['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#abf0a0f48abdee783e911c2e425924c04',1,'DJI::onboardSDK::WayPointInitData::altitude()']]], + ['angle',['Angle',['../namespaceDJI.html#a2cefac21654530417c2fa39c8e7ef709',1,'DJI']]], + ['api_5ferror_5fdata',['API_ERROR_DATA',['../DJI__Config_8h.html#a27a3f3004903b8fb75fb414b1068a1d6',1,'DJI_Config.h']]], + ['api_5flog',['API_LOG',['../DJI__Type_8h.html#a2c663cc30300205e6a25232ef72f25e3',1,'DJI_Type.h']]], + ['armcallback',['armCallback',['../classDJI_1_1onboardSDK_1_1Flight.html#ae4f2810f68f99c675adf16bbd5131985',1,'DJI::onboardSDK::Flight']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_1.js b/dji_sdk_doc/doxygen/html/search/all_1.js index 1dcb3474..c6baee2a 100644 --- a/dji_sdk_doc/doxygen/html/search/all_1.js +++ b/dji_sdk_doc/doxygen/html/search/all_1.js @@ -1,17 +1,8 @@ var searchData= [ - ['a',['a',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#ae0abd37507060ab7d48d158abd409d25',1,'DJI::onboardSDK::BroadcastData']]], - ['ack',['Ack',['../structDJI_1_1onboardSDK_1_1Ack.html',1,'DJI::onboardSDK']]], - ['ack_5fdata',['ack_data',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aadc5da4d57b8eaa5b7bdb5ed29a0bf69',1,'DJI::onboardSDK::CoreAPI']]], - ['ack_5ferror_5fcode',['ACK_ERROR_CODE',['../DJI__API_8h.html#ae9b83ce82c2006a3c98b5564354985c9',1,'DJI::onboardSDK']]], - ['acksession',['ACKSession',['../structDJI_1_1onboardSDK_1_1ACKSession.html',1,'DJI::onboardSDK']]], - ['activate',['activate',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a8466a9e84832b06f529b5a8c4add13c2',1,'DJI::onboardSDK::CoreAPI::activate(ActivateData *data, CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aa86e92debf14c980712fd2805eed70e0',1,'DJI::onboardSDK::CoreAPI::activate(ActivateData *data, int timeout)']]], - ['activatedata',['ActivateData',['../structDJI_1_1onboardSDK_1_1ActivateData.html',1,'DJI::onboardSDK']]], - ['activation',['activation',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#adcc7240b20c1e562808cbbe815f9dcf7',1,'DJI::onboardSDK::BroadcastData']]], - ['aes256_5fdecrypt_5fecb',['aes256_decrypt_ecb',['../DJI__Codec_8cpp.html#a34034040728c3dc9f29845ac7fb8fe31',1,'DJI_Codec.cpp']]], - ['altitude',['altitude',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#abf0a0f48abdee783e911c2e425924c04',1,'DJI::onboardSDK::WayPointInitData::altitude()'],['../structDJI_1_1onboardSDK_1_1PositionData.html#ac006d44f830b1493da4f672bf25b2ad1',1,'DJI::onboardSDK::PositionData::altitude()'],['../structDJI_1_1onboardSDK_1_1GPSPositionData.html#acd215ea39f8ef93865d200fc8b2c3b0a',1,'DJI::onboardSDK::GPSPositionData::altitude()']]], - ['angle',['Angle',['../namespaceDJI.html#a2cefac21654530417c2fa39c8e7ef709',1,'DJI']]], - ['api_5ferror_5fdata',['API_ERROR_DATA',['../DJI__Config_8h.html#a27a3f3004903b8fb75fb414b1068a1d6',1,'DJI_Config.h']]], - ['api_5flog',['API_LOG',['../DJI__Type_8h.html#a2c663cc30300205e6a25232ef72f25e3',1,'DJI_Type.h']]], - ['armcallback',['armCallback',['../classDJI_1_1onboardSDK_1_1Flight.html#ae4f2810f68f99c675adf16bbd5131985',1,'DJI::onboardSDK::Flight']]] + ['battery',['battery',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a9c77ee1bd184f457446aeed07de02434',1,'DJI::onboardSDK::BroadcastData']]], + ['broadcastdata',['BroadcastData',['../DJI__Type_8h.html#ae6cbba03541bc7bf7d4956e744d026af',1,'DJI::onboardSDK']]], + ['broadcastdata',['BroadcastData',['../structDJI_1_1onboardSDK_1_1BroadcastData.html',1,'DJI::onboardSDK']]], + ['bytehandler',['byteHandler',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af9269aa61bcab29c1deeee70d82ebf53',1,'DJI::onboardSDK::CoreAPI']]], + ['bytestreamhandler',['byteStreamHandler',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a1e60c24675d8af3aee0cd275f3cd4a42',1,'DJI::onboardSDK::CoreAPI']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_10.js b/dji_sdk_doc/doxygen/html/search/all_10.js index ce7df6ba..0a9246e3 100644 --- a/dji_sdk_doc/doxygen/html/search/all_10.js +++ b/dji_sdk_doc/doxygen/html/search/all_10.js @@ -1,32 +1,11 @@ var searchData= [ - ['sdkfilter',['SDKFilter',['../structDJI_1_1onboardSDK_1_1SDKFilter.html',1,'DJI::onboardSDK']]], - ['sdkfilter',['SDKFilter',['../DJI__Type_8h.html#aac87b726305048671bd3c874dfca5e7e',1,'DJI::onboardSDK']]], - ['send',['send',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#accec1bc503740cc4540142a2d8c403db',1,'DJI::onboardSDK::CoreAPI::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)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a34f54e10c7faec4ac0f921cdfa6baf67',1,'DJI::onboardSDK::CoreAPI::send(unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, size_t len, int timeout=0, int retry_time=1, CallBack ack_handler=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ae541770460eb82571214aa7aa5370a21',1,'DJI::onboardSDK::CoreAPI::send(Command *parameter)']]], - ['senddata',['sendData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a72a474c78f12b733244eec8a68d73f5b',1,'DJI::onboardSDK::VirtualRC::sendData(VirtualRCData Data)'],['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a1b6b198870cd24af401dcf75b2493730',1,'DJI::onboardSDK::VirtualRC::sendData()']]], - ['sendpoll',['sendPoll',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5373ef1d252b233a022cc08e7b6df96c',1,'DJI::onboardSDK::CoreAPI']]], - ['sendsafemodedata',['sendSafeModeData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a26bb84b709df68859b7caecefa190849',1,'DJI::onboardSDK::VirtualRC']]], - ['sense_5fmid',['SENSE_MID',['../classDJI_1_1onboardSDK_1_1Follow.html#a963f944b2aaf7b0719a29ee221a56d51a1173b26e1704b80b43232ae269e5701f',1,'DJI::onboardSDK::Follow']]], - ['sensitivity',['SENSITIVITY',['../classDJI_1_1onboardSDK_1_1Follow.html#a963f944b2aaf7b0719a29ee221a56d51',1,'DJI::onboardSDK::Follow']]], - ['setaccountdata',['setAccountData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a76c8fa26fdc252af20b013928ec03ad6',1,'DJI::onboardSDK::CoreAPI']]], - ['setackframestatus',['setACKFrameStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a078feb6bf36b83eb65f5e49b1ace8801',1,'DJI::onboardSDK::CoreAPI']]], - ['setactivation',['setActivation',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a2a8f3380779cf660be316aa45470bb99',1,'DJI::onboardSDK::CoreAPI']]], - ['setbroadcastfreq',['setBroadcastFreq',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5490da3ad6bf7ea37f89783a4a75689a',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af49c3a3266e9a135f71b64c030106e7e',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, int timeout)']]], - ['setbroadcastfreqdefaults',['setBroadcastFreqDefaults',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac02ec7458365af90e9ea4e17ac9e08d1',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreqDefaults()'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5938890f73c9764cb8ceea6bb7d57634',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreqDefaults(int timeout)']]], - ['setcamera',['setCamera',['../classDJI_1_1onboardSDK_1_1Camera.html#a5f5a5e955ca32578a55635cdc6351efb',1,'DJI::onboardSDK::Camera']]], - ['setcontrol',['setControl',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a9148f90dc5a0a63511aef905d8890363',1,'DJI::onboardSDK::CoreAPI::setControl()'],['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a561e25be8d98214360affe7907b52f63',1,'DJI::onboardSDK::VirtualRC::setControl()']]], - ['setdata',['setData',['../classDJI_1_1onboardSDK_1_1Follow.html#adcdf0d6d3f33a6cb1f7ee5d65f064d7f',1,'DJI::onboardSDK::Follow::setData()'],['../classDJI_1_1onboardSDK_1_1HotPoint.html#a71572a01dfd5fe36fed492114d0652bc',1,'DJI::onboardSDK::HotPoint::setData()']]], - ['setdriver',['setDriver',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af11e76e300013a8d9a229019eaf01ab8',1,'DJI::onboardSDK::CoreAPI']]], - ['setfollowdata',['setFollowData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aee573550da2469e7992097540550faef',1,'DJI::onboardSDK::CoreAPI']]], - ['sethotpointdata',['setHotPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aeec7ae9063e509bbd6bf6039ead9be00',1,'DJI::onboardSDK::CoreAPI']]], - ['setinfo',['setInfo',['../classDJI_1_1onboardSDK_1_1WayPoint.html#a697de2d4ae1666c9504755c3307324fb',1,'DJI::onboardSDK::WayPoint']]], - ['setmovementcontrol',['setMovementControl',['../classDJI_1_1onboardSDK_1_1Flight.html#a53ae6a258cac9f81337e6cd1488d9347',1,'DJI::onboardSDK::Flight']]], - ['setobtaincontrolmobilecallback',['setObtainControlMobileCallback',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a221c804340554e0c04b31e8eeba96b33',1,'DJI::onboardSDK::CoreAPI']]], - ['setversion',['setVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aadeecafaad54eeabdfd6212d2b64ea3d',1,'DJI::onboardSDK::CoreAPI']]], - ['setwaypointdata',['setWayPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac8cad19f2b08d929011ad923cf87f45f',1,'DJI::onboardSDK::CoreAPI']]], - ['smoothmode',['SmoothMode',['../classDJI_1_1onboardSDK_1_1Flight.html#a2ba6b590d35f3a2d9c8fb737b5150454',1,'DJI::onboardSDK::Flight']]], - ['spacevector',['SpaceVector',['../namespaceDJI.html#ad1dc49f750d830612593ed9253e4502a',1,'DJI']]], - ['spacevector',['SpaceVector',['../structDJI_1_1SpaceVector.html',1,'DJI']]], - ['start',['start',['../classDJI_1_1onboardSDK_1_1HotPoint.html#a92446411eb21eea88736280fa6c05bee',1,'DJI::onboardSDK::HotPoint']]], - ['stopcond',['stopCond',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a0b5f3dbc0a3113b89ffec5f9bc47609b',1,'DJI::onboardSDK::CoreAPI']]] + ['tagaes256context',['tagAES256Context',['../structtagAES256Context.html',1,'']]], + ['task',['task',['../classDJI_1_1onboardSDK_1_1Flight.html#a758a6c38d51b77ba943024ad8aee26e6',1,'DJI::onboardSDK::Flight']]], + ['taskdata',['TaskData',['../structDJI_1_1onboardSDK_1_1TaskData.html',1,'DJI::onboardSDK']]], + ['time',['time',['../structDJI_1_1onboardSDK_1_1TimeStampData.html#aea9d03bc043adf819a0529665db64fa8',1,'DJI::onboardSDK::TimeStampData']]], + ['timestampdata',['TimeStampData',['../structDJI_1_1onboardSDK_1_1TimeStampData.html',1,'DJI::onboardSDK']]], + ['todo_20list',['Todo List',['../todo.html',1,'']]], + ['toeulerianangle',['toEulerianAngle',['../classDJI_1_1onboardSDK_1_1Flight.html#a782c40da11ad290e1156e78d72170f08',1,'DJI::onboardSDK::Flight']]], + ['toradiodata',['toRadioData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a73145c476b89e8eb38a7d858411b8457',1,'DJI::onboardSDK::VirtualRC']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_11.js b/dji_sdk_doc/doxygen/html/search/all_11.js index 0a9246e3..cc1211ca 100644 --- a/dji_sdk_doc/doxygen/html/search/all_11.js +++ b/dji_sdk_doc/doxygen/html/search/all_11.js @@ -1,11 +1,6 @@ var searchData= [ - ['tagaes256context',['tagAES256Context',['../structtagAES256Context.html',1,'']]], - ['task',['task',['../classDJI_1_1onboardSDK_1_1Flight.html#a758a6c38d51b77ba943024ad8aee26e6',1,'DJI::onboardSDK::Flight']]], - ['taskdata',['TaskData',['../structDJI_1_1onboardSDK_1_1TaskData.html',1,'DJI::onboardSDK']]], - ['time',['time',['../structDJI_1_1onboardSDK_1_1TimeStampData.html#aea9d03bc043adf819a0529665db64fa8',1,'DJI::onboardSDK::TimeStampData']]], - ['timestampdata',['TimeStampData',['../structDJI_1_1onboardSDK_1_1TimeStampData.html',1,'DJI::onboardSDK']]], - ['todo_20list',['Todo List',['../todo.html',1,'']]], - ['toeulerianangle',['toEulerianAngle',['../classDJI_1_1onboardSDK_1_1Flight.html#a782c40da11ad290e1156e78d72170f08',1,'DJI::onboardSDK::Flight']]], - ['toradiodata',['toRadioData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a73145c476b89e8eb38a7d858411b8457',1,'DJI::onboardSDK::VirtualRC']]] + ['updatetarget',['updateTarget',['../classDJI_1_1onboardSDK_1_1Follow.html#af8f6a63b95c36febe8164e2002fd813d',1,'DJI::onboardSDK::Follow']]], + ['uploadindexdata',['uploadIndexData',['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae2f37131569b4e0ee50e6ff0e69af86b',1,'DJI::onboardSDK::WayPoint::uploadIndexData(WayPointData *data, CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1WayPoint.html#a6a49aa300981094c6be97b0d198ae876',1,'DJI::onboardSDK::WayPoint::uploadIndexData(uint8_t pos, CallBack callback=0, UserData userData=0)']]], + ['use_5fencrypt',['USE_ENCRYPT',['../DJI__Config_8h.html#ab711b1ed161a4ec825c22523cda3dc6d',1,'DJI_Config.h']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_12.js b/dji_sdk_doc/doxygen/html/search/all_12.js index d232de67..5feb3043 100644 --- a/dji_sdk_doc/doxygen/html/search/all_12.js +++ b/dji_sdk_doc/doxygen/html/search/all_12.js @@ -1,7 +1,14 @@ var searchData= [ - ['updatetarget',['updateTarget',['../classDJI_1_1onboardSDK_1_1Follow.html#af8f6a63b95c36febe8164e2002fd813d',1,'DJI::onboardSDK::Follow']]], - ['uploadindexdata',['uploadIndexData',['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae2f37131569b4e0ee50e6ff0e69af86b',1,'DJI::onboardSDK::WayPoint::uploadIndexData(WayPointData *data, CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1WayPoint.html#a6a49aa300981094c6be97b0d198ae876',1,'DJI::onboardSDK::WayPoint::uploadIndexData(uint8_t pos, CallBack callback=0, UserData userData=0)']]], - ['use_5fencrypt',['USE_ENCRYPT',['../DJI__Config_8h.html#ab711b1ed161a4ec825c22523cda3dc6d',1,'DJI_Config.h']]], - ['userdata',['UserData',['../namespaceDJI.html#a0988c6a482e73ea79bc55aac26729302',1,'DJI']]] + ['vector3ddata',['Vector3dData',['../structDJI_1_1Vector3dData.html',1,'DJI']]], + ['vector3ddata',['Vector3dData',['../namespaceDJI.html#a28c3320e81dd92ca9907acd13108a901',1,'DJI']]], + ['vector3fdata',['Vector3fData',['../structDJI_1_1onboardSDK_1_1Vector3fData.html',1,'DJI::onboardSDK']]], + ['vector3fdata',['Vector3fData',['../DJI__Type_8h.html#a0fa0b666ea11bdb3c40cb0283a8a0b0e',1,'DJI::onboardSDK']]], + ['velocitydata',['VelocityData',['../structDJI_1_1onboardSDK_1_1VelocityData.html',1,'DJI::onboardSDK']]], + ['velocityground',['velocityGround',['../structDJI_1_1onboardSDK_1_1RTKData.html#a002a95cd7df302a8622651b82fb5c173',1,'DJI::onboardSDK::RTKData::velocityGround()'],['../structDJI_1_1onboardSDK_1_1GPSData.html#ac33952b3d773936e44c478bd1e028ea9',1,'DJI::onboardSDK::GPSData::velocityGround()']]], + ['version',['Version',['../DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495',1,'DJI::onboardSDK']]], + ['versiondata',['VersionData',['../structVersionData.html',1,'']]], + ['virtualrc',['VirtualRC',['../classDJI_1_1onboardSDK_1_1VirtualRC.html',1,'DJI::onboardSDK']]], + ['virtualrcdata',['VirtualRCData',['../structDJI_1_1onboardSDK_1_1VirtualRCData.html',1,'DJI::onboardSDK']]], + ['virtualrcsetting',['VirtualRCSetting',['../structDJI_1_1onboardSDK_1_1VirtualRCSetting.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_13.js b/dji_sdk_doc/doxygen/html/search/all_13.js index 820e68d6..425788bc 100644 --- a/dji_sdk_doc/doxygen/html/search/all_13.js +++ b/dji_sdk_doc/doxygen/html/search/all_13.js @@ -1,14 +1,10 @@ var searchData= [ - ['vector3ddata',['Vector3dData',['../structDJI_1_1Vector3dData.html',1,'DJI']]], - ['vector3ddata',['Vector3dData',['../namespaceDJI.html#a28c3320e81dd92ca9907acd13108a901',1,'DJI']]], - ['vector3fdata',['Vector3fData',['../structDJI_1_1onboardSDK_1_1Vector3fData.html',1,'DJI::onboardSDK']]], - ['vector3fdata',['Vector3fData',['../DJI__Type_8h.html#a0fa0b666ea11bdb3c40cb0283a8a0b0e',1,'DJI::onboardSDK']]], - ['velocitydata',['VelocityData',['../structDJI_1_1onboardSDK_1_1VelocityData.html',1,'DJI::onboardSDK']]], - ['velocityground',['velocityGround',['../structDJI_1_1onboardSDK_1_1RTKData.html#a002a95cd7df302a8622651b82fb5c173',1,'DJI::onboardSDK::RTKData::velocityGround()'],['../structDJI_1_1onboardSDK_1_1GPSData.html#ac33952b3d773936e44c478bd1e028ea9',1,'DJI::onboardSDK::GPSData::velocityGround()']]], - ['version',['Version',['../DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495',1,'DJI::onboardSDK']]], - ['versiondata',['VersionData',['../structDJI_1_1onboardSDK_1_1VersionData.html',1,'DJI::onboardSDK']]], - ['virtualrc',['VirtualRC',['../classDJI_1_1onboardSDK_1_1VirtualRC.html',1,'DJI::onboardSDK']]], - ['virtualrcdata',['VirtualRCData',['../structDJI_1_1onboardSDK_1_1VirtualRCData.html',1,'DJI::onboardSDK']]], - ['virtualrcsetting',['VirtualRCSetting',['../structDJI_1_1onboardSDK_1_1VirtualRCSetting.html',1,'DJI::onboardSDK']]] + ['w',['w',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a04c82cbd21eb9903984de09a4b770b88',1,'DJI::onboardSDK::BroadcastData']]], + ['waypoint',['WayPoint',['../classDJI_1_1onboardSDK_1_1WayPoint.html',1,'DJI::onboardSDK']]], + ['waypointdata',['WayPointData',['../structDJI_1_1onboardSDK_1_1WayPointData.html',1,'DJI::onboardSDK']]], + ['waypointdataack',['WayPointDataACK',['../structDJI_1_1onboardSDK_1_1WayPointDataACK.html',1,'DJI::onboardSDK']]], + ['waypointinitack',['WayPointInitACK',['../structDJI_1_1onboardSDK_1_1WayPointInitACK.html',1,'DJI::onboardSDK']]], + ['waypointinitdata',['WayPointInitData',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html',1,'DJI::onboardSDK']]], + ['waypointvelocityack',['WayPointVelocityACK',['../structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_14.js b/dji_sdk_doc/doxygen/html/search/all_14.js index 42fd4f18..0ba44595 100644 --- a/dji_sdk_doc/doxygen/html/search/all_14.js +++ b/dji_sdk_doc/doxygen/html/search/all_14.js @@ -1,11 +1,5 @@ var searchData= [ - ['w',['w',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a04c82cbd21eb9903984de09a4b770b88',1,'DJI::onboardSDK::BroadcastData']]], - ['waypoint',['WayPoint',['../classDJI_1_1onboardSDK_1_1WayPoint.html',1,'DJI::onboardSDK']]], - ['waypointdata',['WayPointData',['../structDJI_1_1onboardSDK_1_1WayPointData.html',1,'DJI::onboardSDK']]], - ['waypointdataack',['WayPointDataACK',['../structDJI_1_1onboardSDK_1_1WayPointDataACK.html',1,'DJI::onboardSDK']]], - ['waypointinitack',['WayPointInitACK',['../structDJI_1_1onboardSDK_1_1WayPointInitACK.html',1,'DJI::onboardSDK']]], - ['waypointinitdata',['WayPointInitData',['../DJI__Type_8h.html#a25838ff0bcdcd511b138675bbf5c164b',1,'DJI::onboardSDK']]], - ['waypointinitdata',['WayPointInitData',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html',1,'DJI::onboardSDK']]], - ['waypointvelocityack',['WayPointVelocityACK',['../structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html',1,'DJI::onboardSDK']]] + ['yawcoordinate',['YawCoordinate',['../classDJI_1_1onboardSDK_1_1Flight.html#aa04bc1ce0b8934691507e512cb393786',1,'DJI::onboardSDK::Flight']]], + ['yawrate',['YawRate',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate.html',1,'DJI::onboardSDK::HotPoint']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_15.html b/dji_sdk_doc/doxygen/html/search/all_15.html deleted file mode 100644 index 1331c0d7..00000000 --- a/dji_sdk_doc/doxygen/html/search/all_15.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
                          -
                          Loading...
                          -
                          - -
                          Searching...
                          -
                          No Matches
                          - -
                          - - diff --git a/dji_sdk_doc/doxygen/html/search/all_15.js b/dji_sdk_doc/doxygen/html/search/all_15.js deleted file mode 100644 index 0ba44595..00000000 --- a/dji_sdk_doc/doxygen/html/search/all_15.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['yawcoordinate',['YawCoordinate',['../classDJI_1_1onboardSDK_1_1Flight.html#aa04bc1ce0b8934691507e512cb393786',1,'DJI::onboardSDK::Flight']]], - ['yawrate',['YawRate',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate.html',1,'DJI::onboardSDK::HotPoint']]] -]; diff --git a/dji_sdk_doc/doxygen/html/search/all_2.js b/dji_sdk_doc/doxygen/html/search/all_2.js index c6baee2a..7dbb0bfa 100644 --- a/dji_sdk_doc/doxygen/html/search/all_2.js +++ b/dji_sdk_doc/doxygen/html/search/all_2.js @@ -1,8 +1,14 @@ var searchData= [ - ['battery',['battery',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a9c77ee1bd184f457446aeed07de02434',1,'DJI::onboardSDK::BroadcastData']]], - ['broadcastdata',['BroadcastData',['../DJI__Type_8h.html#ae6cbba03541bc7bf7d4956e744d026af',1,'DJI::onboardSDK']]], - ['broadcastdata',['BroadcastData',['../structDJI_1_1onboardSDK_1_1BroadcastData.html',1,'DJI::onboardSDK']]], - ['bytehandler',['byteHandler',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af9269aa61bcab29c1deeee70d82ebf53',1,'DJI::onboardSDK::CoreAPI']]], - ['bytestreamhandler',['byteStreamHandler',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a1e60c24675d8af3aee0cd275f3cd4a42',1,'DJI::onboardSDK::CoreAPI']]] + ['callbackhandler',['CallBackHandler',['../structDJI_1_1onboardSDK_1_1CallBackHandler.html',1,'DJI::onboardSDK']]], + ['callbackpoll',['callbackPoll',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac3111dfefd2a29b2c725e1474034b5cf',1,'DJI::onboardSDK::CoreAPI']]], + ['camera',['Camera',['../classDJI_1_1onboardSDK_1_1Camera.html',1,'DJI::onboardSDK']]], + ['cmd_5fset',['CMD_SET',['../DJI__API_8h.html#a367390bac5784ce51e903df4a1d94896',1,'DJI::onboardSDK']]], + ['cmdsession',['CMDSession',['../structDJI_1_1onboardSDK_1_1CMDSession.html',1,'DJI::onboardSDK']]], + ['command',['Command',['../structDJI_1_1onboardSDK_1_1Command.html',1,'DJI::onboardSDK']]], + ['commandparameter',['commandParameter',['../structDJI_1_1onboardSDK_1_1WayPointData.html#a0933d32e9093b6c5be7db767fcdf13f0',1,'DJI::onboardSDK::WayPointData']]], + ['commondata',['CommonData',['../structDJI_1_1onboardSDK_1_1CommonData.html',1,'DJI::onboardSDK']]], + ['commondata',['CommonData',['../DJI__Type_8h.html#a2ac407a46bc557c653eb82dee70a97ba',1,'DJI::onboardSDK']]], + ['coreapi',['CoreAPI',['../classDJI_1_1onboardSDK_1_1CoreAPI.html',1,'DJI::onboardSDK']]], + ['ctrlinfodata',['CtrlInfoData',['../structDJI_1_1onboardSDK_1_1CtrlInfoData.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_3.js b/dji_sdk_doc/doxygen/html/search/all_3.js index 242c4cdb..34358254 100644 --- a/dji_sdk_doc/doxygen/html/search/all_3.js +++ b/dji_sdk_doc/doxygen/html/search/all_3.js @@ -1,16 +1,35 @@ var searchData= [ - ['callback',['CallBack',['../DJI__Type_8h.html#a76838dd682b371ca42f6554eb60d6c93',1,'DJI::onboardSDK']]], - ['callbackhandler',['CallBackHandler',['../structDJI_1_1onboardSDK_1_1CallBackHandler.html',1,'DJI::onboardSDK']]], - ['callbackhandler',['CallBackHandler',['../DJI__Type_8h.html#a8d688793c294cf31870d06881be995be',1,'DJI::onboardSDK']]], - ['callbackpoll',['callbackPoll',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac3111dfefd2a29b2c725e1474034b5cf',1,'DJI::onboardSDK::CoreAPI']]], - ['camera',['Camera',['../classDJI_1_1onboardSDK_1_1Camera.html',1,'DJI::onboardSDK']]], - ['cmd_5fset',['CMD_SET',['../DJI__API_8h.html#a367390bac5784ce51e903df4a1d94896',1,'DJI::onboardSDK']]], - ['cmdsession',['CMDSession',['../structDJI_1_1onboardSDK_1_1CMDSession.html',1,'DJI::onboardSDK']]], - ['command',['Command',['../structDJI_1_1onboardSDK_1_1Command.html',1,'DJI::onboardSDK']]], - ['commandparameter',['commandParameter',['../structDJI_1_1onboardSDK_1_1WayPointData.html#a0933d32e9093b6c5be7db767fcdf13f0',1,'DJI::onboardSDK::WayPointData']]], - ['commondata',['CommonData',['../structDJI_1_1onboardSDK_1_1CommonData.html',1,'DJI::onboardSDK']]], - ['commondata',['CommonData',['../DJI__Type_8h.html#a2ac407a46bc557c653eb82dee70a97ba',1,'DJI::onboardSDK']]], - ['coreapi',['CoreAPI',['../classDJI_1_1onboardSDK_1_1CoreAPI.html',1,'DJI::onboardSDK']]], - ['ctrlinfodata',['CtrlInfoData',['../structDJI_1_1onboardSDK_1_1CtrlInfoData.html',1,'DJI::onboardSDK']]] + ['decodeackstatus',['decodeACKStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aa084ce8f8847bd4c87a23c01f01d07c2',1,'DJI::onboardSDK::CoreAPI']]], + ['decodemissionstatus',['decodeMissionStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a7be9cc64e49f061947e78956da20e5ef',1,'DJI::onboardSDK::CoreAPI']]], + ['deprecated_20list',['Deprecated List',['../deprecated.html',1,'']]], + ['devicestatus',['deviceStatus',['../structDJI_1_1onboardSDK_1_1CtrlInfoData.html#ade9507d21fa18fab2c2c265970272d90',1,'DJI::onboardSDK::CtrlInfoData']]], + ['dji',['DJI',['../namespaceDJI.html',1,'']]], + ['dji_5fapi_2ecpp',['DJI_API.cpp',['../DJI__API_8cpp.html',1,'']]], + ['dji_5fapi_2eh',['DJI_API.h',['../DJI__API_8h.html',1,'']]], + ['dji_5fapp_2ecpp',['DJI_App.cpp',['../DJI__App_8cpp.html',1,'']]], + ['dji_5fapp_2eh',['DJI_App.h',['../DJI__App_8h.html',1,'']]], + ['dji_5fcamera_2ecpp',['DJI_Camera.cpp',['../DJI__Camera_8cpp.html',1,'']]], + ['dji_5fcamera_2eh',['DJI_Camera.h',['../DJI__Camera_8h.html',1,'']]], + ['dji_5fcodec_2ecpp',['DJI_Codec.cpp',['../DJI__Codec_8cpp.html',1,'']]], + ['dji_5fcodec_2eh',['DJI_Codec.h',['../DJI__Codec_8h.html',1,'']]], + ['dji_5fconfig_2eh',['DJI_Config.h',['../DJI__Config_8h.html',1,'']]], + ['dji_5fflight_2ecpp',['DJI_Flight.cpp',['../DJI__Flight_8cpp.html',1,'']]], + ['dji_5fflight_2eh',['DJI_Flight.h',['../DJI__Flight_8h.html',1,'']]], + ['dji_5ffollow_2ecpp',['DJI_Follow.cpp',['../DJI__Follow_8cpp.html',1,'']]], + ['dji_5ffollow_2eh',['DJI_Follow.h',['../DJI__Follow_8h.html',1,'']]], + ['dji_5fharddriver_2eh',['DJI_HardDriver.h',['../DJI__HardDriver_8h.html',1,'']]], + ['dji_5fhotpoint_2ecpp',['DJI_HotPoint.cpp',['../DJI__HotPoint_8cpp.html',1,'']]], + ['dji_5fhotpoint_2eh',['DJI_HotPoint.h',['../DJI__HotPoint_8h.html',1,'']]], + ['dji_5flink_2ecpp',['DJI_Link.cpp',['../DJI__Link_8cpp.html',1,'']]], + ['dji_5flink_2eh',['DJI_Link.h',['../DJI__Link_8h.html',1,'']]], + ['dji_5fmemory_2ecpp',['DJI_Memory.cpp',['../DJI__Memory_8cpp.html',1,'']]], + ['dji_5fmission_2ecpp',['DJI_Mission.cpp',['../DJI__Mission_8cpp.html',1,'']]], + ['dji_5ftype_2eh',['DJI_Type.h',['../DJI__Type_8h.html',1,'']]], + ['dji_5fversion_2eh',['DJI_Version.h',['../DJI__Version_8h.html',1,'']]], + ['dji_5fvirtualrc_2ecpp',['DJI_VirtualRC.cpp',['../DJI__VirtualRC_8cpp.html',1,'']]], + ['dji_5fvirtualrc_2eh',['DJI_VirtualRC.h',['../DJI__VirtualRC_8h.html',1,'']]], + ['dji_5fwaypoint_2ecpp',['DJI_WayPoint.cpp',['../DJI__WayPoint_8cpp.html',1,'']]], + ['dji_5fwaypoint_2eh',['DJI_WayPoint.h',['../DJI__WayPoint_8h.html',1,'']]], + ['djicommontype_2eh',['DJICommonType.h',['../DJICommonType_8h.html',1,'']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_4.js b/dji_sdk_doc/doxygen/html/search/all_4.js index 28b554f6..4f3265b5 100644 --- a/dji_sdk_doc/doxygen/html/search/all_4.js +++ b/dji_sdk_doc/doxygen/html/search/all_4.js @@ -1,36 +1,7 @@ var searchData= [ - ['decodeackstatus',['decodeACKStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aa084ce8f8847bd4c87a23c01f01d07c2',1,'DJI::onboardSDK::CoreAPI']]], - ['decodemissionstatus',['decodeMissionStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a7be9cc64e49f061947e78956da20e5ef',1,'DJI::onboardSDK::CoreAPI']]], - ['deprecated_20list',['Deprecated List',['../deprecated.html',1,'']]], - ['devicestatus',['deviceStatus',['../structDJI_1_1onboardSDK_1_1CtrlInfoData.html#ade9507d21fa18fab2c2c265970272d90',1,'DJI::onboardSDK::CtrlInfoData']]], - ['dji',['DJI',['../namespaceDJI.html',1,'']]], - ['dji_5fapi_2ecpp',['DJI_API.cpp',['../DJI__API_8cpp.html',1,'']]], - ['dji_5fapi_2eh',['DJI_API.h',['../DJI__API_8h.html',1,'']]], - ['dji_5fapp_2ecpp',['DJI_App.cpp',['../DJI__App_8cpp.html',1,'']]], - ['dji_5fapp_2eh',['DJI_App.h',['../DJI__App_8h.html',1,'']]], - ['dji_5fcamera_2ecpp',['DJI_Camera.cpp',['../DJI__Camera_8cpp.html',1,'']]], - ['dji_5fcamera_2eh',['DJI_Camera.h',['../DJI__Camera_8h.html',1,'']]], - ['dji_5fcodec_2ecpp',['DJI_Codec.cpp',['../DJI__Codec_8cpp.html',1,'']]], - ['dji_5fcodec_2eh',['DJI_Codec.h',['../DJI__Codec_8h.html',1,'']]], - ['dji_5fconfig_2eh',['DJI_Config.h',['../DJI__Config_8h.html',1,'']]], - ['dji_5fflight_2ecpp',['DJI_Flight.cpp',['../DJI__Flight_8cpp.html',1,'']]], - ['dji_5fflight_2eh',['DJI_Flight.h',['../DJI__Flight_8h.html',1,'']]], - ['dji_5ffollow_2ecpp',['DJI_Follow.cpp',['../DJI__Follow_8cpp.html',1,'']]], - ['dji_5ffollow_2eh',['DJI_Follow.h',['../DJI__Follow_8h.html',1,'']]], - ['dji_5fharddriver_2ecpp',['DJI_HardDriver.cpp',['../DJI__HardDriver_8cpp.html',1,'']]], - ['dji_5fharddriver_2eh',['DJI_HardDriver.h',['../DJI__HardDriver_8h.html',1,'']]], - ['dji_5fhotpoint_2ecpp',['DJI_HotPoint.cpp',['../DJI__HotPoint_8cpp.html',1,'']]], - ['dji_5flink_2ecpp',['DJI_Link.cpp',['../DJI__Link_8cpp.html',1,'']]], - ['dji_5flink_2eh',['DJI_Link.h',['../DJI__Link_8h.html',1,'']]], - ['dji_5fmemory_2ecpp',['DJI_Memory.cpp',['../DJI__Memory_8cpp.html',1,'']]], - ['dji_5fmission_2ecpp',['DJI_Mission.cpp',['../DJI__Mission_8cpp.html',1,'']]], - ['dji_5fmission_2eh',['DJI_Mission.h',['../DJI__Mission_8h.html',1,'']]], - ['dji_5ftype_2eh',['DJI_Type.h',['../DJI__Type_8h.html',1,'']]], - ['dji_5fversion_2eh',['DJI_Version.h',['../DJI__Version_8h.html',1,'']]], - ['dji_5fvirtualrc_2ecpp',['DJI_VirtualRC.cpp',['../DJI__VirtualRC_8cpp.html',1,'']]], - ['dji_5fvirtualrc_2eh',['DJI_VirtualRC.h',['../DJI__VirtualRC_8h.html',1,'']]], - ['dji_5fwaypoint_2ecpp',['DJI_WayPoint.cpp',['../DJI__WayPoint_8cpp.html',1,'']]], - ['dji_5fwaypoint_2eh',['DJI_WayPoint.h',['../DJI__WayPoint_8h.html',1,'']]], - ['djicommontype_2eh',['DJICommonType.h',['../DJICommonType_8h.html',1,'']]] + ['eulerangle',['EulerAngle',['../structDJI_1_1EulerAngle.html',1,'DJI']]], + ['eulerangle',['EulerAngle',['../namespaceDJI.html#aca26b9a79a0952d7ea5d0a355e0a71db',1,'DJI']]], + ['eulerianangle',['EulerianAngle',['../namespaceDJI.html#aae40f85fe3ce9df771ab709f05db2d08',1,'DJI']]], + ['eulerianangle',['EulerianAngle',['../structDJI_1_1EulerianAngle.html',1,'DJI']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_5.js b/dji_sdk_doc/doxygen/html/search/all_5.js index 4f3265b5..6a743cdc 100644 --- a/dji_sdk_doc/doxygen/html/search/all_5.js +++ b/dji_sdk_doc/doxygen/html/search/all_5.js @@ -1,7 +1,10 @@ var searchData= [ - ['eulerangle',['EulerAngle',['../structDJI_1_1EulerAngle.html',1,'DJI']]], - ['eulerangle',['EulerAngle',['../namespaceDJI.html#aca26b9a79a0952d7ea5d0a355e0a71db',1,'DJI']]], - ['eulerianangle',['EulerianAngle',['../namespaceDJI.html#aae40f85fe3ce9df771ab709f05db2d08',1,'DJI']]], - ['eulerianangle',['EulerianAngle',['../structDJI_1_1EulerianAngle.html',1,'DJI']]] + ['flag',['Flag',['../namespaceDJI.html#ac46082a5ea8919b47fb64283edc5bc18',1,'DJI']]], + ['flight',['Flight',['../classDJI_1_1onboardSDK_1_1Flight.html#a32306fffa274c6a34d90481cfb51da37',1,'DJI::onboardSDK::Flight']]], + ['flight',['Flight',['../classDJI_1_1onboardSDK_1_1Flight.html',1,'DJI::onboardSDK']]], + ['flightdata',['FlightData',['../structDJI_1_1onboardSDK_1_1FlightData.html',1,'DJI::onboardSDK']]], + ['follow',['Follow',['../classDJI_1_1onboardSDK_1_1Follow.html',1,'DJI::onboardSDK']]], + ['followdata',['FollowData',['../structDJI_1_1onboardSDK_1_1FollowData.html',1,'DJI::onboardSDK']]], + ['followtarget',['FollowTarget',['../structDJI_1_1onboardSDK_1_1FollowTarget.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_6.js b/dji_sdk_doc/doxygen/html/search/all_6.js index 3a7aeea5..a0bb227e 100644 --- a/dji_sdk_doc/doxygen/html/search/all_6.js +++ b/dji_sdk_doc/doxygen/html/search/all_6.js @@ -1,9 +1,29 @@ var searchData= [ - ['flight',['Flight',['../classDJI_1_1onboardSDK_1_1Flight.html',1,'DJI::onboardSDK']]], - ['flight',['Flight',['../classDJI_1_1onboardSDK_1_1Flight.html#a32306fffa274c6a34d90481cfb51da37',1,'DJI::onboardSDK::Flight']]], - ['flightdata',['FlightData',['../structDJI_1_1onboardSDK_1_1FlightData.html',1,'DJI::onboardSDK']]], - ['follow',['Follow',['../classDJI_1_1onboardSDK_1_1Follow.html',1,'DJI::onboardSDK']]], - ['followdata',['FollowData',['../structDJI_1_1onboardSDK_1_1FollowData.html',1,'DJI::onboardSDK']]], - ['followtarget',['FollowTarget',['../structDJI_1_1onboardSDK_1_1FollowTarget.html',1,'DJI::onboardSDK']]] + ['getacceleration',['getAcceleration',['../classDJI_1_1onboardSDK_1_1Flight.html#a468a431f738f794776f19170735a1637',1,'DJI::onboardSDK::Flight']]], + ['getaccountdata',['getAccountData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ae35f58e3a1293bc5615502055e94864a',1,'DJI::onboardSDK::CoreAPI']]], + ['getapi',['getApi',['../classDJI_1_1onboardSDK_1_1Camera.html#a3b6073643c2afe2c5502789f0fb74b70',1,'DJI::onboardSDK::Camera::getApi()'],['../classDJI_1_1onboardSDK_1_1Flight.html#a26f4cea3ae5a5bae1c63a67a4db24c2f',1,'DJI::onboardSDK::Flight::getApi()']]], + ['getbatterycapacity',['getBatteryCapacity',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#accb169d18e0ce644b0adf7284483cc41',1,'DJI::onboardSDK::CoreAPI']]], + ['getbroadcastdata',['getBroadcastData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a6e28d9d1bf933ee5ccfab6ec8891e16e',1,'DJI::onboardSDK::CoreAPI']]], + ['getdriver',['getDriver',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab06228e965457f85ac8eebc7669a09ef',1,'DJI::onboardSDK::CoreAPI']]], + ['getdroneversion',['getDroneVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ad0af34b1556ba02f25daeaf0e91d61b3',1,'DJI::onboardSDK::CoreAPI']]], + ['getfilter',['getFilter',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab7fa0d20a6e4bf39a43a1c8a4841667f',1,'DJI::onboardSDK::CoreAPI']]], + ['getflightstatus',['getFlightStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a83775b0cee8ef84d454ce6025edc1b62',1,'DJI::onboardSDK::CoreAPI']]], + ['gethotpointdata',['getHotPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a021fc52fda6637f3624ae14e1a96dc28',1,'DJI::onboardSDK::CoreAPI']]], + ['getmagnet',['getMagnet',['../classDJI_1_1onboardSDK_1_1Flight.html#a23fbea760546876fbd6b6af269deb1d1',1,'DJI::onboardSDK::Flight']]], + ['getquaternion',['getQuaternion',['../classDJI_1_1onboardSDK_1_1Flight.html#a63fcbf96eb69c5ffe7c1cfae237ec5de',1,'DJI::onboardSDK::Flight']]], + ['getrcdata',['getRCData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#ab2ff6d77cdc0da443c5ae27736c06501',1,'DJI::onboardSDK::VirtualRC']]], + ['getsdkversion',['getSDKVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f',1,'DJI::onboardSDK::CoreAPI']]], + ['gettime',['getTime',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af90c4551b82a3926d9ed5316b4084bb3',1,'DJI::onboardSDK::CoreAPI']]], + ['getvrcdata',['getVRCData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#adde3376c294c532e5fbea7ec81bef009',1,'DJI::onboardSDK::VirtualRC']]], + ['getwaypointdata',['getWayPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab5aa9af0ebe66a85ef24630284a1699d',1,'DJI::onboardSDK::CoreAPI']]], + ['getyawrate',['getYawRate',['../classDJI_1_1onboardSDK_1_1Flight.html#a097f8e5f55b1de4bc62754b061221bd5',1,'DJI::onboardSDK::Flight']]], + ['gimbalangledata',['GimbalAngleData',['../structDJI_1_1onboardSDK_1_1GimbalAngleData.html',1,'DJI::onboardSDK']]], + ['gimbaldata',['GimbalData',['../structDJI_1_1onboardSDK_1_1GimbalData.html',1,'DJI::onboardSDK']]], + ['gimbalspeeddata',['GimbalSpeedData',['../structDJI_1_1onboardSDK_1_1GimbalSpeedData.html',1,'DJI::onboardSDK']]], + ['gpsdata',['GPSData',['../structDJI_1_1onboardSDK_1_1GPSData.html',1,'DJI::onboardSDK']]], + ['gpsdata',['GPSData',['../DJI__Type_8h.html#ad6db26bb74dcd881f93c0031bae5e914',1,'DJI::onboardSDK']]], + ['gpspositiondata',['GPSPositionData',['../structDJI_1_1onboardSDK_1_1GPSPositionData.html',1,'DJI::onboardSDK']]], + ['gpspositiondata',['GPSPositionData',['../DJI__Type_8h.html#a4cf179a160f63b28aa3d622aa3f73fb2',1,'DJI::onboardSDK']]], + ['gspushdata',['GSPushData',['../structDJI_1_1onboardSDK_1_1GSPushData.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_7.js b/dji_sdk_doc/doxygen/html/search/all_7.js index f124ad39..736a4b42 100644 --- a/dji_sdk_doc/doxygen/html/search/all_7.js +++ b/dji_sdk_doc/doxygen/html/search/all_7.js @@ -1,32 +1,10 @@ var searchData= [ - ['getacceleration',['getAcceleration',['../classDJI_1_1onboardSDK_1_1Flight.html#a468a431f738f794776f19170735a1637',1,'DJI::onboardSDK::Flight']]], - ['getaccountdata',['getAccountData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ae35f58e3a1293bc5615502055e94864a',1,'DJI::onboardSDK::CoreAPI']]], - ['getapi',['getApi',['../classDJI_1_1onboardSDK_1_1Camera.html#a3b6073643c2afe2c5502789f0fb74b70',1,'DJI::onboardSDK::Camera::getApi()'],['../classDJI_1_1onboardSDK_1_1Flight.html#a26f4cea3ae5a5bae1c63a67a4db24c2f',1,'DJI::onboardSDK::Flight::getApi()']]], - ['getbatterycapacity',['getBatteryCapacity',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#accb169d18e0ce644b0adf7284483cc41',1,'DJI::onboardSDK::CoreAPI']]], - ['getbroadcastdata',['getBroadcastData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a6e28d9d1bf933ee5ccfab6ec8891e16e',1,'DJI::onboardSDK::CoreAPI']]], - ['getdriver',['getDriver',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab06228e965457f85ac8eebc7669a09ef',1,'DJI::onboardSDK::CoreAPI']]], - ['getdroneversion',['getDroneVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ad0af34b1556ba02f25daeaf0e91d61b3',1,'DJI::onboardSDK::CoreAPI::getDroneVersion(CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a94346c03fc72f0d9ca8a8709dad67f91',1,'DJI::onboardSDK::CoreAPI::getDroneVersion(int timeout)']]], - ['getfilter',['getFilter',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab7fa0d20a6e4bf39a43a1c8a4841667f',1,'DJI::onboardSDK::CoreAPI']]], - ['getflightstatus',['getFlightStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a83775b0cee8ef84d454ce6025edc1b62',1,'DJI::onboardSDK::CoreAPI']]], - ['gethotpointdata',['getHotPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a021fc52fda6637f3624ae14e1a96dc28',1,'DJI::onboardSDK::CoreAPI']]], - ['getmagnet',['getMagnet',['../classDJI_1_1onboardSDK_1_1Flight.html#a23fbea760546876fbd6b6af269deb1d1',1,'DJI::onboardSDK::Flight']]], - ['getobtaincontrolmobilecmd',['getObtainControlMobileCMD',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ad8fb88ea4af11dbec0e08dcff1be1709',1,'DJI::onboardSDK::CoreAPI']]], - ['getquaternion',['getQuaternion',['../classDJI_1_1onboardSDK_1_1Flight.html#a63fcbf96eb69c5ffe7c1cfae237ec5de',1,'DJI::onboardSDK::Flight']]], - ['getrcdata',['getRCData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#ab2ff6d77cdc0da443c5ae27736c06501',1,'DJI::onboardSDK::VirtualRC']]], - ['getsdkversion',['getSDKVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f',1,'DJI::onboardSDK::CoreAPI']]], - ['gettime',['getTime',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af90c4551b82a3926d9ed5316b4084bb3',1,'DJI::onboardSDK::CoreAPI']]], - ['getvrcdata',['getVRCData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#adde3376c294c532e5fbea7ec81bef009',1,'DJI::onboardSDK::VirtualRC']]], - ['getwaypointdata',['getWayPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab5aa9af0ebe66a85ef24630284a1699d',1,'DJI::onboardSDK::CoreAPI']]], - ['getyawrate',['getYawRate',['../classDJI_1_1onboardSDK_1_1Flight.html#a097f8e5f55b1de4bc62754b061221bd5',1,'DJI::onboardSDK::Flight']]], - ['gimbalangledata',['GimbalAngleData',['../DJI__Type_8h.html#a5dc007d5d982d79aed8091829a3efea3',1,'DJI::onboardSDK']]], - ['gimbalangledata',['GimbalAngleData',['../structDJI_1_1onboardSDK_1_1GimbalAngleData.html',1,'DJI::onboardSDK']]], - ['gimbaldata',['GimbalData',['../structDJI_1_1onboardSDK_1_1GimbalData.html',1,'DJI::onboardSDK']]], - ['gimbalspeeddata',['GimbalSpeedData',['../structDJI_1_1onboardSDK_1_1GimbalSpeedData.html',1,'DJI::onboardSDK']]], - ['gpsdata',['GPSData',['../DJI__Type_8h.html#ad6db26bb74dcd881f93c0031bae5e914',1,'DJI::onboardSDK']]], - ['gpsdata',['GPSData',['../structDJI_1_1onboardSDK_1_1GPSData.html',1,'DJI::onboardSDK']]], - ['gpspositiondata',['GPSPositionData',['../structDJI_1_1onboardSDK_1_1GPSPositionData.html',1,'DJI::onboardSDK']]], - ['gpspositiondata',['GPSPositionData',['../DJI__Type_8h.html#a4cf179a160f63b28aa3d622aa3f73fb2',1,'DJI::onboardSDK']]], - ['gspushdata',['GSPushData',['../structDJI_1_1onboardSDK_1_1GSPushData.html',1,'DJI::onboardSDK']]], - ['gspushdata',['GSPushData',['../DJI__Mission_8h.html#a41d91cb318a3e33fd043da65ae130401',1,'DJI::onboardSDK']]] + ['harddriver',['HardDriver',['../classDJI_1_1onboardSDK_1_1HardDriver.html',1,'DJI::onboardSDK']]], + ['header',['Header',['../structDJI_1_1onboardSDK_1_1Header.html',1,'DJI::onboardSDK']]], + ['height',['height',['../structDJI_1_1onboardSDK_1_1PositionData.html#a4bf7872a54102ef77715f91cbec7a4f6',1,'DJI::onboardSDK::PositionData']]], + ['hmsl',['Hmsl',['../structDJI_1_1onboardSDK_1_1RTKData.html#a52904c80b42d4dca673b750fa0a2dfd8',1,'DJI::onboardSDK::RTKData::Hmsl()'],['../structDJI_1_1onboardSDK_1_1GPSData.html#ac36d3f868cde3d09b8baec73ab453b06',1,'DJI::onboardSDK::GPSData::Hmsl()']]], + ['hotpoint',['HotPoint',['../classDJI_1_1onboardSDK_1_1HotPoint.html',1,'DJI::onboardSDK']]], + ['hotpointackdata',['HotPointACKData',['../structDJI_1_1onboardSDK_1_1HotPointACKData.html',1,'DJI::onboardSDK']]], + ['hotpointdata',['HotPointData',['../structDJI_1_1onboardSDK_1_1HotPointData.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_8.js b/dji_sdk_doc/doxygen/html/search/all_8.js index 5c29fbbe..8cca925b 100644 --- a/dji_sdk_doc/doxygen/html/search/all_8.js +++ b/dji_sdk_doc/doxygen/html/search/all_8.js @@ -1,14 +1,4 @@ var searchData= [ - ['harddriver',['HardDriver',['../classDJI_1_1onboardSDK_1_1HardDriver.html',1,'DJI::onboardSDK']]], - ['header',['Header',['../structDJI_1_1onboardSDK_1_1Header.html',1,'DJI::onboardSDK']]], - ['header',['Header',['../DJI__Type_8h.html#a14ecda64c265b3dd655ce82b06ce8456',1,'DJI::onboardSDK']]], - ['height',['height',['../structDJI_1_1onboardSDK_1_1PositionData.html#a4bf7872a54102ef77715f91cbec7a4f6',1,'DJI::onboardSDK::PositionData']]], - ['hmsl',['Hmsl',['../structDJI_1_1onboardSDK_1_1RTKData.html#a52904c80b42d4dca673b750fa0a2dfd8',1,'DJI::onboardSDK::RTKData::Hmsl()'],['../structDJI_1_1onboardSDK_1_1GPSData.html#ac36d3f868cde3d09b8baec73ab453b06',1,'DJI::onboardSDK::GPSData::Hmsl()']]], - ['hotpoint',['HotPoint',['../classDJI_1_1onboardSDK_1_1HotPoint.html',1,'DJI::onboardSDK']]], - ['hotpointackdata',['HotPointACKData',['../structDJI_1_1onboardSDK_1_1HotPointACKData.html',1,'DJI::onboardSDK']]], - ['hotpointdata',['HotPointData',['../DJI__Type_8h.html#a1448a5d001a91235c5e08145d7f6a6a4',1,'DJI::onboardSDK']]], - ['hotpointdata',['HotPointData',['../structDJI_1_1onboardSDK_1_1HotPointData.html',1,'DJI::onboardSDK']]], - ['hotpointreadack',['HotPointReadACK',['../structDJI_1_1onboardSDK_1_1HotPointReadACK.html',1,'DJI::onboardSDK']]], - ['hotpointstartack',['HotPointStartACK',['../structDJI_1_1onboardSDK_1_1HotPointStartACK.html',1,'DJI::onboardSDK']]] + ['init',['init',['../classDJI_1_1onboardSDK_1_1HardDriver.html#a4bd7d6bcbb708b905e6296f3d1ac9eab',1,'DJI::onboardSDK::HardDriver']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_9.js b/dji_sdk_doc/doxygen/html/search/all_9.js index 8cca925b..da874a3f 100644 --- a/dji_sdk_doc/doxygen/html/search/all_9.js +++ b/dji_sdk_doc/doxygen/html/search/all_9.js @@ -1,4 +1,4 @@ var searchData= [ - ['init',['init',['../classDJI_1_1onboardSDK_1_1HardDriver.html#a4bd7d6bcbb708b905e6296f3d1ac9eab',1,'DJI::onboardSDK::HardDriver']]] + ['longitude',['longitude',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#a5829cb39abac8750ab507796e50d1639',1,'DJI::onboardSDK::WayPointInitData']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_a.js b/dji_sdk_doc/doxygen/html/search/all_a.js index da874a3f..a90147bd 100644 --- a/dji_sdk_doc/doxygen/html/search/all_a.js +++ b/dji_sdk_doc/doxygen/html/search/all_a.js @@ -1,4 +1,18 @@ var searchData= [ - ['longitude',['longitude',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#a5829cb39abac8750ab507796e50d1639',1,'DJI::onboardSDK::WayPointInitData']]] + ['mag',['mag',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a1927a962764da10fd698fdf629126956',1,'DJI::onboardSDK::BroadcastData']]], + ['magdata',['MagData',['../DJI__Type_8h.html#a1a43778cf092a88a6c2b938e651c1b62',1,'DJI::onboardSDK']]], + ['magdata',['MagData',['../structDJI_1_1onboardSDK_1_1MagData.html',1,'DJI::onboardSDK']]], + ['magnetdata',['MagnetData',['../structDJI_1_1onboardSDK_1_1MagnetData.html',1,'DJI::onboardSDK']]], + ['magnetdata',['MagnetData',['../DJI__Type_8h.html#aea6e13bf4b08fb7178bc0eb258fd0e4e',1,'DJI::onboardSDK']]], + ['make_5fversion',['MAKE_VERSION',['../DJI__Version_8h.html#a45b1a7ff62105593af4bf5f37b9010f6',1,'DJI_Version.h']]], + ['measure',['Measure',['../namespaceDJI.html#a33a0392b19136429c35297ee20819e73',1,'DJI']]], + ['measure',['Measure',['../structDJI_1_1Measure.html',1,'DJI']]], + ['measurement',['Measurement',['../structDJI_1_1Measurement.html',1,'DJI']]], + ['measurement',['Measurement',['../namespaceDJI.html#ab8295509ea10f45b68c55ae54614851f',1,'DJI']]], + ['missionackmap',['MissionACKMap',['../structDJI_1_1onboardSDK_1_1MissionACKMap.html',1,'DJI::onboardSDK']]], + ['mmu_5ftab',['MMU_Tab',['../structDJI_1_1onboardSDK_1_1MMU__Tab.html',1,'DJI::onboardSDK']]], + ['mmu_5ftab',['MMU_Tab',['../DJI__Type_8h.html#a112002746462d1469ec7dbc562da0418',1,'DJI::onboardSDK']]], + ['mode',['Mode',['../classDJI_1_1onboardSDK_1_1Flight.html#af83429c89ed162261fe1ee105c009165',1,'DJI::onboardSDK::Flight::Mode()'],['../classDJI_1_1onboardSDK_1_1Follow.html#a275b6488621961b4d93ce9dad6c25aef',1,'DJI::onboardSDK::Follow::MODE()']]], + ['mode_5fsmart',['MODE_SMART',['../classDJI_1_1onboardSDK_1_1Follow.html#a275b6488621961b4d93ce9dad6c25aefaa6cd810b12736e39ad448d4d411bc954',1,'DJI::onboardSDK::Follow']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_b.js b/dji_sdk_doc/doxygen/html/search/all_b.js index 862ddfa0..f07e543f 100644 --- a/dji_sdk_doc/doxygen/html/search/all_b.js +++ b/dji_sdk_doc/doxygen/html/search/all_b.js @@ -1,20 +1,5 @@ var searchData= [ - ['mag',['mag',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a1927a962764da10fd698fdf629126956',1,'DJI::onboardSDK::BroadcastData']]], - ['magdata',['MagData',['../structDJI_1_1onboardSDK_1_1MagData.html',1,'DJI::onboardSDK']]], - ['magdata',['MagData',['../DJI__Type_8h.html#a1a43778cf092a88a6c2b938e651c1b62',1,'DJI::onboardSDK']]], - ['magnetdata',['MagnetData',['../structDJI_1_1onboardSDK_1_1MagnetData.html',1,'DJI::onboardSDK']]], - ['magnetdata',['MagnetData',['../DJI__Type_8h.html#aea6e13bf4b08fb7178bc0eb258fd0e4e',1,'DJI::onboardSDK']]], - ['make_5fversion',['MAKE_VERSION',['../DJI__Version_8h.html#a45b1a7ff62105593af4bf5f37b9010f6',1,'DJI_Version.h']]], - ['measure',['Measure',['../structDJI_1_1Measure.html',1,'DJI']]], - ['measure',['Measure',['../namespaceDJI.html#a33a0392b19136429c35297ee20819e73',1,'DJI']]], - ['measurement',['Measurement',['../namespaceDJI.html#ab8295509ea10f45b68c55ae54614851f',1,'DJI']]], - ['measurement',['Measurement',['../structDJI_1_1Measurement.html',1,'DJI']]], - ['missionack',['MissionACK',['../DJI__Type_8h.html#a57553a650086a257fa205069df5b8c84',1,'DJI::onboardSDK']]], - ['missionackmap',['MissionACKMap',['../structDJI_1_1onboardSDK_1_1MissionACKMap.html',1,'DJI::onboardSDK']]], - ['missionackunion',['MissionACKUnion',['../unionDJI_1_1onboardSDK_1_1MissionACKUnion.html',1,'DJI::onboardSDK']]], - ['mmu_5ftab',['MMU_Tab',['../structDJI_1_1onboardSDK_1_1MMU__Tab.html',1,'DJI::onboardSDK']]], - ['mmu_5ftab',['MMU_Tab',['../DJI__Type_8h.html#a112002746462d1469ec7dbc562da0418',1,'DJI::onboardSDK']]], - ['mode',['Mode',['../classDJI_1_1onboardSDK_1_1Flight.html#af83429c89ed162261fe1ee105c009165',1,'DJI::onboardSDK::Flight::Mode()'],['../classDJI_1_1onboardSDK_1_1Follow.html#a275b6488621961b4d93ce9dad6c25aef',1,'DJI::onboardSDK::Follow::MODE()']]], - ['mode_5fsmart',['MODE_SMART',['../classDJI_1_1onboardSDK_1_1Follow.html#a275b6488621961b4d93ce9dad6c25aefaa6cd810b12736e39ad448d4d411bc954',1,'DJI::onboardSDK::Follow']]] + ['name',['NAME',['../DJI__Type_8h.html#a14111ac8f43949172b152e50dc720aba',1,'DJI_Type.h']]], + ['neutralvrcsticks',['neutralVRCSticks',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a5a7974a1d812e1ed38b8bb9a092bebfc',1,'DJI::onboardSDK::VirtualRC']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_c.js b/dji_sdk_doc/doxygen/html/search/all_c.js index 593b57f9..2380ee96 100644 --- a/dji_sdk_doc/doxygen/html/search/all_c.js +++ b/dji_sdk_doc/doxygen/html/search/all_c.js @@ -1,6 +1,7 @@ var searchData= [ - ['name',['NAME',['../DJI__Type_8h.html#a14111ac8f43949172b152e50dc720aba',1,'DJI_Type.h']]], - ['neutralvrcsticks',['neutralVRCSticks',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a5a7974a1d812e1ed38b8bb9a092bebfc',1,'DJI::onboardSDK::VirtualRC']]], - ['notifycaller',['notifyCaller',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a8295bc2e7fc96c5c1742083a757f9ad6',1,'DJI::onboardSDK::CoreAPI']]] + ['passdata',['passData',['../DJI__App_8cpp.html#a60f2a66b609bddc01c60372127d609c1',1,'DJI_App.cpp']]], + ['pause',['pause',['../classDJI_1_1onboardSDK_1_1Follow.html#a014e135f35a4646303335c1922ef0b2b',1,'DJI::onboardSDK::Follow::pause()'],['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae8554465c36efe306ac7159e9c4fb2d0',1,'DJI::onboardSDK::WayPoint::pause()']]], + ['positiondata',['PositionData',['../structDJI_1_1onboardSDK_1_1PositionData.html',1,'DJI::onboardSDK']]], + ['ptr_5faes256_5fcodec',['ptr_aes256_codec',['../DJI__Codec_8cpp.html#a41cf66b27f6524ea298df0f0e25445b6',1,'DJI_Codec.cpp']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_d.js b/dji_sdk_doc/doxygen/html/search/all_d.js index 403a87b0..e62b455b 100644 --- a/dji_sdk_doc/doxygen/html/search/all_d.js +++ b/dji_sdk_doc/doxygen/html/search/all_d.js @@ -1,8 +1,4 @@ var searchData= [ - ['parsefrommobilecallback',['parseFromMobileCallback',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#afdf9c3d84a6b4445edacff7e2e29c219',1,'DJI::onboardSDK::CoreAPI']]], - ['passdata',['passData',['../DJI__App_8cpp.html#a60f2a66b609bddc01c60372127d609c1',1,'DJI_App.cpp']]], - ['pause',['pause',['../classDJI_1_1onboardSDK_1_1Follow.html#a014e135f35a4646303335c1922ef0b2b',1,'DJI::onboardSDK::Follow::pause()'],['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae8554465c36efe306ac7159e9c4fb2d0',1,'DJI::onboardSDK::WayPoint::pause()']]], - ['positiondata',['PositionData',['../structDJI_1_1onboardSDK_1_1PositionData.html',1,'DJI::onboardSDK']]], - ['ptr_5faes256_5fcodec',['ptr_aes256_codec',['../DJI__Codec_8cpp.html#a41cf66b27f6524ea298df0f0e25445b6',1,'DJI_Codec.cpp']]] + ['quaterniondata',['QuaternionData',['../structDJI_1_1onboardSDK_1_1QuaternionData.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_e.js b/dji_sdk_doc/doxygen/html/search/all_e.js index e62b455b..ea5c4e08 100644 --- a/dji_sdk_doc/doxygen/html/search/all_e.js +++ b/dji_sdk_doc/doxygen/html/search/all_e.js @@ -1,4 +1,18 @@ var searchData= [ - ['quaterniondata',['QuaternionData',['../structDJI_1_1onboardSDK_1_1QuaternionData.html',1,'DJI::onboardSDK']]] + ['radiodata',['RadioData',['../structDJI_1_1onboardSDK_1_1RadioData.html',1,'DJI::onboardSDK']]], + ['radiodata',['RadioData',['../DJI__Type_8h.html#a7036f4c0336e21dfd1e56471fd311354',1,'DJI::onboardSDK']]], + ['rc',['rc',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a9f939c4413767acefca0c2b162eecf8a',1,'DJI::onboardSDK::BroadcastData']]], + ['rcdata',['RCData',['../structDJI_1_1onboardSDK_1_1RCData.html',1,'DJI::onboardSDK']]], + ['rcdata',['RCData',['../DJI__Type_8h.html#a5643d95a442bf936449b7c191e95c7cf',1,'DJI::onboardSDK']]], + ['readack',['ReadACK',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1ReadACK.html',1,'DJI::onboardSDK::HotPoint']]], + ['readidlevelocity',['readIdleVelocity',['../classDJI_1_1onboardSDK_1_1WayPoint.html#a3393f8aa0e40460ca897e137f54aa403',1,'DJI::onboardSDK::WayPoint']]], + ['readindexdata',['readIndexData',['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae08206461380c81a6aa6c13525ff0020',1,'DJI::onboardSDK::WayPoint']]], + ['req_5fid_5ft',['req_id_t',['../structreq__id__t.html',1,'']]], + ['resetdata',['resetData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a9c5a799eb6b658be4e18ac24c16a1d2d',1,'DJI::onboardSDK::VirtualRC']]], + ['reversed0',['reversed0',['../structDJI_1_1onboardSDK_1_1Header.html#af3ce36bcc06b7a8fb9f0577c2c594b76',1,'DJI::onboardSDK::Header']]], + ['reversed1',['reversed1',['../structDJI_1_1onboardSDK_1_1Header.html#a8795aa82bbd107a742721f6983aa8cba',1,'DJI::onboardSDK::Header']]], + ['roll',['roll',['../structDJI_1_1onboardSDK_1_1VirtualRCData.html#a943d5f3b60294d2909dcc8d6da51dca8',1,'DJI::onboardSDK::VirtualRCData']]], + ['rtkdata',['RTKData',['../structDJI_1_1onboardSDK_1_1RTKData.html',1,'DJI::onboardSDK']]], + ['rtkdata',['RTKData',['../DJI__Type_8h.html#ab1bfe50ba801d7466eb0f5c3c09a5474',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/all_f.js b/dji_sdk_doc/doxygen/html/search/all_f.js index 6e281d3c..6cfa91d2 100644 --- a/dji_sdk_doc/doxygen/html/search/all_f.js +++ b/dji_sdk_doc/doxygen/html/search/all_f.js @@ -1,17 +1,29 @@ var searchData= [ - ['radiodata',['RadioData',['../structDJI_1_1onboardSDK_1_1RadioData.html',1,'DJI::onboardSDK']]], - ['radiodata',['RadioData',['../DJI__Type_8h.html#a7036f4c0336e21dfd1e56471fd311354',1,'DJI::onboardSDK']]], - ['rc',['rc',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a9f939c4413767acefca0c2b162eecf8a',1,'DJI::onboardSDK::BroadcastData']]], - ['rcdata',['RCData',['../structDJI_1_1onboardSDK_1_1RCData.html',1,'DJI::onboardSDK']]], - ['rcdata',['RCData',['../DJI__Type_8h.html#a5643d95a442bf936449b7c191e95c7cf',1,'DJI::onboardSDK']]], - ['readidlevelocity',['readIdleVelocity',['../classDJI_1_1onboardSDK_1_1WayPoint.html#a3393f8aa0e40460ca897e137f54aa403',1,'DJI::onboardSDK::WayPoint']]], - ['readindexdata',['readIndexData',['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae08206461380c81a6aa6c13525ff0020',1,'DJI::onboardSDK::WayPoint']]], - ['req_5fid_5ft',['req_id_t',['../structreq__id__t.html',1,'']]], - ['resetdata',['resetData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a9c5a799eb6b658be4e18ac24c16a1d2d',1,'DJI::onboardSDK::VirtualRC']]], - ['reversed0',['reversed0',['../structDJI_1_1onboardSDK_1_1Header.html#af3ce36bcc06b7a8fb9f0577c2c594b76',1,'DJI::onboardSDK::Header']]], - ['reversed1',['reversed1',['../structDJI_1_1onboardSDK_1_1Header.html#a8795aa82bbd107a742721f6983aa8cba',1,'DJI::onboardSDK::Header']]], - ['roll',['roll',['../structDJI_1_1onboardSDK_1_1VirtualRCData.html#a943d5f3b60294d2909dcc8d6da51dca8',1,'DJI::onboardSDK::VirtualRCData']]], - ['rtkdata',['RTKData',['../structDJI_1_1onboardSDK_1_1RTKData.html',1,'DJI::onboardSDK']]], - ['rtkdata',['RTKData',['../DJI__Type_8h.html#ab1bfe50ba801d7466eb0f5c3c09a5474',1,'DJI::onboardSDK']]] + ['sdkfilter',['SDKFilter',['../structDJI_1_1onboardSDK_1_1SDKFilter.html',1,'DJI::onboardSDK']]], + ['sdkfilter',['SDKFilter',['../DJI__Type_8h.html#aac87b726305048671bd3c874dfca5e7e',1,'DJI::onboardSDK']]], + ['send',['send',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#accec1bc503740cc4540142a2d8c403db',1,'DJI::onboardSDK::CoreAPI::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)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a34f54e10c7faec4ac0f921cdfa6baf67',1,'DJI::onboardSDK::CoreAPI::send(unsigned char session_mode, bool is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, size_t len, int timeout=0, int retry_time=1, CallBack ack_handler=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ae541770460eb82571214aa7aa5370a21',1,'DJI::onboardSDK::CoreAPI::send(Command *parameter)']]], + ['senddata',['sendData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a72a474c78f12b733244eec8a68d73f5b',1,'DJI::onboardSDK::VirtualRC::sendData(VirtualRCData Data)'],['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a1b6b198870cd24af401dcf75b2493730',1,'DJI::onboardSDK::VirtualRC::sendData()']]], + ['sendpoll',['sendPoll',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5373ef1d252b233a022cc08e7b6df96c',1,'DJI::onboardSDK::CoreAPI']]], + ['sendsafemodedata',['sendSafeModeData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a26bb84b709df68859b7caecefa190849',1,'DJI::onboardSDK::VirtualRC']]], + ['sense_5fmid',['SENSE_MID',['../classDJI_1_1onboardSDK_1_1Follow.html#a963f944b2aaf7b0719a29ee221a56d51a1173b26e1704b80b43232ae269e5701f',1,'DJI::onboardSDK::Follow']]], + ['sensitivity',['SENSITIVITY',['../classDJI_1_1onboardSDK_1_1Follow.html#a963f944b2aaf7b0719a29ee221a56d51',1,'DJI::onboardSDK::Follow']]], + ['setaccountdata',['setAccountData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a76c8fa26fdc252af20b013928ec03ad6',1,'DJI::onboardSDK::CoreAPI']]], + ['setactivation',['setActivation',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a2a8f3380779cf660be316aa45470bb99',1,'DJI::onboardSDK::CoreAPI']]], + ['setbroadcastfreq',['setBroadcastFreq',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5490da3ad6bf7ea37f89783a4a75689a',1,'DJI::onboardSDK::CoreAPI']]], + ['setcamera',['setCamera',['../classDJI_1_1onboardSDK_1_1Camera.html#a5f5a5e955ca32578a55635cdc6351efb',1,'DJI::onboardSDK::Camera']]], + ['setcontrol',['setControl',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a561e25be8d98214360affe7907b52f63',1,'DJI::onboardSDK::VirtualRC']]], + ['setdata',['setData',['../classDJI_1_1onboardSDK_1_1Follow.html#adcdf0d6d3f33a6cb1f7ee5d65f064d7f',1,'DJI::onboardSDK::Follow::setData()'],['../classDJI_1_1onboardSDK_1_1HotPoint.html#a71572a01dfd5fe36fed492114d0652bc',1,'DJI::onboardSDK::HotPoint::setData()']]], + ['setdriver',['setDriver',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af11e76e300013a8d9a229019eaf01ab8',1,'DJI::onboardSDK::CoreAPI']]], + ['setfollowdata',['setFollowData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aee573550da2469e7992097540550faef',1,'DJI::onboardSDK::CoreAPI']]], + ['sethotpointdata',['setHotPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aeec7ae9063e509bbd6bf6039ead9be00',1,'DJI::onboardSDK::CoreAPI']]], + ['setinfo',['setInfo',['../classDJI_1_1onboardSDK_1_1WayPoint.html#a697de2d4ae1666c9504755c3307324fb',1,'DJI::onboardSDK::WayPoint']]], + ['setmovementcontrol',['setMovementControl',['../classDJI_1_1onboardSDK_1_1Flight.html#a53ae6a258cac9f81337e6cd1488d9347',1,'DJI::onboardSDK::Flight']]], + ['setversion',['setVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aadeecafaad54eeabdfd6212d2b64ea3d',1,'DJI::onboardSDK::CoreAPI']]], + ['setwaypointdata',['setWayPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac8cad19f2b08d929011ad923cf87f45f',1,'DJI::onboardSDK::CoreAPI']]], + ['smoothmode',['SmoothMode',['../classDJI_1_1onboardSDK_1_1Flight.html#a2ba6b590d35f3a2d9c8fb737b5150454',1,'DJI::onboardSDK::Flight']]], + ['spacevector',['SpaceVector',['../namespaceDJI.html#ad1dc49f750d830612593ed9253e4502a',1,'DJI']]], + ['spacevector',['SpaceVector',['../structDJI_1_1SpaceVector.html',1,'DJI']]], + ['start',['start',['../classDJI_1_1onboardSDK_1_1HotPoint.html#a92446411eb21eea88736280fa6c05bee',1,'DJI::onboardSDK::HotPoint']]], + ['startack',['StartACK',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1StartACK.html',1,'DJI::onboardSDK::HotPoint']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/classes_0.js b/dji_sdk_doc/doxygen/html/search/classes_0.js index 79e6b8f3..104fffda 100644 --- a/dji_sdk_doc/doxygen/html/search/classes_0.js +++ b/dji_sdk_doc/doxygen/html/search/classes_0.js @@ -2,5 +2,5 @@ var searchData= [ ['ack',['Ack',['../structDJI_1_1onboardSDK_1_1Ack.html',1,'DJI::onboardSDK']]], ['acksession',['ACKSession',['../structDJI_1_1onboardSDK_1_1ACKSession.html',1,'DJI::onboardSDK']]], - ['activatedata',['ActivateData',['../structDJI_1_1onboardSDK_1_1ActivateData.html',1,'DJI::onboardSDK']]] + ['activatedata',['ActivateData',['../structActivateData.html',1,'']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/classes_6.js b/dji_sdk_doc/doxygen/html/search/classes_6.js index 0517ddf2..e3bc6b1c 100644 --- a/dji_sdk_doc/doxygen/html/search/classes_6.js +++ b/dji_sdk_doc/doxygen/html/search/classes_6.js @@ -4,7 +4,5 @@ var searchData= ['header',['Header',['../structDJI_1_1onboardSDK_1_1Header.html',1,'DJI::onboardSDK']]], ['hotpoint',['HotPoint',['../classDJI_1_1onboardSDK_1_1HotPoint.html',1,'DJI::onboardSDK']]], ['hotpointackdata',['HotPointACKData',['../structDJI_1_1onboardSDK_1_1HotPointACKData.html',1,'DJI::onboardSDK']]], - ['hotpointdata',['HotPointData',['../structDJI_1_1onboardSDK_1_1HotPointData.html',1,'DJI::onboardSDK']]], - ['hotpointreadack',['HotPointReadACK',['../structDJI_1_1onboardSDK_1_1HotPointReadACK.html',1,'DJI::onboardSDK']]], - ['hotpointstartack',['HotPointStartACK',['../structDJI_1_1onboardSDK_1_1HotPointStartACK.html',1,'DJI::onboardSDK']]] + ['hotpointdata',['HotPointData',['../structDJI_1_1onboardSDK_1_1HotPointData.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/classes_7.js b/dji_sdk_doc/doxygen/html/search/classes_7.js index 3f4667b8..f94013a4 100644 --- a/dji_sdk_doc/doxygen/html/search/classes_7.js +++ b/dji_sdk_doc/doxygen/html/search/classes_7.js @@ -5,6 +5,5 @@ var searchData= ['measure',['Measure',['../structDJI_1_1Measure.html',1,'DJI']]], ['measurement',['Measurement',['../structDJI_1_1Measurement.html',1,'DJI']]], ['missionackmap',['MissionACKMap',['../structDJI_1_1onboardSDK_1_1MissionACKMap.html',1,'DJI::onboardSDK']]], - ['missionackunion',['MissionACKUnion',['../unionDJI_1_1onboardSDK_1_1MissionACKUnion.html',1,'DJI::onboardSDK']]], ['mmu_5ftab',['MMU_Tab',['../structDJI_1_1onboardSDK_1_1MMU__Tab.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/classes_a.js b/dji_sdk_doc/doxygen/html/search/classes_a.js index de349f56..ffb4e0b1 100644 --- a/dji_sdk_doc/doxygen/html/search/classes_a.js +++ b/dji_sdk_doc/doxygen/html/search/classes_a.js @@ -2,6 +2,7 @@ var searchData= [ ['radiodata',['RadioData',['../structDJI_1_1onboardSDK_1_1RadioData.html',1,'DJI::onboardSDK']]], ['rcdata',['RCData',['../structDJI_1_1onboardSDK_1_1RCData.html',1,'DJI::onboardSDK']]], + ['readack',['ReadACK',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1ReadACK.html',1,'DJI::onboardSDK::HotPoint']]], ['req_5fid_5ft',['req_id_t',['../structreq__id__t.html',1,'']]], ['rtkdata',['RTKData',['../structDJI_1_1onboardSDK_1_1RTKData.html',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/classes_b.js b/dji_sdk_doc/doxygen/html/search/classes_b.js index 95b02ede..8bfd7aa8 100644 --- a/dji_sdk_doc/doxygen/html/search/classes_b.js +++ b/dji_sdk_doc/doxygen/html/search/classes_b.js @@ -1,5 +1,6 @@ var searchData= [ ['sdkfilter',['SDKFilter',['../structDJI_1_1onboardSDK_1_1SDKFilter.html',1,'DJI::onboardSDK']]], - ['spacevector',['SpaceVector',['../structDJI_1_1SpaceVector.html',1,'DJI']]] + ['spacevector',['SpaceVector',['../structDJI_1_1SpaceVector.html',1,'DJI']]], + ['startack',['StartACK',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1StartACK.html',1,'DJI::onboardSDK::HotPoint']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/classes_d.js b/dji_sdk_doc/doxygen/html/search/classes_d.js index e9b64725..c5142806 100644 --- a/dji_sdk_doc/doxygen/html/search/classes_d.js +++ b/dji_sdk_doc/doxygen/html/search/classes_d.js @@ -3,7 +3,7 @@ var searchData= ['vector3ddata',['Vector3dData',['../structDJI_1_1Vector3dData.html',1,'DJI']]], ['vector3fdata',['Vector3fData',['../structDJI_1_1onboardSDK_1_1Vector3fData.html',1,'DJI::onboardSDK']]], ['velocitydata',['VelocityData',['../structDJI_1_1onboardSDK_1_1VelocityData.html',1,'DJI::onboardSDK']]], - ['versiondata',['VersionData',['../structDJI_1_1onboardSDK_1_1VersionData.html',1,'DJI::onboardSDK']]], + ['versiondata',['VersionData',['../structVersionData.html',1,'']]], ['virtualrc',['VirtualRC',['../classDJI_1_1onboardSDK_1_1VirtualRC.html',1,'DJI::onboardSDK']]], ['virtualrcdata',['VirtualRCData',['../structDJI_1_1onboardSDK_1_1VirtualRCData.html',1,'DJI::onboardSDK']]], ['virtualrcsetting',['VirtualRCSetting',['../structDJI_1_1onboardSDK_1_1VirtualRCSetting.html',1,'DJI::onboardSDK']]] diff --git a/dji_sdk_doc/doxygen/html/search/defines_0.js b/dji_sdk_doc/doxygen/html/search/defines_0.js index 660e9976..fe29a21c 100644 --- a/dji_sdk_doc/doxygen/html/search/defines_0.js +++ b/dji_sdk_doc/doxygen/html/search/defines_0.js @@ -1,4 +1,5 @@ var searchData= [ - ['_5f_5funused',['__UNUSED',['../DJI__Type_8h.html#a6c30d490cd2302ff05d355f3ec844c1f',1,'DJI_Type.h']]] + ['api_5ferror_5fdata',['API_ERROR_DATA',['../DJI__Config_8h.html#a27a3f3004903b8fb75fb414b1068a1d6',1,'DJI_Config.h']]], + ['api_5flog',['API_LOG',['../DJI__Type_8h.html#a2c663cc30300205e6a25232ef72f25e3',1,'DJI_Type.h']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/defines_1.js b/dji_sdk_doc/doxygen/html/search/defines_1.js index fe29a21c..9b8dbad1 100644 --- a/dji_sdk_doc/doxygen/html/search/defines_1.js +++ b/dji_sdk_doc/doxygen/html/search/defines_1.js @@ -1,5 +1,4 @@ var searchData= [ - ['api_5ferror_5fdata',['API_ERROR_DATA',['../DJI__Config_8h.html#a27a3f3004903b8fb75fb414b1068a1d6',1,'DJI_Config.h']]], - ['api_5flog',['API_LOG',['../DJI__Type_8h.html#a2c663cc30300205e6a25232ef72f25e3',1,'DJI_Type.h']]] + ['make_5fversion',['MAKE_VERSION',['../DJI__Version_8h.html#a45b1a7ff62105593af4bf5f37b9010f6',1,'DJI_Version.h']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/defines_2.js b/dji_sdk_doc/doxygen/html/search/defines_2.js index 9b8dbad1..a6a3f145 100644 --- a/dji_sdk_doc/doxygen/html/search/defines_2.js +++ b/dji_sdk_doc/doxygen/html/search/defines_2.js @@ -1,4 +1,4 @@ var searchData= [ - ['make_5fversion',['MAKE_VERSION',['../DJI__Version_8h.html#a45b1a7ff62105593af4bf5f37b9010f6',1,'DJI_Version.h']]] + ['name',['NAME',['../DJI__Type_8h.html#a14111ac8f43949172b152e50dc720aba',1,'DJI_Type.h']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/defines_3.js b/dji_sdk_doc/doxygen/html/search/defines_3.js index a6a3f145..8ed92867 100644 --- a/dji_sdk_doc/doxygen/html/search/defines_3.js +++ b/dji_sdk_doc/doxygen/html/search/defines_3.js @@ -1,4 +1,4 @@ var searchData= [ - ['name',['NAME',['../DJI__Type_8h.html#a14111ac8f43949172b152e50dc720aba',1,'DJI_Type.h']]] + ['use_5fencrypt',['USE_ENCRYPT',['../DJI__Config_8h.html#ab711b1ed161a4ec825c22523cda3dc6d',1,'DJI_Config.h']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/defines_4.html b/dji_sdk_doc/doxygen/html/search/defines_4.html deleted file mode 100644 index c6864f75..00000000 --- a/dji_sdk_doc/doxygen/html/search/defines_4.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
                          -
                          Loading...
                          -
                          - -
                          Searching...
                          -
                          No Matches
                          - -
                          - - diff --git a/dji_sdk_doc/doxygen/html/search/defines_4.js b/dji_sdk_doc/doxygen/html/search/defines_4.js deleted file mode 100644 index 8ed92867..00000000 --- a/dji_sdk_doc/doxygen/html/search/defines_4.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['use_5fencrypt',['USE_ENCRYPT',['../DJI__Config_8h.html#ab711b1ed161a4ec825c22523cda3dc6d',1,'DJI_Config.h']]] -]; diff --git a/dji_sdk_doc/doxygen/html/search/enums_0.js b/dji_sdk_doc/doxygen/html/search/enums_0.js index 4cc26aaa..b7262b4e 100644 --- a/dji_sdk_doc/doxygen/html/search/enums_0.js +++ b/dji_sdk_doc/doxygen/html/search/enums_0.js @@ -1,4 +1,4 @@ var searchData= [ - ['ack_5ferror_5fcode',['ACK_ERROR_CODE',['../DJI__API_8h.html#ae9b83ce82c2006a3c98b5564354985c9',1,'DJI::onboardSDK']]] + ['ack_5fcommon_5fcode',['ACK_COMMON_CODE',['../DJI__API_8h.html#aec259c8a8cf384789e0726ecf0773cbd',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/files_0.js b/dji_sdk_doc/doxygen/html/search/files_0.js index 4f7ec9d7..ebd782ed 100644 --- a/dji_sdk_doc/doxygen/html/search/files_0.js +++ b/dji_sdk_doc/doxygen/html/search/files_0.js @@ -13,14 +13,13 @@ var searchData= ['dji_5fflight_2eh',['DJI_Flight.h',['../DJI__Flight_8h.html',1,'']]], ['dji_5ffollow_2ecpp',['DJI_Follow.cpp',['../DJI__Follow_8cpp.html',1,'']]], ['dji_5ffollow_2eh',['DJI_Follow.h',['../DJI__Follow_8h.html',1,'']]], - ['dji_5fharddriver_2ecpp',['DJI_HardDriver.cpp',['../DJI__HardDriver_8cpp.html',1,'']]], ['dji_5fharddriver_2eh',['DJI_HardDriver.h',['../DJI__HardDriver_8h.html',1,'']]], ['dji_5fhotpoint_2ecpp',['DJI_HotPoint.cpp',['../DJI__HotPoint_8cpp.html',1,'']]], + ['dji_5fhotpoint_2eh',['DJI_HotPoint.h',['../DJI__HotPoint_8h.html',1,'']]], ['dji_5flink_2ecpp',['DJI_Link.cpp',['../DJI__Link_8cpp.html',1,'']]], ['dji_5flink_2eh',['DJI_Link.h',['../DJI__Link_8h.html',1,'']]], ['dji_5fmemory_2ecpp',['DJI_Memory.cpp',['../DJI__Memory_8cpp.html',1,'']]], ['dji_5fmission_2ecpp',['DJI_Mission.cpp',['../DJI__Mission_8cpp.html',1,'']]], - ['dji_5fmission_2eh',['DJI_Mission.h',['../DJI__Mission_8h.html',1,'']]], ['dji_5ftype_2eh',['DJI_Type.h',['../DJI__Type_8h.html',1,'']]], ['dji_5fversion_2eh',['DJI_Version.h',['../DJI__Version_8h.html',1,'']]], ['dji_5fvirtualrc_2ecpp',['DJI_VirtualRC.cpp',['../DJI__VirtualRC_8cpp.html',1,'']]], diff --git a/dji_sdk_doc/doxygen/html/search/functions_0.js b/dji_sdk_doc/doxygen/html/search/functions_0.js index 2dd78883..db3eba94 100644 --- a/dji_sdk_doc/doxygen/html/search/functions_0.js +++ b/dji_sdk_doc/doxygen/html/search/functions_0.js @@ -1,6 +1,6 @@ var searchData= [ - ['activate',['activate',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a8466a9e84832b06f529b5a8c4add13c2',1,'DJI::onboardSDK::CoreAPI::activate(ActivateData *data, CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aa86e92debf14c980712fd2805eed70e0',1,'DJI::onboardSDK::CoreAPI::activate(ActivateData *data, int timeout)']]], + ['activate',['activate',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a8466a9e84832b06f529b5a8c4add13c2',1,'DJI::onboardSDK::CoreAPI']]], ['aes256_5fdecrypt_5fecb',['aes256_decrypt_ecb',['../DJI__Codec_8cpp.html#a34034040728c3dc9f29845ac7fb8fe31',1,'DJI_Codec.cpp']]], ['armcallback',['armCallback',['../classDJI_1_1onboardSDK_1_1Flight.html#ae4f2810f68f99c675adf16bbd5131985',1,'DJI::onboardSDK::Flight']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/functions_5.js b/dji_sdk_doc/doxygen/html/search/functions_5.js index a870979f..ccffffba 100644 --- a/dji_sdk_doc/doxygen/html/search/functions_5.js +++ b/dji_sdk_doc/doxygen/html/search/functions_5.js @@ -6,12 +6,11 @@ var searchData= ['getbatterycapacity',['getBatteryCapacity',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#accb169d18e0ce644b0adf7284483cc41',1,'DJI::onboardSDK::CoreAPI']]], ['getbroadcastdata',['getBroadcastData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a6e28d9d1bf933ee5ccfab6ec8891e16e',1,'DJI::onboardSDK::CoreAPI']]], ['getdriver',['getDriver',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab06228e965457f85ac8eebc7669a09ef',1,'DJI::onboardSDK::CoreAPI']]], - ['getdroneversion',['getDroneVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ad0af34b1556ba02f25daeaf0e91d61b3',1,'DJI::onboardSDK::CoreAPI::getDroneVersion(CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a94346c03fc72f0d9ca8a8709dad67f91',1,'DJI::onboardSDK::CoreAPI::getDroneVersion(int timeout)']]], + ['getdroneversion',['getDroneVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ad0af34b1556ba02f25daeaf0e91d61b3',1,'DJI::onboardSDK::CoreAPI']]], ['getfilter',['getFilter',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ab7fa0d20a6e4bf39a43a1c8a4841667f',1,'DJI::onboardSDK::CoreAPI']]], ['getflightstatus',['getFlightStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a83775b0cee8ef84d454ce6025edc1b62',1,'DJI::onboardSDK::CoreAPI']]], ['gethotpointdata',['getHotPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a021fc52fda6637f3624ae14e1a96dc28',1,'DJI::onboardSDK::CoreAPI']]], ['getmagnet',['getMagnet',['../classDJI_1_1onboardSDK_1_1Flight.html#a23fbea760546876fbd6b6af269deb1d1',1,'DJI::onboardSDK::Flight']]], - ['getobtaincontrolmobilecmd',['getObtainControlMobileCMD',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ad8fb88ea4af11dbec0e08dcff1be1709',1,'DJI::onboardSDK::CoreAPI']]], ['getquaternion',['getQuaternion',['../classDJI_1_1onboardSDK_1_1Flight.html#a63fcbf96eb69c5ffe7c1cfae237ec5de',1,'DJI::onboardSDK::Flight']]], ['getrcdata',['getRCData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#ab2ff6d77cdc0da443c5ae27736c06501',1,'DJI::onboardSDK::VirtualRC']]], ['getsdkversion',['getSDKVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f',1,'DJI::onboardSDK::CoreAPI']]], diff --git a/dji_sdk_doc/doxygen/html/search/functions_7.js b/dji_sdk_doc/doxygen/html/search/functions_7.js index 6eaee52e..6c25840b 100644 --- a/dji_sdk_doc/doxygen/html/search/functions_7.js +++ b/dji_sdk_doc/doxygen/html/search/functions_7.js @@ -1,5 +1,4 @@ var searchData= [ - ['neutralvrcsticks',['neutralVRCSticks',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a5a7974a1d812e1ed38b8bb9a092bebfc',1,'DJI::onboardSDK::VirtualRC']]], - ['notifycaller',['notifyCaller',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a8295bc2e7fc96c5c1742083a757f9ad6',1,'DJI::onboardSDK::CoreAPI']]] + ['neutralvrcsticks',['neutralVRCSticks',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a5a7974a1d812e1ed38b8bb9a092bebfc',1,'DJI::onboardSDK::VirtualRC']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/functions_8.js b/dji_sdk_doc/doxygen/html/search/functions_8.js index 1d3012da..ef174973 100644 --- a/dji_sdk_doc/doxygen/html/search/functions_8.js +++ b/dji_sdk_doc/doxygen/html/search/functions_8.js @@ -1,6 +1,5 @@ var searchData= [ - ['parsefrommobilecallback',['parseFromMobileCallback',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#afdf9c3d84a6b4445edacff7e2e29c219',1,'DJI::onboardSDK::CoreAPI']]], ['passdata',['passData',['../DJI__App_8cpp.html#a60f2a66b609bddc01c60372127d609c1',1,'DJI_App.cpp']]], ['pause',['pause',['../classDJI_1_1onboardSDK_1_1Follow.html#a014e135f35a4646303335c1922ef0b2b',1,'DJI::onboardSDK::Follow::pause()'],['../classDJI_1_1onboardSDK_1_1WayPoint.html#ae8554465c36efe306ac7159e9c4fb2d0',1,'DJI::onboardSDK::WayPoint::pause()']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/functions_a.js b/dji_sdk_doc/doxygen/html/search/functions_a.js index 64c71484..d5326e06 100644 --- a/dji_sdk_doc/doxygen/html/search/functions_a.js +++ b/dji_sdk_doc/doxygen/html/search/functions_a.js @@ -5,19 +5,16 @@ var searchData= ['sendpoll',['sendPoll',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5373ef1d252b233a022cc08e7b6df96c',1,'DJI::onboardSDK::CoreAPI']]], ['sendsafemodedata',['sendSafeModeData',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a26bb84b709df68859b7caecefa190849',1,'DJI::onboardSDK::VirtualRC']]], ['setaccountdata',['setAccountData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a76c8fa26fdc252af20b013928ec03ad6',1,'DJI::onboardSDK::CoreAPI']]], - ['setackframestatus',['setACKFrameStatus',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a078feb6bf36b83eb65f5e49b1ace8801',1,'DJI::onboardSDK::CoreAPI']]], ['setactivation',['setActivation',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a2a8f3380779cf660be316aa45470bb99',1,'DJI::onboardSDK::CoreAPI']]], - ['setbroadcastfreq',['setBroadcastFreq',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5490da3ad6bf7ea37f89783a4a75689a',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af49c3a3266e9a135f71b64c030106e7e',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, int timeout)']]], - ['setbroadcastfreqdefaults',['setBroadcastFreqDefaults',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac02ec7458365af90e9ea4e17ac9e08d1',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreqDefaults()'],['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5938890f73c9764cb8ceea6bb7d57634',1,'DJI::onboardSDK::CoreAPI::setBroadcastFreqDefaults(int timeout)']]], + ['setbroadcastfreq',['setBroadcastFreq',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a5490da3ad6bf7ea37f89783a4a75689a',1,'DJI::onboardSDK::CoreAPI']]], ['setcamera',['setCamera',['../classDJI_1_1onboardSDK_1_1Camera.html#a5f5a5e955ca32578a55635cdc6351efb',1,'DJI::onboardSDK::Camera']]], - ['setcontrol',['setControl',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a9148f90dc5a0a63511aef905d8890363',1,'DJI::onboardSDK::CoreAPI::setControl()'],['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a561e25be8d98214360affe7907b52f63',1,'DJI::onboardSDK::VirtualRC::setControl()']]], + ['setcontrol',['setControl',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a561e25be8d98214360affe7907b52f63',1,'DJI::onboardSDK::VirtualRC']]], ['setdata',['setData',['../classDJI_1_1onboardSDK_1_1Follow.html#adcdf0d6d3f33a6cb1f7ee5d65f064d7f',1,'DJI::onboardSDK::Follow::setData()'],['../classDJI_1_1onboardSDK_1_1HotPoint.html#a71572a01dfd5fe36fed492114d0652bc',1,'DJI::onboardSDK::HotPoint::setData()']]], ['setdriver',['setDriver',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#af11e76e300013a8d9a229019eaf01ab8',1,'DJI::onboardSDK::CoreAPI']]], ['setfollowdata',['setFollowData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aee573550da2469e7992097540550faef',1,'DJI::onboardSDK::CoreAPI']]], ['sethotpointdata',['setHotPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aeec7ae9063e509bbd6bf6039ead9be00',1,'DJI::onboardSDK::CoreAPI']]], ['setinfo',['setInfo',['../classDJI_1_1onboardSDK_1_1WayPoint.html#a697de2d4ae1666c9504755c3307324fb',1,'DJI::onboardSDK::WayPoint']]], ['setmovementcontrol',['setMovementControl',['../classDJI_1_1onboardSDK_1_1Flight.html#a53ae6a258cac9f81337e6cd1488d9347',1,'DJI::onboardSDK::Flight']]], - ['setobtaincontrolmobilecallback',['setObtainControlMobileCallback',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a221c804340554e0c04b31e8eeba96b33',1,'DJI::onboardSDK::CoreAPI']]], ['setversion',['setVersion',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aadeecafaad54eeabdfd6212d2b64ea3d',1,'DJI::onboardSDK::CoreAPI']]], ['setwaypointdata',['setWayPointData',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#ac8cad19f2b08d929011ad923cf87f45f',1,'DJI::onboardSDK::CoreAPI']]], ['start',['start',['../classDJI_1_1onboardSDK_1_1HotPoint.html#a92446411eb21eea88736280fa6c05bee',1,'DJI::onboardSDK::HotPoint']]] diff --git a/dji_sdk_doc/doxygen/html/search/searchdata.js b/dji_sdk_doc/doxygen/html/search/searchdata.js index 40fc1bce..44b1fbcb 100644 --- a/dji_sdk_doc/doxygen/html/search/searchdata.js +++ b/dji_sdk_doc/doxygen/html/search/searchdata.js @@ -1,15 +1,15 @@ var indexSectionsWithContent = { - 0: "_abcdefghilmnpqrstuvwy", + 0: "abcdefghilmnpqrstuvwy", 1: "abcefghmpqrstvwy", 2: "d", 3: "d", 4: "abcdfginprstu", - 5: "abcdhlmrstvw", - 6: "abceghmprsuvw", + 5: "abcdhlmrtvw", + 6: "abcefgmprsv", 7: "acmsy", 8: "ms", - 9: "_amnu", + 9: "amnu", 10: "dt" }; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_0.js b/dji_sdk_doc/doxygen/html/search/typedefs_0.js index 4d548e2d..5ea9fcd0 100644 --- a/dji_sdk_doc/doxygen/html/search/typedefs_0.js +++ b/dji_sdk_doc/doxygen/html/search/typedefs_0.js @@ -1,4 +1,5 @@ var searchData= [ + ['activatedata',['ActivateData',['../DJI__App_8h.html#a173a3ff7edd0475f8e6ac7060bec5058',1,'DJI_App.h']]], ['angle',['Angle',['../namespaceDJI.html#a2cefac21654530417c2fa39c8e7ef709',1,'DJI']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_2.js b/dji_sdk_doc/doxygen/html/search/typedefs_2.js index 45ae38d1..7f6b0e64 100644 --- a/dji_sdk_doc/doxygen/html/search/typedefs_2.js +++ b/dji_sdk_doc/doxygen/html/search/typedefs_2.js @@ -1,6 +1,4 @@ var searchData= [ - ['callback',['CallBack',['../DJI__Type_8h.html#a76838dd682b371ca42f6554eb60d6c93',1,'DJI::onboardSDK']]], - ['callbackhandler',['CallBackHandler',['../DJI__Type_8h.html#a8d688793c294cf31870d06881be995be',1,'DJI::onboardSDK']]], ['commondata',['CommonData',['../DJI__Type_8h.html#a2ac407a46bc557c653eb82dee70a97ba',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_4.js b/dji_sdk_doc/doxygen/html/search/typedefs_4.js index 30cb2e66..2ff8b7cf 100644 --- a/dji_sdk_doc/doxygen/html/search/typedefs_4.js +++ b/dji_sdk_doc/doxygen/html/search/typedefs_4.js @@ -1,7 +1,4 @@ var searchData= [ - ['gimbalangledata',['GimbalAngleData',['../DJI__Type_8h.html#a5dc007d5d982d79aed8091829a3efea3',1,'DJI::onboardSDK']]], - ['gpsdata',['GPSData',['../DJI__Type_8h.html#ad6db26bb74dcd881f93c0031bae5e914',1,'DJI::onboardSDK']]], - ['gpspositiondata',['GPSPositionData',['../DJI__Type_8h.html#a4cf179a160f63b28aa3d622aa3f73fb2',1,'DJI::onboardSDK']]], - ['gspushdata',['GSPushData',['../DJI__Mission_8h.html#a41d91cb318a3e33fd043da65ae130401',1,'DJI::onboardSDK']]] + ['flag',['Flag',['../namespaceDJI.html#ac46082a5ea8919b47fb64283edc5bc18',1,'DJI']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_5.js b/dji_sdk_doc/doxygen/html/search/typedefs_5.js index 0389cdcc..357fac3e 100644 --- a/dji_sdk_doc/doxygen/html/search/typedefs_5.js +++ b/dji_sdk_doc/doxygen/html/search/typedefs_5.js @@ -1,5 +1,5 @@ var searchData= [ - ['header',['Header',['../DJI__Type_8h.html#a14ecda64c265b3dd655ce82b06ce8456',1,'DJI::onboardSDK']]], - ['hotpointdata',['HotPointData',['../DJI__Type_8h.html#a1448a5d001a91235c5e08145d7f6a6a4',1,'DJI::onboardSDK']]] + ['gpsdata',['GPSData',['../DJI__Type_8h.html#ad6db26bb74dcd881f93c0031bae5e914',1,'DJI::onboardSDK']]], + ['gpspositiondata',['GPSPositionData',['../DJI__Type_8h.html#a4cf179a160f63b28aa3d622aa3f73fb2',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_6.js b/dji_sdk_doc/doxygen/html/search/typedefs_6.js index d082fd3a..622ddd34 100644 --- a/dji_sdk_doc/doxygen/html/search/typedefs_6.js +++ b/dji_sdk_doc/doxygen/html/search/typedefs_6.js @@ -4,6 +4,5 @@ var searchData= ['magnetdata',['MagnetData',['../DJI__Type_8h.html#aea6e13bf4b08fb7178bc0eb258fd0e4e',1,'DJI::onboardSDK']]], ['measure',['Measure',['../namespaceDJI.html#a33a0392b19136429c35297ee20819e73',1,'DJI']]], ['measurement',['Measurement',['../namespaceDJI.html#ab8295509ea10f45b68c55ae54614851f',1,'DJI']]], - ['missionack',['MissionACK',['../DJI__Type_8h.html#a57553a650086a257fa205069df5b8c84',1,'DJI::onboardSDK']]], ['mmu_5ftab',['MMU_Tab',['../DJI__Type_8h.html#a112002746462d1469ec7dbc562da0418',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_a.js b/dji_sdk_doc/doxygen/html/search/typedefs_a.js index 123fe8a7..772f4573 100644 --- a/dji_sdk_doc/doxygen/html/search/typedefs_a.js +++ b/dji_sdk_doc/doxygen/html/search/typedefs_a.js @@ -1,4 +1,6 @@ var searchData= [ - ['userdata',['UserData',['../namespaceDJI.html#a0988c6a482e73ea79bc55aac26729302',1,'DJI']]] + ['vector3ddata',['Vector3dData',['../namespaceDJI.html#a28c3320e81dd92ca9907acd13108a901',1,'DJI']]], + ['vector3fdata',['Vector3fData',['../DJI__Type_8h.html#a0fa0b666ea11bdb3c40cb0283a8a0b0e',1,'DJI::onboardSDK']]], + ['version',['Version',['../DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495',1,'DJI::onboardSDK']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_b.html b/dji_sdk_doc/doxygen/html/search/typedefs_b.html deleted file mode 100644 index dac1e0f2..00000000 --- a/dji_sdk_doc/doxygen/html/search/typedefs_b.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
                          -
                          Loading...
                          -
                          - -
                          Searching...
                          -
                          No Matches
                          - -
                          - - diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_b.js b/dji_sdk_doc/doxygen/html/search/typedefs_b.js deleted file mode 100644 index 772f4573..00000000 --- a/dji_sdk_doc/doxygen/html/search/typedefs_b.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['vector3ddata',['Vector3dData',['../namespaceDJI.html#a28c3320e81dd92ca9907acd13108a901',1,'DJI']]], - ['vector3fdata',['Vector3fData',['../DJI__Type_8h.html#a0fa0b666ea11bdb3c40cb0283a8a0b0e',1,'DJI::onboardSDK']]], - ['version',['Version',['../DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495',1,'DJI::onboardSDK']]] -]; diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_c.html b/dji_sdk_doc/doxygen/html/search/typedefs_c.html deleted file mode 100644 index 966e7e27..00000000 --- a/dji_sdk_doc/doxygen/html/search/typedefs_c.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
                          -
                          Loading...
                          -
                          - -
                          Searching...
                          -
                          No Matches
                          - -
                          - - diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_c.js b/dji_sdk_doc/doxygen/html/search/typedefs_c.js deleted file mode 100644 index 1e607a8d..00000000 --- a/dji_sdk_doc/doxygen/html/search/typedefs_c.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['waypointinitdata',['WayPointInitData',['../DJI__Type_8h.html#a25838ff0bcdcd511b138675bbf5c164b',1,'DJI::onboardSDK']]] -]; diff --git a/dji_sdk_doc/doxygen/html/search/variables_0.js b/dji_sdk_doc/doxygen/html/search/variables_0.js index 36a6c12a..dcca7664 100644 --- a/dji_sdk_doc/doxygen/html/search/variables_0.js +++ b/dji_sdk_doc/doxygen/html/search/variables_0.js @@ -1,7 +1,6 @@ var searchData= [ ['a',['a',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#ae0abd37507060ab7d48d158abd409d25',1,'DJI::onboardSDK::BroadcastData']]], - ['ack_5fdata',['ack_data',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#aadc5da4d57b8eaa5b7bdb5ed29a0bf69',1,'DJI::onboardSDK::CoreAPI']]], ['activation',['activation',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#adcc7240b20c1e562808cbbe815f9dcf7',1,'DJI::onboardSDK::BroadcastData']]], - ['altitude',['altitude',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#abf0a0f48abdee783e911c2e425924c04',1,'DJI::onboardSDK::WayPointInitData::altitude()'],['../structDJI_1_1onboardSDK_1_1PositionData.html#ac006d44f830b1493da4f672bf25b2ad1',1,'DJI::onboardSDK::PositionData::altitude()'],['../structDJI_1_1onboardSDK_1_1GPSPositionData.html#acd215ea39f8ef93865d200fc8b2c3b0a',1,'DJI::onboardSDK::GPSPositionData::altitude()']]] + ['altitude',['altitude',['../structDJI_1_1onboardSDK_1_1PositionData.html#ac006d44f830b1493da4f672bf25b2ad1',1,'DJI::onboardSDK::PositionData::altitude()'],['../structDJI_1_1onboardSDK_1_1GPSPositionData.html#acd215ea39f8ef93865d200fc8b2c3b0a',1,'DJI::onboardSDK::GPSPositionData::altitude()'],['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#abf0a0f48abdee783e911c2e425924c04',1,'DJI::onboardSDK::WayPointInitData::altitude()']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/variables_8.js b/dji_sdk_doc/doxygen/html/search/variables_8.js index e64e809c..64e04ccb 100644 --- a/dji_sdk_doc/doxygen/html/search/variables_8.js +++ b/dji_sdk_doc/doxygen/html/search/variables_8.js @@ -1,4 +1,4 @@ var searchData= [ - ['stopcond',['stopCond',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a0b5f3dbc0a3113b89ffec5f9bc47609b',1,'DJI::onboardSDK::CoreAPI']]] + ['time',['time',['../structDJI_1_1onboardSDK_1_1TimeStampData.html#aea9d03bc043adf819a0529665db64fa8',1,'DJI::onboardSDK::TimeStampData']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/variables_9.js b/dji_sdk_doc/doxygen/html/search/variables_9.js index 64e04ccb..3a6e03fe 100644 --- a/dji_sdk_doc/doxygen/html/search/variables_9.js +++ b/dji_sdk_doc/doxygen/html/search/variables_9.js @@ -1,4 +1,4 @@ var searchData= [ - ['time',['time',['../structDJI_1_1onboardSDK_1_1TimeStampData.html#aea9d03bc043adf819a0529665db64fa8',1,'DJI::onboardSDK::TimeStampData']]] + ['velocityground',['velocityGround',['../structDJI_1_1onboardSDK_1_1RTKData.html#a002a95cd7df302a8622651b82fb5c173',1,'DJI::onboardSDK::RTKData::velocityGround()'],['../structDJI_1_1onboardSDK_1_1GPSData.html#ac33952b3d773936e44c478bd1e028ea9',1,'DJI::onboardSDK::GPSData::velocityGround()']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/variables_a.js b/dji_sdk_doc/doxygen/html/search/variables_a.js index 3a6e03fe..3ddcbded 100644 --- a/dji_sdk_doc/doxygen/html/search/variables_a.js +++ b/dji_sdk_doc/doxygen/html/search/variables_a.js @@ -1,4 +1,4 @@ var searchData= [ - ['velocityground',['velocityGround',['../structDJI_1_1onboardSDK_1_1RTKData.html#a002a95cd7df302a8622651b82fb5c173',1,'DJI::onboardSDK::RTKData::velocityGround()'],['../structDJI_1_1onboardSDK_1_1GPSData.html#ac33952b3d773936e44c478bd1e028ea9',1,'DJI::onboardSDK::GPSData::velocityGround()']]] + ['w',['w',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a04c82cbd21eb9903984de09a4b770b88',1,'DJI::onboardSDK::BroadcastData']]] ]; diff --git a/dji_sdk_doc/doxygen/html/search/variables_b.html b/dji_sdk_doc/doxygen/html/search/variables_b.html deleted file mode 100644 index c98ef41d..00000000 --- a/dji_sdk_doc/doxygen/html/search/variables_b.html +++ /dev/null @@ -1,26 +0,0 @@ - - - - - - - - - -
                          -
                          Loading...
                          -
                          - -
                          Searching...
                          -
                          No Matches
                          - -
                          - - diff --git a/dji_sdk_doc/doxygen/html/search/variables_b.js b/dji_sdk_doc/doxygen/html/search/variables_b.js deleted file mode 100644 index 3ddcbded..00000000 --- a/dji_sdk_doc/doxygen/html/search/variables_b.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['w',['w',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a04c82cbd21eb9903984de09a4b770b88',1,'DJI::onboardSDK::BroadcastData']]] -]; diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle-members.html index e6710989..fd54894d 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle.html b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle.html index 010329e1..7ba88191 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerAngle.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle-members.html index 4bacfffa..c73572fe 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle.html b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle.html index deeaad8f..b3555014 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1EulerianAngle.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1Measure-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1Measure-members.html index df80a26b..f22ab0c3 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1Measure-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1Measure-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1Measure.html b/dji_sdk_doc/doxygen/html/structDJI_1_1Measure.html index 0922f6da..fb7e7a21 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1Measure.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1Measure.html @@ -114,7 +114,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement-members.html index 96b82731..140a6746 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement.html b/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement.html index d097b46d..841293db 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1Measurement.html @@ -114,7 +114,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector-members.html index f50e5752..b0119edb 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector.html b/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector.html index b4402641..98128973 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1SpaceVector.html @@ -110,14 +110,14 @@  

                          Detailed Description

                          -
                          Warning
                          This struct will be replaced by Vector3dData (similar to Vector3fData in DJI_Type.h) in a future release.
                          +
                          Warning
                          This struct will be replaced by Vector3dData (similar to Vector3fData in DJI_Type.h) in a future release.

                          The documentation for this struct was generated from the following file:
                          diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData-members.html index bf8bfc00..5e5da22c 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData.html index f70bd4cb..106e8e32 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1Vector3dData.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession-members.html index d9e59f0a..471fff5b 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession-members.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession.html index 941505a0..012f2b8f 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ACKSession.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack-members.html index 1684cf28..350c0fd9 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack-members.html @@ -102,7 +102,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack.html index 89b8ed1b..f5f10282 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Ack.html @@ -119,7 +119,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData-members.html deleted file mode 100644 index 3b7cab79..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData-members.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - -Onboard-SDK-ROS: Member List - - - - - - - - - - -
                          -
                          - - - - - - -
                          -
                          Onboard-SDK-ROS -
                          -
                          -
                          - - - - - - -
                          -
                          - - -
                          - -
                          - - -
                          -
                          -
                          -
                          DJI::onboardSDK::ActivateData Member List
                          -
                          - - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData.html deleted file mode 100644 index 33fa54ca..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - -Onboard-SDK-ROS: DJI::onboardSDK::ActivateData Struct Reference - - - - - - - - - - -
                          -
                          - - - - - - -
                          -
                          Onboard-SDK-ROS -
                          -
                          -
                          - - - - - - -
                          -
                          - - -
                          - -
                          - - -
                          -
                          - -
                          -
                          DJI::onboardSDK::ActivateData Struct Reference
                          -
                          -
                          - - - - - - - - - - - - -

                          -Public Attributes

                          -unsigned int ID
                           
                          -unsigned int reserved
                           
                          -unsigned int version
                           
                          -unsigned char iosID [32]
                           
                          -char * encKey
                           
                          -
                          The documentation for this struct was generated from the following file: -
                          - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData-members.html index a8fbe70c..cd07db08 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData-members.html @@ -113,7 +113,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData.html index efddb6aa..23d9061a 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1BroadcastData.html @@ -143,7 +143,7 @@  

                          Detailed Description

                          -
                          Todo:
                          +

                          Member Data Documentation

                          @@ -180,7 +180,7 @@
                          -
                          Todo:
                          define enum
                          +
                          Todo:
                          define enum
                          @@ -229,7 +229,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession-members.html index 0fcdedc2..6c1e71da 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession-members.html @@ -107,7 +107,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession.html index 6f755ead..f6b41b6e 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CMDSession.html @@ -119,7 +119,7 @@ CallBack handler   -UserData userData +UserData userData   uint32_t preSeqNum @@ -134,7 +134,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler-members.html index 67b55eda..536f8df9 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler.html index 0357def3..829c3314 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CallBackHandler.html @@ -94,11 +94,6 @@
                          DJI::onboardSDK::CallBackHandler Struct Reference
                          - -

                          The CallBackHandler struct allows users to encapsulate callbacks and data in one struct. - More...

                          - -

                          #include <DJI_Type.h>

                          @@ -106,18 +101,16 @@ CallBack  +UserData 

                          Public Attributes

                          callback
                           
                          -UserData userData
                          userData
                           
                          -

                          Detailed Description

                          -

                          The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.

                          -

                          The documentation for this struct was generated from the following file:
                            +
                            The documentation for this struct was generated from the following file:
                          diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command-members.html index 1b926baf..0cb70c49 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command-members.html @@ -105,7 +105,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command.html index 637240db..9684f766 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Command.html @@ -119,7 +119,7 @@ CallBack handler   -UserData userData +UserData userData  
                          The documentation for this struct was generated from the following file:
                            @@ -128,7 +128,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData-members.html index 9711098e..057d2d07 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData.html index fd393a26..8a99f035 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CommonData.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData-members.html index 1e7e5b1b..73512f83 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData-members.html @@ -102,7 +102,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData.html index e6efcdf1..46f713be 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1CtrlInfoData.html @@ -122,7 +122,7 @@

                            Member Data Documentation

                            -
                            Todo:
                            mode remote to enums
                            +
                            Todo:
                            mode remote to enums
                            @@ -132,7 +132,7 @@

                            Member Data Documentation

                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData-members.html index ef82ba09..ed252a30 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData-members.html @@ -102,7 +102,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData.html index 7f84cb2f..707faf7e 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FlightData.html @@ -119,7 +119,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData-members.html index 71632c2d..d7536fe4 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData-members.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData.html index 6ce48074..2c700a5b 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowData.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget-members.html index ade10638..add03449 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget-members.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget.html index eaa94503..4ed0fb32 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1FollowTarget.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData-members.html index f92d00b3..9890e270 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData-members.html @@ -105,7 +105,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData.html index b3b444e1..f36af176 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSData.html @@ -123,7 +123,7 @@  

                            Detailed Description

                            -
                            Todo:
                            rename to a final version Detailed GPSData from the A3. This is not available on the M100.
                            +
                            Todo:
                            rename to a final version

                            Member Data Documentation

                            @@ -157,7 +157,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData-members.html index 3636cabb..217b17c7 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData-members.html @@ -100,7 +100,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData.html index 840c7ab1..d93e0b56 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GPSPositionData.html @@ -130,7 +130,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData-members.html index b460d704..47bb9f85 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData-members.html @@ -103,7 +103,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData.html index 9ec1a0fe..ae2346a4 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GSPushData.html @@ -119,14 +119,14 @@  

                            Detailed Description

                            -
                            Todo:
                            unify the naming style
                            +
                            Todo:
                            unify the naming style

                            The documentation for this struct was generated from the following file:
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData-members.html index d679c143..8b30cebe 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData-members.html @@ -102,7 +102,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData.html index 7379a938..f80b58dc 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalAngleData.html @@ -94,8 +94,6 @@
                            DJI::onboardSDK::GimbalAngleData Struct Reference
                            - -

                            #include <DJI_Type.h>

                            @@ -115,15 +113,13 @@ uint8_t 

                            Public Attributes

                            duration
                             
                            -

                            Detailed Description

                            -

                            Gimbal Data

                            -

                            The documentation for this struct was generated from the following file:
                              +
                              The documentation for this struct was generated from the following file:
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData-members.html index d007cf19..2d01f735 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData-members.html @@ -104,7 +104,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData.html index 817f6d26..73345e44 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalData.html @@ -125,7 +125,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData-members.html index 830d09f7..b27f70c7 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData-members.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData.html index dcf6cdc8..d1f1e7d4 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1GimbalSpeedData.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header-members.html index d0c0bdaa..05865f70 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header-members.html @@ -108,7 +108,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header.html index 78653d52..0c1d967e 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Header.html @@ -94,11 +94,6 @@
                            DJI::onboardSDK::Header Struct Reference
                            - -

                            The Header struct is meant to handle the open protocol header. - More...

                            - -

                            #include <DJI_Type.h>

                            @@ -134,9 +129,7 @@ unsigned int 

                            Public Attributes

                            crc: 16
                             
                            -

                            Detailed Description

                            -

                            The Header struct is meant to handle the open protocol header.

                            -

                            Member Data Documentation

                            +

                            Member Data Documentation

                            @@ -169,7 +162,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData-members.html index 86b98a6c..77f56e7e 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData-members.html @@ -101,7 +101,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData.html index 7770d10d..575c52d8 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointACKData.html @@ -116,7 +116,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData-members.html index 7567777b..b3d00217 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData-members.html @@ -107,7 +107,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData.html index b23a7af3..dc7eb59b 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointData.html @@ -94,8 +94,6 @@
                            DJI::onboardSDK::HotPointData Struct Reference
                            - -

                            #include <DJI_Type.h>

                            @@ -130,15 +128,13 @@ uint8_t 

                            Public Attributes

                            reserved [11]
                             
                            -

                            Detailed Description

                            -

                            HotPoint Data

                            -

                            The documentation for this struct was generated from the following file:
                              -
                            • dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
                            • +
                              The documentation for this struct was generated from the following file:
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK-members.html deleted file mode 100644 index 1159ff85..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK-members.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - -Onboard-SDK-ROS: Member List - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            -
                            -
                            DJI::onboardSDK::HotPointReadACK Member List
                            -
                            -
                            - -

                            This is the complete list of members for DJI::onboardSDK::HotPointReadACK, including all inherited members.

                            - - - -
                            ack (defined in DJI::onboardSDK::HotPointReadACK)DJI::onboardSDK::HotPointReadACK
                            data (defined in DJI::onboardSDK::HotPointReadACK)DJI::onboardSDK::HotPointReadACK
                            - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK.html deleted file mode 100644 index 64e2f778..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK.html +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - -Onboard-SDK-ROS: DJI::onboardSDK::HotPointReadACK Struct Reference - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            - -
                            -
                            DJI::onboardSDK::HotPointReadACK Struct Reference
                            -
                            -
                            - - - - - - -

                            -Public Attributes

                            -MissionACK ack
                             
                            -HotPointData data
                             
                            -
                            The documentation for this struct was generated from the following file: -
                            - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK-members.html deleted file mode 100644 index 93eeb07b..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK-members.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - -Onboard-SDK-ROS: Member List - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            -
                            -
                            DJI::onboardSDK::HotPointStartACK Member List
                            -
                            -
                            - -

                            This is the complete list of members for DJI::onboardSDK::HotPointStartACK, including all inherited members.

                            - - - -
                            ack (defined in DJI::onboardSDK::HotPointStartACK)DJI::onboardSDK::HotPointStartACK
                            maxRadius (defined in DJI::onboardSDK::HotPointStartACK)DJI::onboardSDK::HotPointStartACK
                            - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK.html deleted file mode 100644 index 8f098190..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK.html +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - -Onboard-SDK-ROS: DJI::onboardSDK::HotPointStartACK Struct Reference - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            - -
                            -
                            DJI::onboardSDK::HotPointStartACK Struct Reference
                            -
                            -
                            - - - - - - -

                            -Public Attributes

                            -uint8_t ack
                             
                            -float32_t maxRadius
                             
                            -
                            The documentation for this struct was generated from the following file: -
                            - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate-members.html index 85cf8bca..f507baaf 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate.html index ed945062..dec37f9e 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPoint_1_1YawRate.html @@ -110,7 +110,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab-members.html index 8f9c399f..411cd4be 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab-members.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab.html index 692aac2b..4ce2946e 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MMU__Tab.html @@ -120,7 +120,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData-members.html index 59e11b6e..23f53aba 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData.html index b9bc0a9e..735a271f 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagData.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData-members.html index de17ca8f..cdc1b7a4 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData.html index efdbd830..fe9c6ba7 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MagnetData.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap-members.html index 7246c505..172176e1 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap.html index a799759e..37422778 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1MissionACKMap.html @@ -110,7 +110,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData-members.html index 01afee73..5be970a8 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData-members.html @@ -102,7 +102,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData.html index c73cc562..352c63db 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1PositionData.html @@ -146,7 +146,7 @@

                            Member Data Documentation

                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData-members.html index 19712435..1a996150 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData-members.html @@ -101,7 +101,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData.html index ada57b02..7d5c25fb 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1QuaternionData.html @@ -116,7 +116,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData-members.html index 3e3cf7e7..a94f7870 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData-members.html @@ -103,7 +103,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData.html index 469d88a8..f3928a8d 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RCData.html @@ -126,7 +126,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData-members.html index 851de404..a8ae4d7d 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData-members.html @@ -108,7 +108,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData.html index 316abf25..d3847359 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RTKData.html @@ -132,7 +132,7 @@  

                            Detailed Description

                            -
                            Todo:
                            rename to a final version RTKData from the A3. This is not available on the M100.
                            +
                            Todo:
                            rename to a final version

                            Member Data Documentation

                            @@ -166,7 +166,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData-members.html index 6cc7e35a..2ec80b40 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData-members.html @@ -103,7 +103,7 @@
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData.html index 3bf27aad..f06c11f5 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1RadioData.html @@ -126,7 +126,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter-members.html index 88303725..5f91526a 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter-members.html @@ -103,7 +103,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter.html index 81e31ddd..1d04a3a2 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1SDKFilter.html @@ -126,7 +126,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData-members.html index 2992cde1..3be56880 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData.html index 315e9849..2f121546 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TaskData.html @@ -110,7 +110,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData-members.html index 0248c66b..f505dc80 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData.html index d8b4b34b..f52bba33 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1TimeStampData.html @@ -116,7 +116,7 @@

                            Member Data Documentation

                            -
                            Todo:
                            type modify
                            +
                            Todo:
                            type modify
                            @@ -126,7 +126,7 @@

                            Member Data Documentation

                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData-members.html index e8d7743b..2802c0ce 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData.html index 39d21c1f..277be433 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1Vector3fData.html @@ -117,7 +117,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData-members.html index a0d8e6e8..e109fe46 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData-members.html @@ -103,7 +103,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData.html index 6a343042..8a2a5c7d 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VelocityData.html @@ -122,7 +122,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData-members.html deleted file mode 100644 index 0fd8e32b..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData-members.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - -Onboard-SDK-ROS: Member List - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            -
                            -
                            DJI::onboardSDK::VersionData Member List
                            -
                            -
                            - -

                            This is the complete list of members for DJI::onboardSDK::VersionData, including all inherited members.

                            - - - - - - -
                            version (defined in DJI::onboardSDK::VersionData)DJI::onboardSDK::VersionData
                            version_ack (defined in DJI::onboardSDK::VersionData)DJI::onboardSDK::VersionData
                            version_crc (defined in DJI::onboardSDK::VersionData)DJI::onboardSDK::VersionData
                            version_ID (defined in DJI::onboardSDK::VersionData)DJI::onboardSDK::VersionData
                            version_name (defined in DJI::onboardSDK::VersionData)DJI::onboardSDK::VersionData
                            - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData.html deleted file mode 100644 index b09716b5..00000000 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - -Onboard-SDK-ROS: DJI::onboardSDK::VersionData Struct Reference - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            - -
                            -
                            DJI::onboardSDK::VersionData Struct Reference
                            -
                            -
                            - - - - - - - - - - - - -

                            -Public Attributes

                            -unsigned short version_ack
                             
                            -unsigned int version_crc
                             
                            -char version_ID [11]
                             
                            -char version_name [32]
                             
                            -DJI::onboardSDK::Version version
                             
                            -
                            The documentation for this struct was generated from the following file: -
                            - - - - diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData-members.html index bf502460..f9a08396 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData-members.html @@ -113,7 +113,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData.html index 0872ebab..b4b16ad1 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCData.html @@ -156,7 +156,7 @@

                            Member Data Documentation

                            Note
                            this is default mapping data structure for virtual remote controller.
                            -
                            Todo:
                            channel mapping
                            +
                            Todo:
                            channel mapping
                            @@ -166,7 +166,7 @@

                            Member Data Documentation

                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting-members.html index 2f145ad6..f50c1f49 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting-members.html @@ -100,7 +100,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting.html index e3d61e4e..568c5b06 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VirtualRCSetting.html @@ -113,7 +113,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData-members.html index 84b51495..fceaf1e3 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData-members.html @@ -112,7 +112,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData.html index 0afcaa2f..7a8f4453 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointData.html @@ -157,12 +157,12 @@

                            Member Data Documentation


                            The documentation for this struct was generated from the following file: diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK-members.html index 803870f9..bd0ee5a6 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK.html index 2c4afcad..bf5fa795 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointDataACK.html @@ -105,12 +105,12 @@  
                            The documentation for this struct was generated from the following file: diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK-members.html index bf52a89b..e963ea99 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK.html index b246177a..84060130 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitACK.html @@ -105,12 +105,12 @@  
                            The documentation for this struct was generated from the following file: diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData-members.html index 97b60df8..178ca09b 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData-members.html @@ -110,7 +110,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData.html index e0850617..fdb721ba 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointInitData.html @@ -94,8 +94,6 @@
                            DJI::onboardSDK::WayPointInitData Struct Reference
                            - -

                            #include <DJI_Type.h>

                            @@ -139,9 +137,7 @@ uint8_t 

                            Public Attributes

                            reserved [16]
                             
                            -

                            Detailed Description

                            -

                            WayPoint Data

                            -

                            Member Data Documentation

                            +

                            Member Data Documentation

                            @@ -151,17 +147,17 @@
                            -
                            Note
                            For Camera to recording
                            +
                            Note
                            For Camera to recording

                            The documentation for this struct was generated from the following file:
                            diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK-members.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK-members.html index 60314645..b629d696 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK-members.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK-members.html @@ -99,7 +99,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html index 6347d85d..262fdd38 100644 --- a/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html +++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html @@ -105,12 +105,12 @@  
                            The documentation for this struct was generated from the following file: diff --git a/dji_sdk_doc/doxygen/html/structreq__id__t-members.html b/dji_sdk_doc/doxygen/html/structreq__id__t-members.html index 7e97fa91..0d2606fa 100644 --- a/dji_sdk_doc/doxygen/html/structreq__id__t-members.html +++ b/dji_sdk_doc/doxygen/html/structreq__id__t-members.html @@ -97,7 +97,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structreq__id__t.html b/dji_sdk_doc/doxygen/html/structreq__id__t.html index 7697c27b..2509946f 100644 --- a/dji_sdk_doc/doxygen/html/structreq__id__t.html +++ b/dji_sdk_doc/doxygen/html/structreq__id__t.html @@ -112,7 +112,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structtagAES256Context-members.html b/dji_sdk_doc/doxygen/html/structtagAES256Context-members.html index 36f164db..9f6cb26e 100644 --- a/dji_sdk_doc/doxygen/html/structtagAES256Context-members.html +++ b/dji_sdk_doc/doxygen/html/structtagAES256Context-members.html @@ -96,7 +96,7 @@ diff --git a/dji_sdk_doc/doxygen/html/structtagAES256Context.html b/dji_sdk_doc/doxygen/html/structtagAES256Context.html index 9ad02c87..bc7b86af 100644 --- a/dji_sdk_doc/doxygen/html/structtagAES256Context.html +++ b/dji_sdk_doc/doxygen/html/structtagAES256Context.html @@ -109,7 +109,7 @@ diff --git a/dji_sdk_doc/doxygen/html/todo.html b/dji_sdk_doc/doxygen/html/todo.html index 2e122614..c5b4598a 100644 --- a/dji_sdk_doc/doxygen/html/todo.html +++ b/dji_sdk_doc/doxygen/html/todo.html @@ -81,65 +81,63 @@
                            -
                            Member API_ERROR_DATA
                            -
                            Not supported in this release.
                            -
                            Member API_LOG (driver, title, fmt,...)
                            +
                            Member ActivateData
                            +
                            move to type.h
                            +
                            Member API_ERROR_DATA
                            +
                            not available yet, only affect WayPoint
                            +
                            Member API_LOG (driver, title, fmt,...)
                            fix warning.
                            -
                            Member DJI::Angle
                            +
                            Member DJI::Angle
                            range mathematial class class Angle { public: Angle(double degree = 0);
                            -
                            Member DJI::onboardSDK::ACK_ERROR_CODE
                            +
                            Member DJI::onboardSDK::ACK_COMMON_CODE
                            sort enum and move to a new file
                            -
                            Member DJI::onboardSDK::BroadcastData
                            +
                            Member DJI::onboardSDK::BroadcastData
                            -
                            Member DJI::onboardSDK::BroadcastData::battery
                            +
                            Member DJI::onboardSDK::BroadcastData::battery
                            define enum
                            -
                            Member DJI::onboardSDK::CoreAPI::activate (ActivateData *data, int timeout)
                            -
                            Implement high resolution timer to catch ACK timeout
                            -
                            Member DJI::onboardSDK::CoreAPI::byteHandler (const uint8_t in_data)
                            +
                            Member DJI::onboardSDK::CoreAPI::byteHandler (const uint8_t in_data)
                            Pipeline refactoring
                            -
                            Member DJI::onboardSDK::CoreAPI::byteStreamHandler (uint8_t *buffer, size_t size)
                            +
                            Member DJI::onboardSDK::CoreAPI::byteStreamHandler (uint8_t *buffer, size_t size)
                            Implement stream handler
                            -
                            Member DJI::onboardSDK::CoreAPI::callbackPoll (void)
                            +
                            Member DJI::onboardSDK::CoreAPI::callbackPoll (void)

                            Implement callback poll handler

                            Implement callback poll here

                            -
                            Member DJI::onboardSDK::CoreAPI::decodeMissionStatus (uint8_t ack)
                            +
                            Member DJI::onboardSDK::CoreAPI::decodeMissionStatus (uint8_t ack)
                            Fix memory leak issue
                            -
                            Member DJI::onboardSDK::CoreAPI::getDroneVersion (int timeout)
                            -
                            Implement high resolution timer to catch ACK timeout
                            -
                            Member DJI::onboardSDK::CoreAPI::setBroadcastFreqDefaults (int timeout)
                            -
                            Implement high resolution timer to catch ACK timeout
                            -
                            Member DJI::onboardSDK::CoreAPI::setControl (bool enable, int timeout)
                            -
                            Implement high resolution timer to catch ACK timeout
                            -
                            Member DJI::onboardSDK::CtrlInfoData::deviceStatus
                            +
                            Member DJI::onboardSDK::CtrlInfoData::deviceStatus
                            mode remote to enums
                            -
                            Member DJI::onboardSDK::Flight::Mode
                            +
                            Member DJI::onboardSDK::Flight::Mode
                            rename
                            -
                            Member DJI::onboardSDK::GPSData
                            -
                            rename to a final version Detailed GPSData from the A3. This is not available on the M100.
                            -
                            Member DJI::onboardSDK::GSPushData
                            +
                            Member DJI::onboardSDK::GPSData
                            +
                            rename to a final version
                            +
                            Class DJI::onboardSDK::GSPushData
                            unify the naming style
                            -
                            Member DJI::onboardSDK::RTKData
                            -
                            rename to a final version RTKData from the A3. This is not available on the M100.
                            -
                            Member DJI::onboardSDK::TimeStampData::time
                            +
                            Member DJI::onboardSDK::RTKData
                            +
                            rename to a final version
                            +
                            Member DJI::onboardSDK::TimeStampData::time
                            type modify
                            -
                            Member DJI::onboardSDK::VirtualRCData::roll
                            +
                            Member DJI::onboardSDK::Version
                            +
                            better version control structure
                            +
                            Member DJI::onboardSDK::VirtualRCData::roll
                            channel mapping
                            -
                            Member DJI::onboardSDK::WayPoint::readIdleVelocity (CallBack callback=0, UserData userData=0)
                            +
                            Member DJI::onboardSDK::WayPoint::readIdleVelocity (CallBack callback=0, UserData userData=0)
                            implement
                            -
                            Member DJI::onboardSDK::WayPoint::readIndexData (uint8_t index, CallBack callback=0, UserData userData=0)
                            +
                            Member DJI::onboardSDK::WayPoint::readIndexData (uint8_t index, CallBack callback=0, UserData userData=0)
                            implement
                            -
                            Member DJI::onboardSDK::WayPoint::setInfo (const WayPointInitData &value)
                            +
                            Member DJI::onboardSDK::WayPoint::setInfo (const WayPointInitData &value)
                            set information for way point
                            -
                            Member DJI::onboardSDK::WayPoint::uploadIndexData (WayPointData *data, CallBack callback=0, UserData userData=0)
                            +
                            Member DJI::onboardSDK::WayPoint::uploadIndexData (WayPointData *data, CallBack callback=0, UserData userData=0)
                            uploadAll
                            +
                            File DJI_Codec.h
                            +
                            spilt this header into 4 header files
                            Member passData (uint16_t flag, uint16_t &enable, void *data, unsigned char *buf, size_t datalen, size_t &offset)
                            new algorithm
                            diff --git a/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion-members.html b/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion-members.html deleted file mode 100644 index b9a8e216..00000000 --- a/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion-members.html +++ /dev/null @@ -1,111 +0,0 @@ - - - - - - -Onboard-SDK-ROS: Member List - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            -
                            -
                            DJI::onboardSDK::MissionACKUnion Member List
                            -
                            - - - - - diff --git a/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion.html b/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion.html deleted file mode 100644 index 5612fa35..00000000 --- a/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion.html +++ /dev/null @@ -1,130 +0,0 @@ - - - - - - -Onboard-SDK-ROS: DJI::onboardSDK::MissionACKUnion Union Reference - - - - - - - - - - -
                            -
                            - - - - - - -
                            -
                            Onboard-SDK-ROS -
                            -
                            -
                            - - - - - - -
                            -
                            - - -
                            - -
                            - - -
                            -
                            - -
                            -
                            DJI::onboardSDK::MissionACKUnion Union Reference
                            -
                            -
                            - - - - - - - - - - - - - - -

                            -Public Attributes

                            -uint8_t raw_ack_array [5]
                             
                            -MissionACK missionACK
                             
                            -SimpleACK simpleACK
                             
                            -HotPointStartACK hotpointStartACK
                             
                            -WayPointDataACK waypointDataACK
                             
                            -WayPointVelocityACK waypointVelocityACK
                             
                            -
                            The documentation for this union was generated from the following file: -
                            - - - - 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 e2b13eb9..df6b34c0 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h @@ -25,11 +25,11 @@ #ifndef DJI_API_H #define DJI_API_H -#include "DJI_Type.h" -//#include "DJI_Mission.h" +#include "DJI_Type.h" #include "DJI_HardDriver.h" #include "DJI_App.h" + namespace DJI { namespace onboardSDK @@ -72,11 +72,13 @@ enum ACK_ACTIVE_CODE enum ACK_SETCONTROL_CODE { - ACK_SETCONTROL_NEED_MODE_F = 0x0000, + ACK_SETCONTROL_ERROR_MODE = 0x0000, ACK_SETCONTROL_RELEASE_SUCCESS = 0x0001, ACK_SETCONTROL_OBTAIN_SUCCESS = 0x0002, ACK_SETCONTROL_OBTAIN_RUNNING = 0x0003, ACK_SETCONTROL_RELEASE_RUNNING = 0x0004, + ACK_SETCONTROL_NEED_MODE_F = 0x0006, + ACK_SETCONTROL_NEED_MODE_P = 0x0005, ACK_SETCONTROL_IOC = 0x00C9, }; @@ -227,11 +229,10 @@ class CoreAPI void ack(req_id_t req_id, unsigned char *ackdata, int len); //! Notify caller ACK frame arrived + void allocateACK(Header *protocolHeader); void notifyCaller(Header *protocolHeader); - void notifyNonBlockingCaller(Header *protocolHeader); - //@{ /** * @remark @@ -551,7 +552,6 @@ class CoreAPI void setVersion(const Version &value); /** - * Setters and getters for Mobile CMD variables - these are used * when interacting with a Data Transparent Transmission App */ @@ -611,7 +611,6 @@ class CoreAPI unsigned char encodeSendData[BUFFER_SIZE]; unsigned char encodeACK[ACK_SIZE]; - //! Mobile Data Transparent Transmission - callbacks CallBackHandler fromMobileCallback; CallBackHandler broadcastCallback; @@ -647,6 +646,7 @@ class CoreAPI bool takePhotoMobileCMD; bool startVideoMobileCMD; bool stopVideoMobileCMD; + bool drawCirMobileCMD; bool drawSqrMobileCMD; bool attiCtrlMobileCMD; @@ -656,11 +656,11 @@ class CoreAPI bool globalNavTestMobileCMD; bool VRCTestMobileCMD; bool localMissionPlanCMD; + VersionData versionData; ActivateData accountData; unsigned short seq_num; - unsigned char *version_ack_data; SDKFilter filter; diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h index c6fa971d..e773e0bb 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h @@ -33,7 +33,7 @@ #define API_STATUS_DATA //! @note if you do NOT want to use AES encrypt, comment this macro below -#define USE_ENCRYPT +//#define USE_ENCRYPT //! @todo Not supported in this release. //#define USE_SIMULATION 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 3366e076..1ab0bf98 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h @@ -1,6 +1,6 @@ /*! @file DJI_Type.h - * @version 3.1.7 - * @date Jul 01 2016 + * @version 3.1.9 + * @date November 10, 2016 * * @brief * Type definition for DJI onboardSDK library. @@ -22,6 +22,8 @@ #include "DJI_Config.h" #include "DJICommonType.h" #include +#include +#include #define NAME(x) #x @@ -122,6 +124,13 @@ extern uint8_t encrypt; const size_t SESSION_TABLE_NUM = 32; 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; + //! The CoreAPI class definition is detailed in DJI_API.h class CoreAPI; @@ -337,18 +346,7 @@ typedef struct WayPointVelocityACK float32_t idleVelocity; } WayPointVelocityACK; - -typedef union MissionACKUnion -{ - uint8_t raw_ack_array[5]; - MissionACK missionACK; - SimpleACK simpleACK; - HotPointStartACK hotpointStartACK; - WayPointDataACK waypointDataACK; - WayPointVelocityACK waypointVelocityACK; -} MissionACKUnion; - -// These big structs have structs within and don't seem to be used +// HotPoint data read from flight controller typedef struct HotPointReadACK { MissionACK ack; @@ -361,6 +359,33 @@ typedef struct WayPointInitACK WayPointInitData data; } WayPointInitACK; +typedef struct DroneVersionACK +{ + unsigned char ack[MAX_ACK_SIZE]; +}; + +typedef union MissionACKUnion +{ + uint8_t raw_ack_array[MAX_ACK_SIZE]; + DroneVersionACK droneVersion; + MissionACK missionACK; + + SimpleACK simpleACK; + + HotPointStartACK hotpointStartACK; + + // Contains 1-Byte ACK plus hotpoint mission + // information read from flight controller + HotpointReadACK hotpointReadACK; + + // Contains 1-Byte ACK plus waypoint mission + // information read from flight controller + WayPointInitACK waypointInitACK; + + WayPointDataACK waypointDataACK; + WayPointVelocityACK waypointVelocityACK; +} MissionACKUnion; + typedef struct QuaternionData { float32_t q0; diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h index 87169fb4..b51c8466 100644 --- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h +++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h @@ -35,6 +35,7 @@ typedef uint32_t Version; const Version versionM100_23 = (MAKE_VERSION(2, 3, 10, 0)); const Version versionM100_31 = (MAKE_VERSION(3, 1, 10, 0)); const Version versionA3_31 = (MAKE_VERSION(3, 1, 100, 0)); +const Version versionA3_32 = (MAKE_VERSION(3, 2, 0, 0)); #ifdef SDK_DEV #include "dev.h" diff --git a/dji_sdk_lib/src/DJI_API.cpp b/dji_sdk_lib/src/DJI_API.cpp index 3ffed111..b841ef76 100644 --- a/dji_sdk_lib/src/DJI_API.cpp +++ b/dji_sdk_lib/src/DJI_API.cpp @@ -1,6 +1,6 @@ /** @file DJI_API.cpp - * @version 3.1.7 - * @date July 1st, 2016 + * @version 3.1.9 + * @date November 10, 2016 * * @brief * Core API for DJI onboardSDK library @@ -179,7 +179,7 @@ VersionData CoreAPI::getDroneVersion(int timeout) unsigned char cmd_data = 0; send(2, 0, SET_ACTIVATION, CODE_GETVERSION, (unsigned char *)&cmd_data, 1, cmd_timeout, - retry_time, 0, 0); + retry_time, 0, 0); // Wait for end of ACK frame to arrive serialDevice->lockACK(); @@ -187,18 +187,23 @@ VersionData CoreAPI::getDroneVersion(int timeout) serialDevice->freeACK(); // Parse return value - - versionData.version_ack = version_ack_data[0] + (version_ack_data[1] << 8); - version_ack_data += 2; - versionData.version_crc = - version_ack_data[0] + (version_ack_data[1] << 8) + (version_ack_data[2] << 16) + (version_ack_data[3] << 24); - ack_data += 4; - if (versionData.version != versionM100_23) - { - memcpy(versionData.version_ID, version_ack_data, 11); - ack_data += 11; + 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); } - memcpy(versionData.version_name, version_ack_data, 32); return versionData; } @@ -244,7 +249,6 @@ unsigned short CoreAPI::activate(ActivateData *data, int timeout) return ack_data; } - void CoreAPI::sendToMobile(uint8_t *data, uint8_t len, CallBack callback, UserData userData) { if (len > 100) @@ -317,7 +321,8 @@ void CoreAPI::setBroadcastFreqDefaults() { uint8_t freq[16]; - /* Channels definition: + /* Channels definition: + * M100: * 0 - Timestamp * 1 - Attitude Quaterniouns * 2 - Acceleration @@ -330,21 +335,55 @@ void CoreAPI::setBroadcastFreqDefaults() * 9 - Flight Status * 10 - Battery Level * 11 - Control Information + * + * A3: + * 0 - Timestamp + * 1 - Attitude Quaterniouns + * 2 - Acceleration + * 3 - Velocity (Ground Frame) + * 4 - Angular Velocity (Body Frame) + * 5 - Position + * 6 - GPS Detailed Information + * 7 - RTK Detailed Information + * 8 - Magnetometer + * 9 - RC Channels Data + * 10 - Gimbal Data + * 11 - Flight Status + * 12 - Battery Level + * 13 - Control Information + * */ - freq[0] = BROADCAST_FREQ_1HZ; - freq[1] = BROADCAST_FREQ_10HZ; - freq[2] = BROADCAST_FREQ_50HZ; - freq[3] = BROADCAST_FREQ_100HZ; - freq[4] = BROADCAST_FREQ_50HZ; - freq[5] = BROADCAST_FREQ_10HZ; - freq[6] = BROADCAST_FREQ_1HZ; - freq[7] = BROADCAST_FREQ_10HZ; - freq[8] = BROADCAST_FREQ_50HZ; - freq[9] = BROADCAST_FREQ_100HZ; - freq[10] = BROADCAST_FREQ_50HZ; - freq[11] = BROADCAST_FREQ_10HZ; - + if (versionData.version == versionM100_31 || versionData.version == versionM100_23) { + freq[0] = BROADCAST_FREQ_1HZ; + freq[1] = BROADCAST_FREQ_10HZ; + freq[2] = BROADCAST_FREQ_50HZ; + freq[3] = BROADCAST_FREQ_100HZ; + freq[4] = BROADCAST_FREQ_50HZ; + freq[5] = BROADCAST_FREQ_10HZ; + freq[6] = BROADCAST_FREQ_1HZ; + freq[7] = BROADCAST_FREQ_10HZ; + freq[8] = BROADCAST_FREQ_50HZ; + freq[9] = BROADCAST_FREQ_100HZ; + freq[10] = BROADCAST_FREQ_50HZ; + freq[11] = BROADCAST_FREQ_10HZ; + } + else if (versionData.version == versionA3_31 || versionData.version == versionA3_32) { + freq[0] = BROADCAST_FREQ_1HZ; + freq[1] = BROADCAST_FREQ_10HZ; + freq[2] = BROADCAST_FREQ_50HZ; + freq[3] = BROADCAST_FREQ_100HZ; + freq[4] = BROADCAST_FREQ_50HZ; + freq[5] = BROADCAST_FREQ_10HZ; + freq[6] = BROADCAST_FREQ_0HZ; + freq[7] = BROADCAST_FREQ_0HZ; + freq[8] = BROADCAST_FREQ_1HZ; + freq[9] = BROADCAST_FREQ_10HZ; + freq[10] = BROADCAST_FREQ_50HZ; + freq[11] = BROADCAST_FREQ_100HZ; + freq[12] = BROADCAST_FREQ_50HZ; + freq[13] = BROADCAST_FREQ_10HZ; + } setBroadcastFreq(freq); } @@ -353,19 +392,37 @@ void CoreAPI::setBroadcastFreqToZero() uint8_t freq[16]; /* Channels definition: - * 0 - Timestamp - * 1 - Attitude Quaterniouns - * 2 - Acceleration - * 3 - Velocity (Ground Frame) - * 4 - Angular Velocity (Body Frame) - * 5 - Position - * 6 - Magnetometer - * 7 - RC Channels Data - * 8 - Gimbal Data - * 9 - Flight Status - * 10 - Battery Level - * 11 - Control Information - */ + * M100: + * 0 - Timestamp + * 1 - Attitude Quaterniouns + * 2 - Acceleration + * 3 - Velocity (Ground Frame) + * 4 - Angular Velocity (Body Frame) + * 5 - Position + * 6 - Magnetometer + * 7 - RC Channels Data + * 8 - Gimbal Data + * 9 - Flight Status + * 10 - Battery Level + * 11 - Control Information + * + * A3: + * 0 - Timestamp + * 1 - Attitude Quaterniouns + * 2 - Acceleration + * 3 - Velocity (Ground Frame) + * 4 - Angular Velocity (Body Frame) + * 5 - Position + * 6 - GPS Detailed Information + * 7 - RTK Detailed Information + * 8 - Magnetometer + * 9 - RC Channels Data + * 10 - Gimbal Data + * 11 - Flight Status + * 12 - Battery Level + * 13 - Control Information + * + */ freq[0] = BROADCAST_FREQ_0HZ; freq[1] = BROADCAST_FREQ_0HZ; @@ -379,7 +436,11 @@ 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; + } setBroadcastFreq(freq); } @@ -389,32 +450,68 @@ unsigned short CoreAPI::setBroadcastFreqDefaults(int timeout) uint8_t freq[16]; /* Channels definition: - * 0 - Timestamp - * 1 - Attitude Quaterniouns - * 2 - Acceleration - * 3 - Velocity (Ground Frame) - * 4 - Angular Velocity (Body Frame) - * 5 - Position - * 6 - Magnetometer - * 7 - RC Channels Data - * 8 - Gimbal Data - * 9 - Flight Status - * 10 - Battery Level - * 11 - Control Information - */ - - freq[0] = BROADCAST_FREQ_1HZ; - freq[1] = BROADCAST_FREQ_10HZ; - freq[2] = BROADCAST_FREQ_50HZ; - freq[3] = BROADCAST_FREQ_100HZ; - freq[4] = BROADCAST_FREQ_50HZ; - freq[5] = BROADCAST_FREQ_10HZ; - freq[6] = BROADCAST_FREQ_1HZ; - freq[7] = BROADCAST_FREQ_10HZ; - freq[8] = BROADCAST_FREQ_50HZ; - freq[9] = BROADCAST_FREQ_100HZ; - freq[10] = BROADCAST_FREQ_50HZ; - freq[11] = BROADCAST_FREQ_10HZ; + * M100: + * 0 - Timestamp + * 1 - Attitude Quaterniouns + * 2 - Acceleration + * 3 - Velocity (Ground Frame) + * 4 - Angular Velocity (Body Frame) + * 5 - Position + * 6 - Magnetometer + * 7 - RC Channels Data + * 8 - Gimbal Data + * 9 - Flight Status + * 10 - Battery Level + * 11 - Control Information + * + * A3: + * 0 - Timestamp + * 1 - Attitude Quaterniouns + * 2 - Acceleration + * 3 - Velocity (Ground Frame) + * 4 - Angular Velocity (Body Frame) + * 5 - Position + * 6 - GPS Detailed Information + * 7 - RTK Detailed Information + * 8 - Magnetometer + * 9 - RC Channels Data + * 10 - Gimbal Data + * 11 - Flight Status + * 12 - Battery Level + * 13 - Control Information + * + */ + + if (versionData.version == versionM100_31 || versionData.version == versionM100_23) { + freq[0] = BROADCAST_FREQ_1HZ; + freq[1] = BROADCAST_FREQ_10HZ; + freq[2] = BROADCAST_FREQ_50HZ; + freq[3] = BROADCAST_FREQ_100HZ; + freq[4] = BROADCAST_FREQ_50HZ; + freq[5] = BROADCAST_FREQ_10HZ; + freq[6] = BROADCAST_FREQ_1HZ; + freq[7] = BROADCAST_FREQ_10HZ; + freq[8] = BROADCAST_FREQ_50HZ; + freq[9] = BROADCAST_FREQ_100HZ; + freq[10] = BROADCAST_FREQ_50HZ; + freq[11] = BROADCAST_FREQ_10HZ; + } + else if (versionData.version == versionA3_31 || versionData.version == versionA3_32) { + freq[0] = BROADCAST_FREQ_1HZ; + freq[1] = BROADCAST_FREQ_10HZ; + freq[2] = BROADCAST_FREQ_50HZ; + freq[3] = BROADCAST_FREQ_100HZ; + freq[4] = BROADCAST_FREQ_50HZ; + freq[5] = BROADCAST_FREQ_10HZ; + freq[6] = BROADCAST_FREQ_0HZ; + freq[7] = BROADCAST_FREQ_0HZ; + freq[8] = BROADCAST_FREQ_1HZ; + freq[9] = BROADCAST_FREQ_10HZ; + freq[10] = BROADCAST_FREQ_50HZ; + freq[11] = BROADCAST_FREQ_100HZ; + freq[12] = BROADCAST_FREQ_50HZ; + freq[13] = BROADCAST_FREQ_10HZ; + } return setBroadcastFreq(freq, timeout); } @@ -456,6 +553,14 @@ unsigned short CoreAPI::setControl(bool enable, int timeout) serialDevice->wait(timeout); serialDevice->freeACK(); + if (missionACKUnion.simpleACK == ACK_SETCONTROL_ERROR_MODE) + { + if(versionData.version != versionA3_32) + missionACKUnion.simpleACK = ACK_SETCONTROL_NEED_MODE_F; + else + missionACKUnion.simpleACK = ACK_SETCONTROL_NEED_MODE_P; + } + return missionACKUnion.simpleACK; } @@ -468,23 +573,33 @@ 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); - - 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; + 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); } - memcpy(api->versionData.version_name, ptemp, 32); API_LOG(api->serialDevice, STATUS_LOG, "version ack = %d\n", api->versionData.version_ack); - 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->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); + } + API_LOG(api->serialDevice, STATUS_LOG, "version name = %.32s\n", api->versionData.version_name); } @@ -781,9 +896,15 @@ void CoreAPI::setControlCallback(CoreAPI *api, Header *protocolHeader, UserData switch (ack_data) { - case ACK_SETCONTROL_NEED_MODE_F: - API_LOG(api->serialDevice, STATUS_LOG, "Obtain control failed, conditions did not " - "satisfied"); + case ACK_SETCONTROL_ERROR_MODE: + if(api->versionData.version != versionA3_32) + { + 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"); + } break; case ACK_SETCONTROL_RELEASE_SUCCESS: API_LOG(api->serialDevice, STATUS_LOG, "Released control successfully\n"); diff --git a/dji_sdk_lib/src/DJI_App.cpp b/dji_sdk_lib/src/DJI_App.cpp index 44a202d3..b3dd2285 100644 --- a/dji_sdk_lib/src/DJI_App.cpp +++ b/dji_sdk_lib/src/DJI_App.cpp @@ -91,7 +91,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) + if (versionData.version == versionA3_31 || versionData.version == versionA3_32) { passData(*enableFlag, DATA_FLAG, &broadcastData.gps, pdata, sizeof(GPSData), len); passData(*enableFlag, DATA_FLAG, &broadcastData.rtk, pdata, sizeof(RTKData), len); diff --git a/dji_sdk_lib/src/DJI_Link.cpp b/dji_sdk_lib/src/DJI_Link.cpp index a527a73f..293a6e09 100644 --- a/dji_sdk_lib/src/DJI_Link.cpp +++ b/dji_sdk_lib/src/DJI_Link.cpp @@ -1,6 +1,6 @@ /** @file DJI_Link.cpp - * @version 3.1.7 - * @date July 1st, 2016 + * @version 3.1.9 + * @date November 10, 2016 * * @brief * Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library @@ -71,32 +71,36 @@ void CoreAPI::appHandler(Header *protocolHeader) data = CMDSessionTab[protocolHeader->sessionID].userData; freeSession(&CMDSessionTab[protocolHeader->sessionID]); serialDevice->freeMemory(); - if (callBack) { - //! Non-blocking callback thread - if (nonBlockingCBThreadEnable == true) { - notifyNonBlockingCaller(protocolHeader); - } else if (nonBlockingCBThreadEnable == false) { - callBack(this, protocolHeader, data); - } - } + if (callBack) + { + //! Non-blocking callback thread + if (nonBlockingCBThreadEnable == true) + { + notifyNonBlockingCaller(protocolHeader); + } + else if (nonBlockingCBThreadEnable == false) + { + callBack(this, protocolHeader, data); + } + } else { // Notify caller end of ACK frame arrived notifyCaller(protocolHeader); } - /** - * Set end of ACK frame - * @todo Implement proper notification mechanism - */ - // setACKFrameStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag); - + /** + * Set end of ACK frame + * @todo Implement proper notification mechanism + */ setACKFrameStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag); } else + { serialDevice->freeMemory(); - } + } + } } } else @@ -156,21 +160,27 @@ void CoreAPI::appHandler(Header *protocolHeader) } } -void CoreAPI::notifyCaller(Header *protocolHeader) -{ - serialDevice->lockACK(); +void CoreAPI::allocateACK(Header *protocolHeader) { + + const size_t MAX_ACK_SIZE = (versionData.version == versionM100_31) ? + M100_MAX_ACK_SIZE : A3_MAX_ACK_SIZE; - // In case of getDroneVersion? Should be only one case. - if(protocolHeader->length < 64) + if (protocolHeader->length <= MAX_ACK_SIZE) { memcpy(missionACKUnion.raw_ack_array, ((unsigned char *)protocolHeader) + sizeof(Header), - (protocolHeader->length - EXC_DATA_SIZE)); - } + (protocolHeader->length - EXC_DATA_SIZE)); + } else { - // Special case for getDroneVersion API call - version_ack_data = ((unsigned char *)protocolHeader) + sizeof(Header); + throw std::runtime_error("Unknown ACK"); } +} + +void CoreAPI::notifyCaller(Header *protocolHeader) +{ + serialDevice->lockACK(); + + allocateACK(protocolHeader); // Notify caller end of ACK frame arrived serialDevice->notify(); @@ -184,16 +194,8 @@ void CoreAPI::notifyNonBlockingCaller(Header *protocolHeader) //! This version of non-blocking can be limited in performance since the //! read thread waits for the callback thread to return before the read thread continues. - if(protocolHeader->length < 64) - { - memcpy(missionACKUnion.raw_ack_array, ((unsigned char *)protocolHeader) + sizeof(Header), - (protocolHeader->length - EXC_DATA_SIZE)); - } - else - { - //! Special case for getDroneVersion API call - version_ack_data = ((unsigned char *)protocolHeader) + sizeof(Header); - } + allocateACK(protocolHeader); + //! Copying protocol header to a global variable - will be passed to the Callback thread. //! protHeader is not thread safe and is passed to Callback for legacy purposes. //! Ack is available in the callback via MissionACKUnion. @@ -203,7 +205,6 @@ void CoreAPI::notifyNonBlockingCaller(Header *protocolHeader) serialDevice->lockProtocolHeader(); serialDevice->notifyNonBlockCBAckRecv(); serialDevice->freeProtocolHeader(); - } void CoreAPI::sendPoll() diff --git a/dji_sdk_lib/src/DJI_WayPoint.cpp b/dji_sdk_lib/src/DJI_WayPoint.cpp index 1a98fc71..8be9301b 100644 --- a/dji_sdk_lib/src/DJI_WayPoint.cpp +++ b/dji_sdk_lib/src/DJI_WayPoint.cpp @@ -154,7 +154,7 @@ WayPointDataACK WayPoint::uploadIndexData(WayPointData *data, int timeout) if (data->index < info.indexNumber) wpData = index[data->index]; else - std::runtime_error("Range error.\n"); + throw std::runtime_error("Range error\n"); api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_ADDPOINT, &wpData, sizeof(wpData), 1000, 4, 0, 0);