From ce66e1b32b235cd897e96fa7e8fa44e2fb3036e8 Mon Sep 17 00:00:00 2001
From: Arjun
Date: Fri, 5 Aug 2016 11:17:40 -0700
Subject: [PATCH 1/4] Mobile-OSDK comm support and bug fix release. For
specific changes refer to the release notes
https://developer.dji.com/onboard-sdk/documentation/appendix/releaseNotes.html.
Please see the documentation link to take a look at the new Mobile-OSDK
communication
https://developer.dji.com/onboard-sdk/documentation/quick-start/index.html.
This release is tagged 3.1.8
---
.../include/dji_sdk/DJI_HardDriver_Manifold.h | 85 ++-
dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h | 14 +
dji_sdk/include/dji_sdk/dji_drone.h | 318 ++++++++++
dji_sdk/include/dji_sdk/dji_sdk.h | 13 +
dji_sdk/include/dji_sdk/dji_sdk_mission.h | 11 +
dji_sdk/include/dji_sdk/dji_sdk_node.h | 12 +
dji_sdk/launch/sdk_manifold.launch | 6 +-
dji_sdk/src/dji_sdk_node.cpp | 11 +
dji_sdk/src/modules/dji_sdk_node_actions.cpp | 12 +
dji_sdk/src/modules/dji_sdk_node_main.cpp | 12 +
dji_sdk/src/modules/dji_sdk_node_mission.cpp | 13 +-
dji_sdk/src/modules/dji_sdk_node_services.cpp | 17 +-
dji_sdk_demo/src/client.cpp | 568 +++++++++++++++---
.../include/dji_sdk_lib/DJICommonType.h | 12 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_API.h | 325 +++++++---
dji_sdk_lib/include/dji_sdk_lib/DJI_App.h | 29 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Camera.h | 6 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Codec.h | 24 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h | 34 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h | 3 +
dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h | 8 +-
.../include/dji_sdk_lib/DJI_HardDriver.h | 33 +-
.../include/dji_sdk_lib/DJI_HotPoint.h | 60 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h | 27 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Memory.h | 11 +
dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h | 22 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h | 155 ++++-
dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h | 7 +-
.../include/dji_sdk_lib/DJI_VirtualRC.h | 7 +-
.../include/dji_sdk_lib/DJI_WayPoint.h | 102 +---
dji_sdk_lib/src/DJI_API.cpp | 359 ++++++++++-
dji_sdk_lib/src/DJI_App.cpp | 29 +-
dji_sdk_lib/src/DJI_Camera.cpp | 5 +-
dji_sdk_lib/src/DJI_Codec.cpp | 4 +-
dji_sdk_lib/src/DJI_Flight.cpp | 30 +-
dji_sdk_lib/src/DJI_Follow.cpp | 44 +-
dji_sdk_lib/src/DJI_HardDriver.cpp | 11 +
dji_sdk_lib/src/DJI_HotPoint.cpp | 113 +++-
dji_sdk_lib/src/DJI_Link.cpp | 50 +-
dji_sdk_lib/src/DJI_Memory.cpp | 27 +-
dji_sdk_lib/src/DJI_Mission.cpp | 8 +-
dji_sdk_lib/src/DJI_VirtualRC.cpp | 5 +-
dji_sdk_lib/src/DJI_WayPoint.cpp | 76 ++-
43 files changed, 2198 insertions(+), 520 deletions(-)
diff --git a/dji_sdk/include/dji_sdk/DJI_HardDriver_Manifold.h b/dji_sdk/include/dji_sdk/DJI_HardDriver_Manifold.h
index 1da52282..8cf14338 100644
--- a/dji_sdk/include/dji_sdk/DJI_HardDriver_Manifold.h
+++ b/dji_sdk/include/dji_sdk/DJI_HardDriver_Manifold.h
@@ -1,3 +1,15 @@
+/** @file DJI_HardDriver_Manifold.h
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * Hardware level driver code
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
+
#ifndef __DJI_HARDDRIVER_MANIFOLD_H__
#define __DJI_HARDDRIVER_MANIFOLD_H__
@@ -16,6 +28,8 @@
#include
#include
+#define BUFFER_SIZE 1024
+
namespace DJI {
namespace onboardSDK {
@@ -28,24 +42,46 @@ class HardDriver_Manifold : public HardDriver {
m_baudrate = baudrate;
m_memLock = PTHREAD_MUTEX_INITIALIZER;
m_msgLock = PTHREAD_MUTEX_INITIALIZER;
+ m_ackLock = PTHREAD_MUTEX_INITIALIZER;
+ pthread_cond_init (&ack_recv_cv, NULL);
}
~HardDriver_Manifold() {
_serialClose();
+ pthread_mutex_destroy(&m_memLock);
+ pthread_mutex_destroy(&m_msgLock);
+ pthread_mutex_destroy(&m_ackLock);
+ pthread_cond_destroy(&ack_recv_cv);
}
- void init() {
- API_LOG(this, STATUS_LOG, "going to open device %s with baudrate %u...\n",
+ void init()
+ {
+ API_LOG(this, STATUS_LOG, "Open serial device %s with baudrate %u...\n",
m_device.c_str(), m_baudrate);
- if( _serialStart(m_device.c_str(), m_baudrate) < 0 ) {
+ if( _serialStart(m_device.c_str(), m_baudrate) < 0 )
+ {
_serialClose();
- API_LOG(this, ERROR_LOG, "...fail to start serial\n");
- } else {
- API_LOG(this, STATUS_LOG, "...succeed to start serial\n");
+ API_LOG(this, ERROR_LOG, "Failed to start serial device\n");
+ deviceStatus = false;
}
- }
+
+ deviceStatus = true;
+/*
+ uint8_t buf[BUFFER_SIZE];
+ usleep(5000);
+
+ //! Check if serial connection valid
+ if(_serialRead(buf, BUFFER_SIZE) > 0)
+ {
+ API_LOG(this, STATUS_LOG, "Succeeded to read from serial device\n");
+ deviceStatus = true;
+ return;
+ }
+ API_LOG(this, ERROR_LOG, "Failed to read from serial device\n");
+ deviceStatus = false;
+*/ }
/**
@@ -69,6 +105,11 @@ class HardDriver_Manifold : public HardDriver {
}
+ bool getDevieStatus()
+ {
+ return deviceStatus;
+ }
+
time_ms getTimeStamp() {
#ifdef __MACH__
struct timeval now;
@@ -111,22 +152,50 @@ class HardDriver_Manifold : public HardDriver {
pthread_mutex_unlock(&m_msgLock);
}
+ void lockACK() {
+ pthread_mutex_lock(&m_ackLock);
+ }
+
+
+ void freeACK() {
+ pthread_mutex_unlock(&m_ackLock);
+ }
+
+ void notify() {
+ pthread_cond_signal(&ack_recv_cv);
+ }
+
+ void wait(int timeoutInSeconds){
+ struct timespec curTime, absTimeout;
+ //Use clock_gettime instead of getttimeofday for compatibility with POSIX APIs
+ clock_gettime(CLOCK_REALTIME, &curTime);
+ //absTimeout = curTime;
+ absTimeout.tv_sec = curTime.tv_sec + timeoutInSeconds;
+ absTimeout.tv_nsec = curTime.tv_nsec;
+ pthread_cond_timedwait(&ack_recv_cv, &m_ackLock, &absTimeout);
+ }
private:
std::string m_device;
unsigned int m_baudrate;
pthread_mutex_t m_memLock;
+
+ // Message synchronization data
+ pthread_mutex_t m_ackLock;
pthread_mutex_t m_msgLock;
+ pthread_cond_t ack_recv_cv;
int m_serial_fd;
fd_set m_serial_fd_set;
+ bool deviceStatus;
+
bool _serialOpen(const char* dev) {
// notice: use O_NONBLOCK to raise the frequency that read data from buffer
m_serial_fd = open(dev, O_RDWR | O_NONBLOCK);
if(m_serial_fd < 0) {
- API_LOG(this, ERROR_LOG, "cannot open device %s\n", dev);
+ API_LOG(this, ERROR_LOG, "Failed to open serial device %s\n", dev);
return false;
}
return true;
diff --git a/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h b/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h
index dda5e272..4cd776ea 100644
--- a/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h
+++ b/dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h
@@ -1,3 +1,13 @@
+/** @file DJI_LIB_ROS_Adapter.h
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * ROS Adapter to communicate with CoreAPI
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
#ifndef _DJI_LIB_ROS_ADAPTER_H_
#define _DJI_LIB_ROS_ADAPTER_H_
@@ -77,12 +87,14 @@ class ROSAdapter {
static void broadcastCallback(CoreAPI *coreAPI, Header *header, void *userData) {
( (ROSAdapter*)userData )->m_broadcastCallback();
+
}
static void fromMobileCallback(CoreAPI *coreAPI, Header *header, void *userData) {
uint8_t *data = ((unsigned char*) header) + sizeof(Header) + SET_CMD_SIZE;
uint8_t len = header->length - SET_CMD_SIZE - EXC_DATA_SIZE;
( (ROSAdapter*)userData )->m_fromMobileCallback(data, len);
+
}
static void missionStatusCallback(CoreAPI *coreAPI, Header *header, void *userData) {
@@ -139,12 +151,14 @@ class ROSAdapter {
void setBroadcastCallback( void (T::*func)(), T *obj ) {
m_broadcastCallback = std::bind(func, obj);
coreAPI->setBroadcastCallback(&ROSAdapter::broadcastCallback, (UserData)this);
+ printf("Broadcast call back received \n");
}
template
void setFromMobileCallback( void (T::*func)(uint8_t *, uint8_t), T *obj) {
m_fromMobileCallback = std::bind(func, obj, std::placeholders::_1, std::placeholders::_2);
coreAPI->setFromMobileCallback(&ROSAdapter::fromMobileCallback, (UserData)this);
+
}
template
diff --git a/dji_sdk/include/dji_sdk/dji_drone.h b/dji_sdk/include/dji_sdk/dji_drone.h
index 87f11b68..4b37b99f 100644
--- a/dji_sdk/include/dji_sdk/dji_drone.h
+++ b/dji_sdk/include/dji_sdk/dji_drone.h
@@ -1,3 +1,15 @@
+/** @file dji_drone.h
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * Contains client side ROS code. Including this header
+ * as a part of your project will allow your project to be used as a custom client.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
#include
#include
#include
@@ -52,6 +64,7 @@ class DJIDrone
ros::ServiceClient mission_hp_reset_yaw_service;
ros::ServiceClient mission_fm_upload_service;
ros::ServiceClient mission_fm_set_target_service;
+ //ros::ServiceClient mobile_commands_service;
ros::Subscriber acceleration_subscriber;
ros::Subscriber attitude_quaternion_subscriber;
@@ -70,6 +83,7 @@ class DJIDrone
ros::Subscriber time_stamp_subscriber;
ros::Subscriber mission_status_subscriber;
ros::Subscriber mission_event_subscriber;
+ ros::Subscriber mobile_data_subscriber;
public:
@@ -78,12 +92,14 @@ class DJIDrone
dji_sdk::Compass compass;
dji_sdk::FlightControlInfo flight_control_info;
uint8_t flight_status;
+ uint8_t mobile_new_data;
dji_sdk::Gimbal gimbal;
dji_sdk::GlobalPosition global_position;
dji_sdk::GlobalPosition global_position_ref;
dji_sdk::LocalPosition local_position;
dji_sdk::LocalPosition local_position_ref;
dji_sdk::PowerStatus power_status;
+ dji_sdk::TransparentTransmissionData mobile_data;
dji_sdk::RCChannels rc_channels;
dji_sdk::Velocity velocity;
nav_msgs::Odometry odometry;
@@ -104,6 +120,15 @@ class DJIDrone
dji_sdk::MissionEventWpAction waypoint_action_result;
dji_sdk::MissionEventWpReach waypoint_reached_result;
+typedef void *UserData;
+typedef void (*CallBack)(DJIDrone *);
+
+typedef struct CallBackHandler
+{
+ CallBack callback;
+ UserData userData;
+} CallBackHandler;
+
private:
void acceleration_subscriber_callback(dji_sdk::Acceleration acceleration)
{
@@ -212,6 +237,174 @@ class DJIDrone
}
+ //! Callback Handler functions for Mobile data commands
+ CallBackHandler obtainControlCallback;
+ CallBackHandler releaseControlCallback;
+ CallBackHandler takeOffCallback;
+ CallBackHandler landingCallback;
+ CallBackHandler getSDKVersionCallback;
+ CallBackHandler armCallback;
+ CallBackHandler disArmCallback;
+ CallBackHandler goHomeCallback;
+ CallBackHandler takePhotoCallback;
+ CallBackHandler startVideoCallback;
+ CallBackHandler stopVideoCallback;
+ CallBackHandler drawCircleDemoCallback;
+ CallBackHandler drawSquareDemoCallback;
+ CallBackHandler attitudeControlDemoCallback;
+ CallBackHandler waypointNavigationTestCallback;
+ CallBackHandler localNavigationTestCallback;
+ CallBackHandler globalNavigationTestCallback;
+ CallBackHandler virtualRCTestCallback;
+ CallBackHandler gimbalControlDemoCallback;
+
+ void mobile_data_push_info_callback(dji_sdk::TransparentTransmissionData information)
+ {
+ this->mobile_data = information;
+ mobile_new_data = 1;
+ int cmdID = mobile_data.data[0];
+ printf("Command ID code is %d \n", cmdID);
+
+ switch(cmdID)
+ {
+ case 2:
+ if (obtainControlCallback.callback)
+ {
+ obtainControlCallback.callback(this);
+ }
+ break;
+
+ case 3:
+ if (releaseControlCallback.callback)
+ {
+ releaseControlCallback.callback(this);
+ }
+ break;
+
+ case 4:
+ //if (obtainControlCallback.callback)
+ //{
+ // obtainControlCallback.callback();
+ //}
+ break;
+
+ case 5:
+ if (armCallback.callback)
+ {
+ armCallback.callback(this);
+ }
+ break;
+
+ case 6:
+ if (disArmCallback.callback)
+ {
+ disArmCallback.callback(this);
+ }
+ break;
+
+ case 7:
+ if (takeOffCallback.callback)
+ {
+ takeOffCallback.callback(this);
+ }
+ break;
+
+ case 8:
+ if (landingCallback.callback)
+ {
+ landingCallback.callback(this);
+ }
+ break;
+
+ case 9:
+ if (goHomeCallback.callback)
+ {
+ goHomeCallback.callback(this);
+ }
+ break;
+
+ case 10:
+ if (takePhotoCallback.callback)
+ {
+ takePhotoCallback.callback(this);
+ }
+ break;
+
+ case 11:
+ if (startVideoCallback.callback)
+ {
+ startVideoCallback.callback(this);
+ }
+ break;
+
+ case 13:
+ if (stopVideoCallback.callback)
+ {
+ stopVideoCallback.callback(this);
+ }
+ break;
+
+ case 61:
+ if (drawCircleDemoCallback.callback)
+ {
+ drawCircleDemoCallback.callback(this);
+ }
+ break;
+
+
+ case 62:
+ if (drawSquareDemoCallback.callback)
+ {
+ drawSquareDemoCallback.callback(this);
+ }
+ break;
+
+ case 63:
+ if (attitudeControlDemoCallback.callback)
+ {
+ attitudeControlDemoCallback.callback(this);
+ }
+ break;
+
+ case 64:
+ if (gimbalControlDemoCallback.callback)
+ {
+ gimbalControlDemoCallback.callback(this);
+ }
+ break;
+
+ case 65:
+ if (waypointNavigationTestCallback.callback)
+ {
+ waypointNavigationTestCallback.callback(this);
+ }
+ break;
+
+ case 66:
+ if (localNavigationTestCallback.callback)
+ {
+ localNavigationTestCallback.callback(this);
+ }
+ break;
+
+ case 67:
+ if (globalNavigationTestCallback.callback)
+ {
+ globalNavigationTestCallback.callback(this);
+ }
+ break;
+
+ case 68:
+ if (virtualRCTestCallback.callback)
+ {
+ virtualRCTestCallback.callback(this);
+ }
+ break;
+
+
+ }
+ }
+
void mission_event_push_info_callback(dji_sdk::MissionPushInfo event_push_info)
{
this->incident_type = event_push_info.type;
@@ -259,6 +452,7 @@ class DJIDrone
drone_arm_control_service = nh.serviceClient("dji_sdk/drone_arm_control");
sync_flag_control_service = nh.serviceClient("dji_sdk/sync_flag_control");
message_frequency_control_service = nh.serviceClient("dji_sdk/message_frequency_control");
+ //mobile_commands_service = nh.serviceClient("dji_sdk/mobile_commands");
mission_start_service = nh.serviceClient("dji_sdk/mission_start");
mission_pause_service = nh.serviceClient("dji_sdk/mission_pause");
@@ -291,8 +485,132 @@ class DJIDrone
time_stamp_subscriber = nh.subscribe("dji_sdk/time_stamp", 10, &DJIDrone::time_stamp_subscriber_callback,this);
mission_status_subscriber = nh.subscribe("dji_sdk/mission_status", 10, &DJIDrone::mission_status_push_info_callback, this);
mission_event_subscriber = nh.subscribe("dji_sdk/mission_event", 10, &DJIDrone::mission_event_push_info_callback, this);
+ mobile_data_subscriber = nh.subscribe("dji_sdk/data_received_from_remote_device", 10, &DJIDrone::mobile_data_push_info_callback, this);
+ }
+
+ void setObtainControlMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ obtainControlCallback.callback = userCallback;
+ obtainControlCallback.userData = userData;
+ }
+
+
+ void setReleaseControlMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ releaseControlCallback.callback = userCallback;
+ releaseControlCallback.userData = userData;
+ }
+
+ void setTakeOffMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ takeOffCallback.callback = userCallback;
+ takeOffCallback.userData = userData;
+ }
+
+
+ void setLandingMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ landingCallback.callback = userCallback;
+ landingCallback.userData = userData;
}
+
+ void setGetSDKVersionMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ getSDKVersionCallback.callback = userCallback;
+ getSDKVersionCallback.userData = userData;
+ }
+
+
+ void setArmMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ armCallback.callback = userCallback;
+ armCallback.userData = userData;
+ }
+
+ void setDisarmMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ disArmCallback.callback = userCallback;
+ disArmCallback.userData = userData;
+ }
+
+
+
+ void setGoHomeMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ goHomeCallback.callback = userCallback;
+ goHomeCallback.userData = userData;
+ }
+
+
+ void setTakePhotoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ takePhotoCallback.callback = userCallback;
+ takePhotoCallback.userData = userData;
+ }
+
+
+ void setStartVideoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ startVideoCallback.callback = userCallback;
+ startVideoCallback.userData = userData;
+ }
+
+
+ void setStopVideoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ stopVideoCallback.callback = userCallback;
+ stopVideoCallback.userData = userData;
+ }
+
+ void setDrawCircleDemoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ drawCircleDemoCallback.callback = userCallback;
+ drawCircleDemoCallback.userData = userData;
+ }
+
+ void setDrawSquareDemoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ drawSquareDemoCallback.callback = userCallback;
+ drawSquareDemoCallback.userData = userData;
+ }
+
+ void setAttitudeControlDemoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ attitudeControlDemoCallback.callback = userCallback;
+ attitudeControlDemoCallback.userData = userData;
+ }
+
+ void setLocalNavigationTestMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ localNavigationTestCallback.callback = userCallback;
+ localNavigationTestCallback.userData = userData;
+ }
+
+ void setGlobalNavigationTestMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ globalNavigationTestCallback.callback = userCallback;
+ globalNavigationTestCallback.userData = userData;
+ }
+
+ void setWaypointNavigationTestMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ waypointNavigationTestCallback.callback = userCallback;
+ waypointNavigationTestCallback.userData = userData;
+ }
+
+ void setVirtuaRCTestMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ virtualRCTestCallback.callback = userCallback;
+ virtualRCTestCallback.userData = userData;
+ }
+
+ void setGimbalControlDemoMobileCallback(DJIDrone::CallBack userCallback, UserData userData)
+ {
+ gimbalControlDemoCallback.callback = userCallback;
+ gimbalControlDemoCallback.userData = userData;
+ }
+
bool activate()
{
dji_sdk::Activation activate;
diff --git a/dji_sdk/include/dji_sdk/dji_sdk.h b/dji_sdk/include/dji_sdk/dji_sdk.h
index 3a94499f..7570f915 100644
--- a/dji_sdk/include/dji_sdk/dji_sdk.h
+++ b/dji_sdk/include/dji_sdk/dji_sdk.h
@@ -1,3 +1,16 @@
+/** @file dji_sdk.h
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * This file lists all functionalities as a part of
+ * the messages, services and actions in ROS.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
+
#ifndef SDK_LIBRARY_H
#define SDK_LIBRARY_H
diff --git a/dji_sdk/include/dji_sdk/dji_sdk_mission.h b/dji_sdk/include/dji_sdk/dji_sdk_mission.h
index 3ff8d3f2..fd754ce7 100644
--- a/dji_sdk/include/dji_sdk/dji_sdk_mission.h
+++ b/dji_sdk/include/dji_sdk/dji_sdk_mission.h
@@ -1,3 +1,14 @@
+/** @file dji_sdk_mission.h
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * Mission services are advertised here.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
#ifndef __DJI_MISSION_NODE_H__
#define __DJI_MISSION_NODE_H__
diff --git a/dji_sdk/include/dji_sdk/dji_sdk_node.h b/dji_sdk/include/dji_sdk/dji_sdk_node.h
index f51b70d5..b60c955a 100644
--- a/dji_sdk/include/dji_sdk/dji_sdk_node.h
+++ b/dji_sdk/include/dji_sdk/dji_sdk_node.h
@@ -1,3 +1,14 @@
+/** @file dji_sdk_node.h
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * Initializes all Publishers, Services and Actions
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
#ifndef __DJI_SDK_NODE_H__
#define __DJI_SDK_NODE_H__
@@ -14,6 +25,7 @@
#define DEG2RAD(DEG) ((DEG)*((C_PI)/(180.0)))
extern DJI::onboardSDK::ROSAdapter *rosAdapter;
+using namespace DJI::onboardSDK;
class DJISDKNode
{
diff --git a/dji_sdk/launch/sdk_manifold.launch b/dji_sdk/launch/sdk_manifold.launch
index b3ff37ef..98c23a47 100644
--- a/dji_sdk/launch/sdk_manifold.launch
+++ b/dji_sdk/launch/sdk_manifold.launch
@@ -2,12 +2,12 @@
-
+
-
+
-
+
diff --git a/dji_sdk/src/dji_sdk_node.cpp b/dji_sdk/src/dji_sdk_node.cpp
index acd1fb86..31a1e81d 100644
--- a/dji_sdk/src/dji_sdk_node.cpp
+++ b/dji_sdk/src/dji_sdk_node.cpp
@@ -1,3 +1,14 @@
+/** @file dji_sdk_node.cpp
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * Main function for ROS Node
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
#include
#include
#include
diff --git a/dji_sdk/src/modules/dji_sdk_node_actions.cpp b/dji_sdk/src/modules/dji_sdk_node_actions.cpp
index 6f836e83..71b732d8 100644
--- a/dji_sdk/src/modules/dji_sdk_node_actions.cpp
+++ b/dji_sdk/src/modules/dji_sdk_node_actions.cpp
@@ -1,3 +1,15 @@
+/** @file dji_sdk_node_actions.cpp
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * All the action callbacks are implemented here.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
+
#include
#include
diff --git a/dji_sdk/src/modules/dji_sdk_node_main.cpp b/dji_sdk/src/modules/dji_sdk_node_main.cpp
index 45ffed13..b3c59962 100644
--- a/dji_sdk/src/modules/dji_sdk_node_main.cpp
+++ b/dji_sdk/src/modules/dji_sdk_node_main.cpp
@@ -1,3 +1,15 @@
+/** @file dji_sdk_node_main.cpp
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * Broadcast and Mobile callbacks are implemented here.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
+
#include
#include
#include
diff --git a/dji_sdk/src/modules/dji_sdk_node_mission.cpp b/dji_sdk/src/modules/dji_sdk_node_mission.cpp
index 72d94726..872e7599 100644
--- a/dji_sdk/src/modules/dji_sdk_node_mission.cpp
+++ b/dji_sdk/src/modules/dji_sdk_node_mission.cpp
@@ -1,3 +1,14 @@
+/** @file dji_sdk_node_mission.cpp
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * All the mission callbacks are implemented here.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
#include
DJI::onboardSDK::HotPointData new_hotpoint = {0};
@@ -67,7 +78,7 @@ bool DJISDKMission::mission_start_callback(dji_sdk::MissionStart::Request& reque
new_follow.target.angle = 0; //unused param
new_follow.sensitivity = followme_task.sensitivity;
rosAdapter->followme->setData(new_follow);
- rosAdapter->followme->start();
+ rosAdapter->followme->start(0,0,0);
break;
diff --git a/dji_sdk/src/modules/dji_sdk_node_services.cpp b/dji_sdk/src/modules/dji_sdk_node_services.cpp
index b63417af..9c3e8779 100644
--- a/dji_sdk/src/modules/dji_sdk_node_services.cpp
+++ b/dji_sdk/src/modules/dji_sdk_node_services.cpp
@@ -1,9 +1,20 @@
+/** @file dji_sdk_node_services.cpp
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * All the purchase callbacks are implemented here.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
#include
bool DJISDKNode::activation_callback(dji_sdk::Activation::Request& request, dji_sdk::Activation::Response& response)
{
- rosAdapter->coreAPI->activate(&user_act_data, NULL);
+ rosAdapter->coreAPI->activate(&user_act_data);
response.result = true;
return true;
}
@@ -206,7 +217,9 @@ bool DJISDKNode::velocity_control_callback(dji_sdk::VelocityControl::Request& re
bool DJISDKNode::version_check_callback(dji_sdk::VersionCheck::Request& request, dji_sdk::VersionCheck::Response& response)
{
- rosAdapter->coreAPI->getSDKVersion();
+ int sdkVer;
+ sdkVer = rosAdapter->coreAPI->getSDKVersion();
+ std::cout << std::hex << sdkVer << '\n';
response.result = true;
return true;
}
diff --git a/dji_sdk_demo/src/client.cpp b/dji_sdk_demo/src/client.cpp
index 05c4ed94..4ac8ef39 100644
--- a/dji_sdk_demo/src/client.cpp
+++ b/dji_sdk_demo/src/client.cpp
@@ -1,3 +1,16 @@
+/** @file client.cpp
+ * @version 3.1.8
+ * @date July 29th, 2016
+ *
+ * @brief
+ * All the exampls for ROS are implemented here.
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
+
+
+
#include
#include
#include
@@ -7,35 +20,60 @@
using namespace DJI::onboardSDK;
+//! Function Prototypes for Mobile command callbacks - Core Functions
+void ObtainControlMobileCallback(DJIDrone *drone);
+void ReleaseControlMobileCallback(DJIDrone *drone);
+void TakeOffMobileCallback(DJIDrone *drone);
+void LandingMobileCallback(DJIDrone *drone);
+void GetSDKVersionMobileCallback(DJIDrone *drone);
+void ArmMobileCallback(DJIDrone *drone);
+void DisarmMobileCallback(DJIDrone *drone);
+void GoHomeMobileCallback(DJIDrone *drone);
+void TakePhotoMobileCallback(DJIDrone *drone);
+void StartVideoMobileCallback(DJIDrone *drone);
+void StopVideoMobileCallback(DJIDrone *drone);
+//! Function Prototypes for Mobile command callbacks - Custom Missions
+void DrawCircleDemoMobileCallback(DJIDrone *drone);
+void DrawSquareDemoMobileCallback(DJIDrone *drone);
+void GimbalControlDemoMobileCallback(DJIDrone *drone);
+void AttitudeControlDemoMobileCallback(DJIDrone *drone);
+void LocalNavigationTestMobileCallback(DJIDrone *drone);
+void GlobalNavigationTestMobileCallback(DJIDrone *drone);
+void WaypointNavigationTestMobileCallback(DJIDrone *drone);
+void VirtuaRCTestMobileCallback(DJIDrone *drone);
+
+
static void Display_Main_Menu(void)
{
printf("\r\n");
printf("+-------------------------- < Main menu > ------------------------+\n");
- printf("| [a] SDK Version Query | [s] Virtual RC Test |\n");
- printf("| [b] Request Control | [t] Set Sync Flag Test |\n");
- printf("| [c] Release Control | [u] Set Msg Frequency Test |\n");
- printf("| [d] Takeoff | [v] Waypoint Mission Upload |\n");
- printf("| [e] Landing | [w] Hotpoint Mission Upload |\n");
- printf("| [f] Go Home | [x] Followme Mission Upload |\n");
- printf("| [g] Gimbal Control Sample | [y] Mission Start |\n");
- printf("| [h] Attitude Control Sample | [z] Mission Pause |\n");
- printf("| [i] Draw Circle Sample | [1] Mission Resume |\n");
- printf("| [j] Draw Square Sample | [2] Mission Cancel |\n");
- printf("| [k] Take a Picture | [3] Mission Waypoint Download |\n");
- printf("| [l] Start Record Video | [4] Mission Waypoint Set Speed |\n");
- printf("| [m] Stop Record Video | [5] Mission Waypoint Get Speed |\n");
- printf("| [n] Local Navigation Test | [6] Mission Hotpoint Set Speed |\n");
- printf("| [o] Global Navigation Test | [7] Mission Hotpoint Set Radius |\n");
- printf("| [p] Waypoint Navigation Test | [8] Mission Hotpoint Reset Yaw |\n");
- printf("| [q] Arm the Drone | [9] Mission Followme Set Target |\n");
- printf("| [r] Disarm the Drone | [0] Mission Hotpoint Download |\n");
+ printf("| [1] SDK Version Query | [20] Set Sync Flag Test |\n");
+ printf("| [2] Request Control | [21] Set Msg Frequency Test |\n");
+ printf("| [3] Release Control | [22] Waypoint Mission Upload |\n");
+ printf("| [4] Takeoff | [23] Hotpoint Mission Upload |\n");
+ printf("| [5] Landing | [24] Followme Mission Upload |\n");
+ printf("| [6] Go Home | [25] Mission Start |\n");
+ printf("| [7] Gimbal Control Sample | [26] Mission Pause |\n");
+ printf("| [8] Attitude Control Sample | [27] Mission Resume |\n");
+ printf("| [9] Draw Circle Sample | [28] Mission Cancel |\n");
+ printf("| [10] Draw Square Sample | [29] Mission Waypoint Download |\n");
+ printf("| [11] Take a Picture | [30] Mission Waypoint Set Speed |\n");
+ printf("| [12] Start Record Video | [31] Mission Waypoint Get Speed |\n");
+ printf("| [13] Stop Record Video | [32] Mission Hotpoint Set Speed |\n");
+ printf("| [14] Local Navigation Test | [33] Mission Hotpoint Set Radius |\n");
+ printf("| [15] Global Navigation Test | [34] Mission Hotpoint Reset Yaw |\n");
+ printf("| [16] Waypoint Navigation Test | [35] Mission Followme Set Target |\n");
+ printf("| [17] Arm the Drone | [36] Mission Hotpoint Download |\n");
+ printf("| [18] Disarm the Drone | [37] Enter Mobile commands mode |\n");
+ printf("| [19] Virtual RC Test \n");
printf("+-----------------------------------------------------------------+\n");
printf("input a/b/c etc..then press enter key\r\n");
printf("use `rostopic echo` to query drone status\r\n");
printf("----------------------------------------\r\n");
- printf("input: ");
}
-int main(int argc, char **argv)
+
+
+int main(int argc, char *argv[])
{
int main_operate_code = 0;
int temp32;
@@ -69,62 +107,75 @@ int main(int argc, char **argv)
dji_sdk::MissionHotpointTask hotpoint_task;
dji_sdk::MissionFollowmeTask followme_task;
dji_sdk::MissionFollowmeTarget followme_target;
+ uint8_t userData = 0;
+ ros::spinOnce();
+
+ //! Setting functions to be called for Mobile App Commands mode
+ drone->setObtainControlMobileCallback(ObtainControlMobileCallback, &userData);
+ drone->setReleaseControlMobileCallback(ReleaseControlMobileCallback, &userData);
+ drone->setTakeOffMobileCallback(TakeOffMobileCallback, &userData);
+ drone->setLandingMobileCallback(LandingMobileCallback, &userData);
+ drone->setGetSDKVersionMobileCallback(GetSDKVersionMobileCallback, &userData);
+ drone->setArmMobileCallback(ArmMobileCallback, &userData);
+ drone->setDisarmMobileCallback(DisarmMobileCallback, &userData);
+ drone->setGoHomeMobileCallback(GoHomeMobileCallback, &userData);
+ drone->setTakePhotoMobileCallback(TakePhotoMobileCallback, &userData);
+ drone->setStartVideoMobileCallback(StartVideoMobileCallback,&userData);
+ drone->setStopVideoMobileCallback(StopVideoMobileCallback,&userData);
+ drone->setDrawCircleDemoMobileCallback(DrawCircleDemoMobileCallback, &userData);
+ drone->setDrawSquareDemoMobileCallback(DrawSquareDemoMobileCallback, &userData);
+ drone->setGimbalControlDemoMobileCallback(GimbalControlDemoMobileCallback, &userData);
+ drone->setAttitudeControlDemoMobileCallback(AttitudeControlDemoMobileCallback, &userData);
+ drone->setLocalNavigationTestMobileCallback(LocalNavigationTestMobileCallback, &userData);
+ drone->setGlobalNavigationTestMobileCallback(GlobalNavigationTestMobileCallback, &userData);
+ drone->setWaypointNavigationTestMobileCallback(WaypointNavigationTestMobileCallback, &userData);
+ drone->setVirtuaRCTestMobileCallback(VirtuaRCTestMobileCallback, &userData);
+
Display_Main_Menu();
while(1)
{
- ros::spinOnce();
- temp32 = getchar();
- if(temp32 != 10)
+ ros::spinOnce();
+ std::cout << "Enter Input Val: ";
+ std::cin >> temp32;
+
+ if(temp32>0 && temp32<38)
{
- if(valid_flag == false)
- {
- main_operate_code = temp32;
- valid_flag = true;
- }
- else
- {
- err_flag = true;
- }
- continue;
+ main_operate_code = temp32;
}
else
{
- if(err_flag == true)
- {
- printf("input: ERROR\n");
- Display_Main_Menu();
- err_flag = valid_flag = false;
- continue;
- }
+ printf("ERROR - Out of range Input \n");
+ Display_Main_Menu();
+ continue;
}
switch(main_operate_code)
{
- case 'a':
+ case 1:
/* SDK version query*/
drone->check_version();
break;
- case 'b':
+ case 2:
/* request control ability*/
drone->request_sdk_permission_control();
break;
- case 'c':
+ case 3:
/* release control ability*/
drone->release_sdk_permission_control();
break;
- case 'd':
+ case 4:
/* take off */
drone->takeoff();
break;
- case 'e':
+ case 5:
/* landing*/
drone->landing();
break;
- case 'f':
+ case 6:
/* go home*/
drone->gohome();
break;
- case 'g':
+ case 7:
/*gimbal test*/
drone->gimbal_angle_control(0, 0, 1800, 20);
@@ -154,7 +205,7 @@ int main(int argc, char **argv)
drone->gimbal_angle_control(0, 0, 0, 20);
break;
- case 'h':
+ case 8:
/* attitude control sample*/
drone->takeoff();
sleep(8);
@@ -254,7 +305,7 @@ int main(int argc, char **argv)
break;
- case 'i':
+ case 9:
/*draw circle sample*/
static float R = 2;
static float V = 2;
@@ -288,21 +339,20 @@ int main(int argc, char **argv)
y_center = drone->local_position.y;
circleRadiusIncrements = 0.01;
- for(int j = 0; j < 1000; j ++)
+ for(int j = 0; j < 1000; j ++)
{
- if (circleRadiusIncrements < circleRadius)
- {
- x = x_center + circleRadiusIncrements;
- y = y_center;
- circleRadiusIncrements = circleRadiusIncrements + 0.01;
- //printf("%f \n",circleRadiusIncrements);
- drone->local_position_control(x ,y ,circleHeight, 0);
- usleep(20000);
- }
- else
- {
- break;
- }
+ if (circleRadiusIncrements < circleRadius)
+ {
+ x = x_center + circleRadiusIncrements;
+ y = y_center;
+ circleRadiusIncrements = circleRadiusIncrements + 0.01;
+ drone->local_position_control(x ,y ,circleHeight, 0);
+ usleep(20000);
+ }
+ else
+ {
+ break;
+ }
}
/* start to draw circle */
@@ -316,7 +366,7 @@ int main(int argc, char **argv)
}
break;
- case 'j':
+ case 10:
/*draw square sample*/
for(int i = 0;i < 60;i++)
{
@@ -359,27 +409,27 @@ int main(int argc, char **argv)
usleep(20000);
}
break;
- case 'k':
+ case 11:
/*take a picture*/
drone->take_picture();
break;
- case 'l':
+ case 12:
/*start video*/
drone->start_video();
break;
- case 'm':
+ case 13:
/*stop video*/
drone->stop_video();
break;
- case 'n':
+ case 14:
/* Local Navi Test */
drone->local_position_navigation_send_request(-100, -100, 100);
break;
- case 'o':
+ case 15:
/* GPS Navi Test */
- drone->global_position_navigation_send_request(22.535, 113.95, 100);
+ drone->global_position_navigation_send_request(22.5420, 113.9580, 10);
break;
- case 'p':
+ case 16:
/* Waypoint List Navi Test */
{
waypoint0.latitude = 22.535;
@@ -428,15 +478,15 @@ int main(int argc, char **argv)
drone->waypoint_navigation_send_request(newWaypointList);
break;
- case 'q':
+ case 17:
//drone arm
drone->drone_arm();
break;
- case 'r':
+ case 18:
//drone disarm
drone->drone_disarm();
break;
- case 's':
+ case 19:
//virtual rc test 1: arm & disarm
drone->virtual_rc_enable();
usleep(20000);
@@ -468,16 +518,16 @@ int main(int argc, char **argv)
}
drone->virtual_rc_disable();
break;
- case 't':
+ case 20:
//sync flag
drone->sync_flag_control(1);
break;
- case 'u':
+ case 21:
//set msg frequency
drone->set_message_frequency(msg_frequency_data);
break;
- case 'v':
+ case 22:
// Clear the vector of previous waypoints
waypoint_task.mission_waypoint.clear();
@@ -547,10 +597,10 @@ int main(int argc, char **argv)
drone->mission_waypoint_upload(waypoint_task);
break;
- case 'w':
+ case 23:
//mission hotpoint upload
- hotpoint_task.latitude = 22.540091;
- hotpoint_task.longitude = 113.946593;
+ hotpoint_task.latitude = 22.542813;
+ hotpoint_task.longitude = 113.958902;
hotpoint_task.altitude = 20;
hotpoint_task.radius = 10;
hotpoint_task.angular_speed = 10;
@@ -560,7 +610,7 @@ int main(int argc, char **argv)
drone->mission_hotpoint_upload(hotpoint_task);
break;
- case 'x':
+ case 24:
//mission followme upload
followme_task.mode = 0;
followme_task.yaw_mode = 0;
@@ -571,47 +621,47 @@ int main(int argc, char **argv)
drone->mission_followme_upload(followme_task);
break;
- case 'y':
+ case 25:
//mission start
drone->mission_start();
break;
- case 'z':
+ case 26:
//mission pause
drone->mission_pause();
break;
- case '1':
+ case 27:
//mission resume
drone->mission_resume();
break;
- case '2':
+ case 28:
//mission cancel
drone->mission_cancel();
break;
- case '3':
+ case 29:
//waypoint mission download
waypoint_task = drone->mission_waypoint_download();
break;
- case '4':
+ case 30:
//mission waypoint set speed
drone->mission_waypoint_set_speed((float)5);
break;
- case '5':
+ case 31:
//mission waypoint get speed
printf("%f", drone->mission_waypoint_get_speed());
break;
- case '6':
+ case 32:
//mission hotpoint set speed
drone->mission_hotpoint_set_speed((float)5,(uint8_t)1);
break;
- case '7':
+ case 33:
//mission hotpoint set radius
drone->mission_hotpoint_set_radius((float)5);
break;
- case '8':
+ case 34:
//mission hotpoint reset yaw
drone->mission_hotpoint_reset_yaw();
break;
- case '9':
+ case 35:
//mission followme update target
for (int i = 0; i < 20; i++)
{
@@ -622,15 +672,345 @@ int main(int argc, char **argv)
usleep(20000);
}
break;
- case '0':
+ case 37:
+ printf("Mobile Data Commands mode entered. Use OSDK Mobile App to use this feature \n");
+ printf("End program to exit this mode \n");
+ while(1)
+ {
+ ros::spinOnce();
+ }
+ case 36:
hotpoint_task = drone->mission_hotpoint_download();
default:
break;
}
main_operate_code = -1;
- err_flag = valid_flag = false;
Display_Main_Menu();
}
return 0;
}
+
+//! Callback functions for Mobile Commands
+ void ObtainControlMobileCallback(DJIDrone *drone)
+ {
+ drone->request_sdk_permission_control();
+ }
+
+ void ReleaseControlMobileCallback(DJIDrone *drone)
+ {
+ drone->release_sdk_permission_control();
+ }
+
+ void TakeOffMobileCallback(DJIDrone *drone)
+ {
+ drone->takeoff();
+ }
+
+ void LandingMobileCallback(DJIDrone *drone)
+ {
+ drone->landing();
+ }
+
+ void GetSDKVersionMobileCallback(DJIDrone *drone)
+ {
+ drone->check_version();
+ }
+
+ void ArmMobileCallback(DJIDrone *drone)
+ {
+ drone->drone_arm();
+ }
+
+ void DisarmMobileCallback(DJIDrone *drone)
+ {
+ drone->drone_disarm();
+ }
+
+ void GoHomeMobileCallback(DJIDrone *drone)
+ {
+ drone->gohome();
+ }
+
+ void TakePhotoMobileCallback(DJIDrone *drone)
+ {
+ drone->take_picture();
+ }
+
+ void StartVideoMobileCallback(DJIDrone *drone)
+ {
+ drone->start_video();
+ }
+
+ void StopVideoMobileCallback(DJIDrone *drone)
+ {
+ drone->stop_video();
+ }
+
+ void DrawCircleDemoMobileCallback(DJIDrone *drone)
+ {
+ static float R = 2;
+ static float V = 2;
+ static float x;
+ static float y;
+ int circleRadius;
+ int circleHeight;
+ float Phi =0, circleRadiusIncrements;
+ int x_center, y_center, yaw_local;
+
+ circleHeight = 7;
+ circleRadius = 7;
+
+ x_center = drone->local_position.x;
+ y_center = drone->local_position.y;
+ circleRadiusIncrements = 0.01;
+
+ for(int j = 0; j < 1000; j ++)
+ {
+ if (circleRadiusIncrements < circleRadius)
+ {
+ x = x_center + circleRadiusIncrements;
+ y = y_center;
+ circleRadiusIncrements = circleRadiusIncrements + 0.01;
+ drone->local_position_control(x ,y ,circleHeight, 0);
+ usleep(20000);
+ }
+ else
+ {
+ break;
+ }
+ }
+
+
+ /* start to draw circle */
+ for(int i = 0; i < 1890; i ++)
+ {
+ x = x_center + circleRadius*cos((Phi/300));
+ y = y_center + circleRadius*sin((Phi/300));
+ Phi = Phi+1;
+ drone->local_position_control(x ,y ,circleHeight, 0);
+ usleep(20000);
+ }
+
+ }
+ void DrawSquareDemoMobileCallback(DJIDrone *drone)
+ {
+ /*draw square sample*/
+ for(int i = 0;i < 60;i++)
+ {
+ drone->attitude_control( Flight::HorizontalLogic::HORIZONTAL_POSITION |
+ Flight::VerticalLogic::VERTICAL_VELOCITY |
+ Flight::YawLogic::YAW_ANGLE |
+ Flight::HorizontalCoordinate::HORIZONTAL_BODY |
+ Flight::SmoothMode::SMOOTH_ENABLE,
+ 3, 3, 0, 0 );
+ usleep(20000);
+ }
+ for(int i = 0;i < 60;i++)
+ {
+ drone->attitude_control( Flight::HorizontalLogic::HORIZONTAL_POSITION |
+ Flight::VerticalLogic::VERTICAL_VELOCITY |
+ Flight::YawLogic::YAW_ANGLE |
+ Flight::HorizontalCoordinate::HORIZONTAL_BODY |
+ Flight::SmoothMode::SMOOTH_ENABLE,
+ -3, 3, 0, 0);
+ usleep(20000);
+ }
+ for(int i = 0;i < 60;i++)
+ {
+ drone->attitude_control( Flight::HorizontalLogic::HORIZONTAL_POSITION |
+ Flight::VerticalLogic::VERTICAL_VELOCITY |
+ Flight::YawLogic::YAW_ANGLE |
+ Flight::HorizontalCoordinate::HORIZONTAL_BODY |
+ Flight::SmoothMode::SMOOTH_ENABLE,
+ -3, -3, 0, 0);
+ usleep(20000);
+ }
+ for(int i = 0;i < 60;i++)
+ {
+ drone->attitude_control( Flight::HorizontalLogic::HORIZONTAL_POSITION |
+ Flight::VerticalLogic::VERTICAL_VELOCITY |
+ Flight::YawLogic::YAW_ANGLE |
+ Flight::HorizontalCoordinate::HORIZONTAL_BODY |
+ Flight::SmoothMode::SMOOTH_ENABLE,
+ 3, -3, 0, 0);
+ usleep(20000);
+ }
+ }
+
+ void GimbalControlDemoMobileCallback(DJIDrone *drone)
+ {
+ drone->gimbal_angle_control(0, 0, 1800, 20);
+ sleep(2);
+ drone->gimbal_angle_control(0, 0, -1800, 20);
+ sleep(2);
+ drone->gimbal_angle_control(300, 0, 0, 20);
+ sleep(2);
+ drone->gimbal_angle_control(-300, 0, 0, 20);
+ sleep(2);
+ drone->gimbal_angle_control(0, 300, 0, 20);
+ sleep(2);
+ drone->gimbal_angle_control(0, -300, 0, 20);
+ sleep(2);
+ drone->gimbal_speed_control(100, 0, 0);
+ sleep(2);
+ drone->gimbal_speed_control(-100, 0, 0);
+ sleep(2);
+ drone->gimbal_speed_control(0, 0, 200);
+ sleep(2);
+ drone->gimbal_speed_control(0, 0, -200);
+ sleep(2);
+ drone->gimbal_speed_control(0, 200, 0);
+ sleep(2);
+ drone->gimbal_speed_control(0, -200, 0);
+ sleep(2);
+ drone->gimbal_angle_control(0, 0, 0, 20);
+ }
+
+ void AttitudeControlDemoMobileCallback(DJIDrone *drone)
+ {
+ /* attitude control sample*/
+ drone->takeoff();
+ sleep(8);
+
+
+ for(int i = 0; i < 100; i ++)
+ {
+ if(i < 90)
+ drone->attitude_control(0x40, 0, 2, 0, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0x40, 2, 0, 0, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0x40, -2, 0, 0, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0x40, 0, 2, 0, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0x40, 0, -2, 0, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0x40, 0, 0, 0.5, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0x40, 0, 0, -0.5, 0);
+ else
+ drone->attitude_control(0x40, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0xA, 0, 0, 0, 90);
+ else
+ drone->attitude_control(0xA, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ for(int i = 0; i < 200; i ++)
+ {
+ if(i < 180)
+ drone->attitude_control(0xA, 0, 0, 0, -90);
+ else
+ drone->attitude_control(0xA, 0, 0, 0, 0);
+ usleep(20000);
+ }
+ sleep(1);
+
+ drone->landing();
+
+ }
+ void LocalNavigationTestMobileCallback(DJIDrone *drone)
+ {
+
+ }
+ void GlobalNavigationTestMobileCallback(DJIDrone *drone)
+ {
+
+ }
+ void WaypointNavigationTestMobileCallback(DJIDrone *drone)
+ {
+
+ }
+ void VirtuaRCTestMobileCallback(DJIDrone *drone)
+ {
+ //virtual RC test data
+ uint32_t virtual_rc_data[16];
+ //virtual rc test 1: arm & disarm
+ drone->virtual_rc_enable();
+ usleep(20000);
+
+ virtual_rc_data[0] = 1024; //0-> roll [1024-660,1024+660]
+ virtual_rc_data[1] = 1024; //1-> pitch [1024-660,1024+660]
+ virtual_rc_data[2] = 1024+660; //2-> throttle [1024-660,1024+660]
+ virtual_rc_data[3] = 1024; //3-> yaw [1024-660,1024+660]
+ virtual_rc_data[4] = 1684; //4-> gear {1684(UP), 1324(DOWN)}
+ virtual_rc_data[6] = 1552; //6-> mode {1552(P), 1024(A), 496(F)}
+
+ for (int i = 0; i < 100; i++){
+ drone->virtual_rc_control(virtual_rc_data);
+ usleep(20000);
+ }
+
+ //virtual rc test 2: yaw
+ drone->virtual_rc_enable();
+ virtual_rc_data[0] = 1024; //0-> roll [1024-660,1024+660]
+ virtual_rc_data[1] = 1024; //1-> pitch [1024-660,1024+660]
+ virtual_rc_data[2] = 1024-200; //2-> throttle [1024-660,1024+660]
+ virtual_rc_data[3] = 1024; //3-> yaw [1024-660,1024+660]
+ virtual_rc_data[4] = 1324; //4-> gear {1684(UP), 1324(DOWN)}
+ virtual_rc_data[6] = 1552; //6-> mode {1552(P), 1024(A), 496(F)}
+
+ for(int i = 0; i < 100; i++) {
+ drone->virtual_rc_control(virtual_rc_data);
+ usleep(20000);
+ }
+ drone->virtual_rc_disable();
+ }
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJICommonType.h b/dji_sdk_lib/include/dji_sdk_lib/DJICommonType.h
index 1cf30e2f..11d2d2be 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJICommonType.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJICommonType.h
@@ -1,10 +1,9 @@
-/*! @brief
- * @file DJICommonType.h
+/*! @file DJICommonType.h
* @version 3.1.7
* @date Jul 01 2016
*
- * @abstract
- * Common Type definition for DJI onboardSDK library
+ * @brief
+ * Common Type definition for DJI onboardSDK library.
* Officially Maintained
*
* @copyright
@@ -13,7 +12,7 @@
/*! @attention
* Do not modify any definition in this file
- * if you are not sure what are you doing.
+ * if you are unsure of what are you doing.
* DJI will not provide any support for changes made to this file.
* */
@@ -28,7 +27,8 @@ namespace DJI
typedef uint64_t time_ms;
typedef uint64_t time_us; // about 0.3 million years
-typedef void *UserData; //! This is used as the datatype for all data arguments in callbacks.
+//! This is used as the datatype for all data arguments in callbacks.
+typedef void *UserData;
typedef uint32_t Flag;
typedef uint8_t size8_t;
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 0ddb6a26..88669fc0 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
@@ -8,15 +8,17 @@
* @copyright 2016 DJI. All rights reserved.
*
*/
-
+
+// The comment block below is made for doxygen.
+
/*! @mainpage
- * This is the officially maintained DJI Onboard SDK library. The library provides a set of APIs for implementing the various functionality available through the [open protocol](https://developer.dji.com/onboard-sdk/documentation/introduction/index.html).
+ * This is the officially maintained DJI Onboard SDK library. The library provides a set of APIs for implementing the various functionality available through the [open protocol](https://developer.dji.com/onboard-sdk/documentation/introduction/index.html).
*
* @section intro_sec Introduction
*
- * API class documentation is available here. Click on the Files/Classes/Namespaces tabs above to see more information about the library. \n
+ * API class documentation is available here. Click on the Files/Classes/Namespaces tabs above to see more information about the library. \n
* Documentation for the SDK has moved to the [DJI Developer Website](https://developer.dji.com/onboard-sdk/documentation/).
- * Please refer to the [Programming Guide](https://developer.dji.com/onboard-sdk/documentation/application-development-guides/programming-guide.html)
+ * Please refer to the [Programming Guide](https://developer.dji.com/onboard-sdk/documentation/application-development-guides/programming-guide.html)
* for more information.
*
*/
@@ -40,6 +42,12 @@ class HotPoint;
//! @todo sort enum and move to a new file
+enum ACK_ERROR_CODE
+{
+ ACK_SUCCESS = 0x0000,
+ ACK_PARAM_ERROR = 0x0001
+};
+
enum ACK_COMMON_CODE
{
ACK_COMMON_SUCCESS = 0x0000,
@@ -81,6 +89,13 @@ enum ACK_ARM_CODE
ACK_ARM_IN_AIR = 0x0003,
};
+enum TASK_ACK_CODE
+{
+ TASK_FAILURE = 0x01,
+ TASK_SUCCESS = 0x02
+};
+
+
//! @note end of ACKs
enum CMD_SET
@@ -195,6 +210,10 @@ enum BROADCAST_FREQ
class CoreAPI
{
public:
+ CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false,
+ CallBack userRecvCallback = 0, UserData userData = 0);
+ CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback,
+ bool userCallbackThread = false);
void sendPoll(void);
void readPoll(void);
//! @todo Implement callback poll handler
@@ -205,14 +224,11 @@ class CoreAPI
//! @todo Implement stream handler
void byteStreamHandler(uint8_t *buffer, size_t size);
- public:
- CoreAPI(HardDriver *Driver = 0, Version SDKVersion = 0, bool userCallbackThread = false,
- CallBack userRecvCallback = 0, UserData userData = 0);
- CoreAPI(HardDriver *Driver, Version SDKVersion, CallBackHandler userRecvCallback,
- bool userCallbackThread = false);
-
void ack(req_id_t req_id, unsigned char *ackdata, int len);
+ //! Notify caller ACK frame arrived
+ void notifyCaller(Header *protocolHeader);
+
//@{
/**
* @remark
@@ -247,8 +263,42 @@ class CoreAPI
* Proceed to programming if activation successful.
*/
void activate(ActivateData *data, CallBack callback = 0, UserData userData = 0);
+
+ /// Blocking API Control
+ /**
+ * @remark
+ * Blocks until ACK frame arrives or timeout occurs
+ *
+ * @brief
+ * Send activation control to your flight controller to check if: \n a)
+ * your application registered in your developer
+ * account \n b) API Control enabled in the Assistant software\n\n
+ * Proceed to programming if activation successful.
+ *
+ * @return ACK from flight controller
+ *
+ * @todo
+ * Implement high resolution timer to catch ACK timeout
+ */
+ unsigned short activate(ActivateData *data, int timeout);
+
void setControl(bool enable, CallBack callback = 0, UserData userData = 0);
+ /// Blocking API Control
+ /**
+ * @remark
+ * Blocks until ACK frame arrives or timeout occurs
+ *
+ * @brief
+ * Obtain control
+ *
+ * @return ACK from flight controller
+ *
+ * @todo
+ * Implement high resolution timer to catch ACK timeout
+ */
+ unsigned short setControl(bool enable, int timeout);
+
/// Activation Control
/**
* @brief
@@ -287,8 +337,40 @@ class CoreAPI
* 11 - Control Information\n
*/
void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback = 0, UserData userData = 0);
- void setSessionStatus(uint32_t usageFlag);
- uint32_t getSessionStatus();
+ unsigned short setBroadcastFreq(uint8_t *dataLenIs16, int timeout);
+
+ /**
+ * Reset all broadcast frequencies to their default values
+ */
+ void setBroadcastFreqDefaults();
+
+ /**
+ * Blocking API Control
+ *
+ * @brief
+ * Set broadcast frequencies to their default values and block until
+ * ACK arrives from flight controller
+ *
+ * @return ACK from flight controller
+ *
+ * @todo
+ * Implement high resolution timer to catch ACK timeout
+ */
+ unsigned short setBroadcastFreqDefaults(int timeout);
+
+ /*
+ * Set all broadcast frequencies to zero. Only ACK data will stay on the line.
+ */
+ void setBroadcastFreqToZero();
+
+ /**
+ * Let user know when ACK and Broadcast messages processed
+ */
+ void setACKFrameStatus(uint32_t usageFlag);
+ uint32_t getACKFrameStatus();
+ void setBroadcastFrameStatus(bool isFrame);
+ bool getBroadcastFrameStatus();
+
void setSyncFreq(uint32_t freqInHz);
void setKey(const char *key);
@@ -301,6 +383,21 @@ class CoreAPI
*/
void getDroneVersion(CallBack callback = 0, UserData userData = 0);
+ /**
+ * Blocking API Control
+ *
+ * @brief
+ * Get drone version from flight controller block until
+ * ACK arrives from flight controller
+ *
+ * @return VersionData containing ACK value, CRC of the
+ * protocol version and protocol version itself
+ *
+ * @todo
+ * Implement high resolution timer to catch ACK timeout
+ */
+ VersionData getDroneVersion(int timeout);
+
/**Get broadcasted data values from flight controller.*/
BroadcastData getBroadcastData() const;
@@ -340,7 +437,6 @@ class CoreAPI
* Get SDK version
*/
Version getSDKVersion() const;
- public:
void setBroadcastCallback(CallBackHandler callback) { broadcastCallback = callback; }
void setFromMobileCallback(CallBackHandler FromMobileEntrance);
@@ -366,16 +462,128 @@ class CoreAPI
static void sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
static void setFrequencyCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
- private:
- BroadcastData broadcastData;
- uint32_t sessionStatus;
+ /**
+ * MOS Protocol parsing lirbary functions.
+ */
+
+ /**
+ * Default MOS Protocol Parser. Calls other callback functions based on data
+ */
+ void parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData = 0);
+
+ /**
+ * Mobile Callback handler functions
+ */
+ void setObtainControlMobileCallback(CallBackHandler callback) {obtainControlMobileCallback = callback;}
+ void setReleaseControlMobileCallback(CallBackHandler callback) {releaseControlMobileCallback = callback;}
+ void setActivateMobileCallback(CallBackHandler callback) {activateMobileCallback = callback;}
+ void setArmMobileCallback(CallBackHandler callback) {armMobileCallback = callback;}
+ void setDisArmMobileCallback(CallBackHandler callback) {disArmMobileCallback = callback;}
+ void setTakeOffMobileCallback(CallBackHandler callback) {takeOffMobileCallback = callback;}
+ void setLandingMobileCallback(CallBackHandler callback) {landingMobileCallback = callback;}
+ void setGoHomeMobileCallback(CallBackHandler callback) {goHomeMobileCallback = callback;}
+ void setTakePhotoMobileCallback(CallBackHandler callback) {takePhotoMobileCallback = callback;}
+ void setStartVideoMobileCallback(CallBackHandler callback) {startVideoMobileCallback = callback;}
+ void setStopVideoMobileCallback(CallBackHandler callback) {stopVideoMobileCallback = callback;}
+
+ /**
+ * ACK decoder.
+ */
+ bool decodeACKStatus(unsigned short ack);
+
+ /**
+ * Flight mission decoder.
+ */
+ bool decodeMissionStatus(uint8_t ack);
+
+ /**
+ *@note Thread data
+ */
+ bool stopCond;
+
+ /**
+ *@note Thread data
+ */
+
+ uint32_t ack_data;
+ HotPointReadACK hotpointReadACK;
+ WayPointInitACK waypointInitACK;
+ MissionACKUnion missionACKUnion;
+
+ /// Open Protocol Control
+ /**
+ * Get Open Protocol packet information.
+ */
+ SDKFilter getFilter() const;
+
+ /// HotPoint Mission Control
+ bool getHotPointData() const;
+
+ /// WayPoint Mission Control
+ bool getWayPointData() const;
+
+ // FollowMe mission Control
+ bool getFollowData() const;
+
+ /// HotPoint Mission Control
+ void setHotPointData(bool value);
+
+ /// WayPoint Mission Control
+ void setWayPointData(bool value);
+
+ /// Follow Me Mission Control
+ void setFollowData(bool value);
+
+ /**
+ * Initialize serial device
+ */
+ void setDriver(HardDriver *value);
+
+ /**
+ * Set SDK version.
+ */
+ void setVersion(const Version &value);
+
+ /**
+ * Setters and getters for Mobile CMD variables
+ */
+ bool getObtainControlMobileCMD() {return obtainControlMobileCMD;}
+ bool getReleaseControlMobileCMD() {return releaseControlMobileCMD;}
+ bool getActivateMobileCMD() {return activateMobileCMD;}
+ bool getArmMobileCMD() {return armMobileCMD;}
+ bool getDisArmMobileCMD() {return disArmMobileCMD;}
+ bool getTakeOffMobileCMD() {return takeOffMobileCMD;}
+ bool getLandingMobileCMD() {return landingMobileCMD;}
+ bool getGoHomeMobileCMD() {return goHomeMobileCMD;}
+ bool getTakePhotoMobileCMD() {return takePhotoMobileCMD;}
+ bool getStartVideoMobileCMD() {return startVideoMobileCMD;}
+ bool getStopVideoMobileCMD() {return stopVideoMobileCMD;}
+ bool getFollowMeMobileCMD() {return followMeMobileCMD;}
+
+ void setObtainControlMobileCMD(bool userInput) {obtainControlMobileCMD = userInput;}
+ void setReleaseControlMobileCMD(bool userInput) {releaseControlMobileCMD= userInput;}
+ void setActivateMobileCMD(bool userInput) {activateMobileCMD= userInput;}
+ void setArmMobileCMD(bool userInput) {armMobileCMD= userInput;}
+ void setDisArmMobileCMD(bool userInput) {disArmMobileCMD= userInput;}
+ void setTakeOffMobileCMD(bool userInput) {takeOffMobileCMD= userInput;}
+ void setLandingMobileCMD(bool userInput) {landingMobileCMD= userInput;}
+ void setGoHomeMobileCMD(bool userInput) {goHomeMobileCMD= userInput;}
+ void setTakePhotoMobileCMD(bool userInput) {takePhotoMobileCMD= userInput;}
+ void setStartVideoMobileCMD(bool userInput) {startVideoMobileCMD= userInput;}
+ void setStopVideoMobileCMD(bool userInput) {stopVideoMobileCMD= userInput;}
+ void setFollowMeMobileCMD(bool userInput) {followMeMobileCMD= userInput;}
+
private:
+ BroadcastData broadcastData;
+ uint32_t ackFrameStatus;
+ bool broadcastFrameStatus;
unsigned char encodeSendData[BUFFER_SIZE];
unsigned char encodeACK[ACK_SIZE];
// uint8_t cblistTail;
// CallBackHandler cbList[CALLBACK_LIST_NUM];
+
CallBackHandler fromMobileCallback;
CallBackHandler broadcastCallback;
CallBackHandler hotPointCallback;
@@ -385,15 +593,39 @@ class CoreAPI
CallBackHandler missionCallback;
CallBackHandler recvCallback;
+ CallBackHandler obtainControlMobileCallback;
+ CallBackHandler releaseControlMobileCallback;
+ CallBackHandler activateMobileCallback;
+ CallBackHandler armMobileCallback;
+ CallBackHandler disArmMobileCallback;
+ CallBackHandler takeOffMobileCallback;
+ CallBackHandler landingMobileCallback;
+ CallBackHandler goHomeMobileCallback;
+ CallBackHandler takePhotoMobileCallback;
+ CallBackHandler startVideoMobileCallback;
+ CallBackHandler stopVideoMobileCallback;
+
+ bool obtainControlMobileCMD;
+ bool releaseControlMobileCMD;
+ bool activateMobileCMD;
+ bool armMobileCMD;
+ bool disArmMobileCMD;
+ bool takeOffMobileCMD;
+ bool landingMobileCMD;
+ bool goHomeMobileCMD;
+ bool takePhotoMobileCMD;
+ bool startVideoMobileCMD;
+ bool stopVideoMobileCMD;
+ bool followMeMobileCMD;
+
VersionData versionData;
ActivateData accountData;
unsigned short seq_num;
+ unsigned char *version_ack_data;
SDKFilter filter;
- private:
-
/// Serial Device Initialization
void init(HardDriver *Driver, CallBackHandler userRecvCallback, bool userCallbackThread,
Version SDKVersion);
@@ -404,8 +636,6 @@ class CoreAPI
int sendInterface(Command *parameter);
int ackInterface(Ack *parameter);
void sendData(unsigned char *buf);
-
- private:
void setup(void);
void setupMMU(void);
void setupSession(void);
@@ -417,14 +647,10 @@ class CoreAPI
void freeACK(ACKSession *session);
ACKSession *allocACK(unsigned short session_id, unsigned short size);
-
- private:
MMU_Tab MMU[MMU_TABLE_NUM];
CMDSession CMDSessionTab[SESSION_TABLE_NUM];
ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
unsigned char memory[MEMORY_SIZE];
-
- private:
unsigned short encrypt(unsigned char *pdest, const unsigned char *psrc,
unsigned short w_len, unsigned char is_ack, unsigned char is_enc,
unsigned char session_id, unsigned short seq_num);
@@ -435,56 +661,9 @@ class CoreAPI
void verifyData(SDKFilter *p_filter);
void callApp(SDKFilter *p_filter);
void storeData(SDKFilter *p_filter, unsigned char in_data);
-
- public:
- /**
- * ACK decoder.
- */
- bool decodeACKStatus(unsigned short ack);
-
- /**
- * Flight mission decoder.
- */
- bool decodeMissionStatus(uint8_t ack);
-
- public:
-
- /// Open Protocol Control
- /**
- * Get Open Protocol packet information.
- */
- SDKFilter getFilter() const;
-
- /// HotPoint Mission Control
- bool getHotPointData() const;
-
- /// WayPoint Mission Control
- bool getWayPointData() const;
-
- // FollowMe mission Control
- bool getFollowData() const;
-
- /// HotPoint Mission Control
- void setHotPointData(bool value);
-
- /// WayPoint Mission Control
- void setWayPointData(bool value);
-
- /// Follow Me Mission Control
- void setFollowData(bool value);
-
- /**
- * Initialize serial device
- */
- void setDriver(HardDriver *value);
-
- /**
- * Set SDK version.
- */
- void setVersion(const Version &value);
-
- private:
+public:
HardDriver *serialDevice;
+private:
bool callbackThread;
bool hotPointData;
bool wayPointData;
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_App.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_App.h
index 2abcdec8..618124f7 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_App.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_App.h
@@ -1,10 +1,9 @@
-/*! @brief
- * @file DJI_App.h
+/*! @file DJI_App.h
* @version 3.1.7
* @date Jul 1, 2016
*
- * @abstract
- * Developer App support functionality for DJI onboardSDK library
+ * @brief
+ * Application layer support functionality for DJI onboardSDK library
*
* Copyright 2016 DJI. All right reserved.
*
@@ -44,27 +43,5 @@ typedef struct
#define STATUS_CMD_EXE_FAIL 0x0004
#define STATUS_CMD_EXE_SUCCESS 0x0005
-//! @todo move to type.h
-#pragma pack(1)
-
-typedef struct ActivateData
-{
- unsigned int ID;
- unsigned int reserved;
- unsigned int version;
- unsigned char iosID[32];
- char *encKey;
-} ActivateData;
-
-typedef struct VersionData
-{
- unsigned short version_ack;
- unsigned int version_crc;
- char version_ID[11];
- char version_name[32];
- DJI::onboardSDK::Version version;
-} VersionData;
-
-#pragma pack()
#endif // DJI_APP_H
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Camera.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Camera.h
index 32562b7f..f23d3d3b 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Camera.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Camera.h
@@ -1,9 +1,8 @@
-/** @brief
- * @file DJI_Camera.h
+/** @file DJI_Camera.h
* @version 3.1.7
* @date July 1st, 2016
*
- * @abstract
+ * @brief
* Camera/Gimbal API for DJI onboardSDK library
*
* @copyright 2016 DJI. All rights reserved.
@@ -19,6 +18,7 @@ namespace DJI
{
namespace onboardSDK
{
+//! Camera class for controlling camera and gimbal-related functions available through open protocol
class Camera
{
public:
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Codec.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Codec.h
index 639bc7b2..1dd04b6b 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Codec.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Codec.h
@@ -1,23 +1,13 @@
-/*! @brief
- * @file DJI_Codec.h
- * @version 3.0
- * @date Dec 16, 2015
+/** @file DJI_Codec.h
+ * @version 3.1.7
+ * @date July 1st, 2016
*
- * @abstract
- * Encode functions for DJI onboardSDK library
+ * @brief
+ * Encoding/Message parsing features for DJI onboardSDK library
*
- * @attention
- * Project configuration:
+ * @copyright 2016 DJI. All rights reserved.
*
- * @todo spilt this header into 4 header files
- *
- * @version features:
- * -* @version V3.0
- * -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake
- * -* @date Dec 16, 2015
- * -* @author william.wu
- *
- * */
+ */
#ifndef DJI_CODEC_H
#define DJI_CODEC_H
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 70c51f9e..73d4d38e 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h
@@ -1,21 +1,12 @@
-/*! @brief
- * @file DJI_Config.h
- * @version 3.0
- * @date Dec 16, 2015
+/*! @file DJI_Config.h
+ * @version 3.1.7
+ * @date Jul 01 2016
*
- * @abstract
- * Configuration optional Micro definitions for DJI onboardSDK library.
- *
- * @attention
- * Project configuration:
- * None
- *
- * @version features:
- * -* @version V3.0
- * -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake
- * -* @date Dec 16, 2015
- * -* @author william.wu
+ * @brief
+ * Optional macro definitions for DJI Onboard SDK. Use for debugging.
*
+ * @copyright
+ * 2016 DJI. All rights reserved.
* */
#ifndef DJI_CONFIG_H
@@ -26,10 +17,13 @@
#define BUFFER_SIZE 1024
#define ACK_SIZE 10
-//! @note it means DJI onboardSDK library will not alloc memory from heap.
-//! @todo not available yet, only affect WayPoint
+//! @note The static memory flag means DJI onboardSDK library will not alloc memory from heap.
+//! @todo Not supported in this release.
+
//#define STATIC_MEMORY
+//! Uncomment these macros to access various messages from the API.
+
//#define API_MISSION_DATA
//#define API_DEBUG_DATA
//#define API_BUFFER_DATA
@@ -37,8 +31,10 @@
#define API_ERROR_DATA
#define API_STATUS_DATA
-//! @note if you do not want to use AES encrypt, comment this micro below
+//! @note if you do NOT want to use AES encrypt, comment this macro below
#define USE_ENCRYPT
+
+//! @todo Not supported in this release.
//#define USE_SIMULATION
#include "DJI_Version.h"
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h
index 38df9819..12916fe2 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Flight.h
@@ -89,6 +89,7 @@ class Flight
STATUS_FINISHING_LANDING = 5,
};
+
enum Device
{
DEVICE_RC = 0,
@@ -137,7 +138,9 @@ class Flight
Flight(CoreAPI *ControlAPI = 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);
+ unsigned short setArm(bool enable, int timer);
void control(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw); //! @deprecated This function will be deprecated, please use setMovementControl instead.
void setMovementControl(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw);
void setFlight(FlightData *data); //! @deprecated old interface. PLease use setMovementControl instead.
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
index e24101ca..3796d753 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
@@ -1,9 +1,8 @@
-/** @brief
- * @file DJI_Follow.h
+/** @file DJI_Follow.h
* @version 3.1.7
* @date July 1st, 2016
*
- * @abstract
+ * @brief
* Follow API for DJI onboardSDK library
*
* @copyright 2016 DJI. All right reserved.
@@ -68,9 +67,12 @@ class Follow
Follow(CoreAPI *ControlAPI = 0);
void resetData();
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);
+ MissionACK stop(int timer);
//! @note true for pause, false for resume
void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
+ MissionACK pause(bool isPause, int timer);
void updateTarget(FollowTarget target); //! @note no ack command
void updateTarget(float64_t latitude, float64_t longitude, uint16_t height,
uint16_t angle); //! @note no ack command
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
index dfac5d79..ed5e0a8f 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
@@ -1,21 +1,14 @@
-/*! @brief
- * @file DJI_HardDriver.h
- * @version 3.0
- * @date Dec 9, 2015
+/*! @file DJI_HardDriver.h
+ * @version 3.1.7
+ * @date Jul 01 2016
*
- * @abstract
- * Hard ware level for DJI onboardSDK library
- *
- * @attention
- * Project configuration:
- *
- * @version features:
- * -* @version V3.0
- * -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake
- * -* @date Dec 9, 2015
- * -* @author william.wu
+ * @brief
+ * Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms.
*
+ * @copyright
+ * 2016 DJI. All rights reserved.
* */
+
#ifndef DJI_HARDDRIVER_H
#define DJI_HARDDRIVER_H
@@ -60,6 +53,10 @@ class HardDriver
* void lockMSG();/ void freeMSG();
* @brief provide a mutex for multi-thread. when operating messages.
*
+ * void notify();/ void wait();
+ * @brief use conditional variable to signal controller thread about
+ * arrival of ACK frame.
+ *
* void displayLog(char *buf);
* @brief Micro "API_LOG" invoked this function, to pass datalog.
* In order to pass data through different stream or channel.
@@ -93,6 +90,12 @@ class HardDriver
virtual void lockMSG() = 0;
virtual void freeMSG() = 0;
+ virtual void lockACK() = 0;
+ virtual void freeACK() = 0;
+
+ virtual void notify() = 0;
+ virtual void wait(int timeout) = 0;
+
public:
virtual void displayLog(const char *buf = 0);
};
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_HotPoint.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_HotPoint.h
index 827604c5..69a81bff 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_HotPoint.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_HotPoint.h
@@ -1,21 +1,13 @@
-/*! @brief
- * @file DJI_HotPoint.h
- * @version 3.0
- * @date Dec 16, 2015
+/** @file DJI_Hotpoint.h
+ * @version 3.1.7
+ * @date July 1st, 2016
*
- * @abstract
+ * @brief
* HotPoint API for DJI onboardSDK library
*
- * @attention
- * Project configuration:
+ * @copyright 2016 DJI. All right resserved.
*
- * @version features:
- * -* @version V3.0
- * -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake
- * -* @date Dec 16, 2015
- * -* @author william.wu
- *
- * */
+ */
#ifndef DJI_HOTPOINT_H
#define DJI_HOTPOINT_H
@@ -27,48 +19,15 @@ namespace DJI
namespace onboardSDK
{
-#pragma pack(1)
-
-typedef struct HotPointData
-{
- uint8_t version;
-
- float64_t latitude;
- float64_t longitude;
- float64_t height;
-
- float64_t radius;
- float32_t yawRate; // degree
-
- uint8_t clockwise;
- uint8_t startPoint;
- uint8_t yawMode;
- uint8_t reserved[11];
-} HotPointData;
-
-#pragma pack()
-
class HotPoint
{
public:
#pragma pack(1)
- typedef struct StartACK
- {
- uint8_t ack;
- float32_t maxRadius;
- } StartACK;
-
typedef struct YawRate
{
uint8_t clockwise;
float32_t yawRate;
} YawRate;
-
- typedef struct ReadACK
- {
- MissionACK ack;
- HotPointData data;
- } ReadACK;
#pragma pack()
enum View
@@ -101,16 +60,23 @@ class HotPoint
* */
void start(CallBack callback = 0, UserData userData = 0);
+ HotPointStartACK start(int timer);
void stop(CallBack callback = 0, UserData userData = 0);
+ MissionACK stop(int timer);
void 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);
+ MissionACK updateYawRate(YawRate &Data, int timer);
void updateYawRate(float32_t yawRate, bool isClockwise, CallBack callback = 0,
UserData userData = 0);
void 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);
+ MissionACK resetYaw(int timer);
void readData(CallBack callback = 0, UserData userData = 0);
+ MissionACK readData(int timer);
public:
//! @note data access functions
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
index 81627a5f..c6aad6c3 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
@@ -1,25 +1,14 @@
-/*! @brief
- * @file DJI_Link.h
- * @version 3.0
- * @date Dec 4, 2015
+/** @file DJI_Link.h
+ * @version 3.1.7
+ * @date July 1st, 2016
*
- * @abstract
+ * @brief
+ * Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library
*
- * @attention
- * Project configuration:
+ * @copyright 2016 DJI. All right reserved.
*
- * @version features:
- * -* @version 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
- *
- * */
+ */
+
#ifndef DJI_LINK_H
#define DJI_LINK_H
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Memory.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Memory.h
index 61638ab2..8816c456 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Memory.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Memory.h
@@ -1,3 +1,14 @@
+/** @file DJI_Link.h
+ * @version 3.1.7
+ * @date July 1st, 2016
+ *
+ * @brief
+ * Implement memory management for Core API of DJI onboardSDK library. See DJI_Memory.cpp for more.
+ *
+ * @copyright 2016 DJI. All right reserved.
+ *
+ */
+
#ifndef DJI_MEMORY_H
#define DJI_MEMORY_H
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h
index 6037eca4..f9f183ca 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h
@@ -1,21 +1,13 @@
-/*! @brief
- * @file DJI_Codec.h
- * @version 3.0
- * @date Dec 16, 2015
+/** @file DJI_Mission.h
+ * @version 3.1.7
+ * @date July 1st, 2016
*
- * @abstract
- * Mission framework for DJI onboardSDK library
+ * @brief
+ * Mission Framework for DJI onboardSDK library
*
- * @attention
- * Project configuration:
+ * @copyright 2016 DJI. All right reserved.
*
- * @version features:
- * -* @version V3.0
- * -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake
- * -* @date Dec 16, 2015
- * -* @author william.wu
- *
- * */
+ */
#ifndef DJI_MISSION_H
#define DJI_MISSION_H
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
index 3945f697..6ad0d3f8 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
@@ -1,10 +1,9 @@
-/*! @brief
- * @file DJI_Type.h
+/*! @file DJI_Type.h
* @version 3.1.7
* @date Jul 01 2016
*
- * @abstract
- * Type definition for DJI onboardSDK library
+ * @brief
+ * Type definition for DJI onboardSDK library.
* Officially Maintained
*
* @copyright
@@ -13,7 +12,7 @@
/*! @attention
* Do not modify any definition in this file
- * if you are not sure what are you doing.
+ * if you are unsure about what are you doing.
* DJI will not provide any support for changes made to this file.
* */
@@ -26,6 +25,7 @@
#define NAME(x) #x
+//! Define the UNUSED macro to suppress compiler warnings about unused arguments
#ifdef __GNUC__
#define __UNUSED __attribute__((__unused__))
#define __DELETE(x) delete (char *) x
@@ -50,6 +50,8 @@
#define __func__ __FUNCTION__
#endif // WIN32
+
+//! This is the default status printing mechanism
#define API_LOG(driver, title, fmt, ...) \
if ((title)) \
{ \
@@ -113,8 +115,10 @@ extern uint8_t encrypt;
const size_t SESSION_TABLE_NUM = 32;
const size_t CALLBACK_LIST_NUM = 10;
+//! The CoreAPI class definition is detailed in DJI_API.h
class CoreAPI;
+//! The Header struct is meant to handle the open protocol header.
typedef struct Header
{
unsigned int sof : 8;
@@ -134,8 +138,10 @@ typedef struct Header
unsigned int crc : 16;
} Header;
+//! The CallBack function pointer is used as an argument in api->send calls
typedef void (*CallBack)(DJI::onboardSDK::CoreAPI *, Header *, UserData);
+//! The CallBackHandler struct allows users to encapsulate callbacks and data in one struct
typedef struct CallBackHandler
{
CallBack callback;
@@ -209,8 +215,10 @@ typedef struct Ack
#pragma pack(1)
typedef uint8_t BatteryData;
-typedef uint8_t MissionACK;
+/**
+ * Gimbal Data
+ */
typedef struct GimbalAngleData
{
int16_t yaw;
@@ -231,6 +239,121 @@ typedef struct GimbalSpeedData
typedef float float32_t;
typedef double float64_t;
+/**
+ * HotPoint Data
+ */
+typedef struct HotPointData
+{
+ uint8_t version;
+
+ float64_t latitude;
+ float64_t longitude;
+ float64_t height;
+
+ float64_t radius;
+ float32_t yawRate; // degree
+
+ uint8_t clockwise;
+ uint8_t startPoint;
+ uint8_t yawMode;
+ uint8_t reserved[11];
+} HotPointData;
+
+/**
+ * WayPoint Data
+ */
+typedef struct WayPointInitData
+{
+ uint8_t indexNumber;
+ float32_t maxVelocity;
+ float32_t idleVelocity;
+
+ uint8_t finishAction;
+ uint8_t executiveTimes;
+ uint8_t yawMode;
+ uint8_t traceMode;
+ uint8_t RCLostAction;
+ uint8_t gimbalPitch;
+ float64_t latitude; //! @note For Camera to recording
+ float64_t longitude; //! not supported yet
+ float32_t altitude;
+
+ uint8_t reserved[16];
+} WayPointInitData;
+
+typedef struct WayPointData
+{
+ uint8_t index;
+
+ float64_t latitude;
+ float64_t longitude;
+ float32_t altitude;
+ float32_t damping;
+
+ int16_t yaw;
+ int16_t gimbalPitch;
+ uint8_t turnMode;
+
+ uint8_t reserved[8];
+ uint8_t hasAction;
+ uint16_t actionTimeLimit;
+
+ uint8_t actionNumber : 4;
+ uint8_t actionRepeat : 4;
+
+ uint8_t commandList[16];//! @note issues here list number is 15
+ int16_t commandParameter[16];
+} WayPointData;
+
+/**
+ * ACK Data
+ */
+
+typedef uint8_t MissionACK;
+typedef uint32_t SimpleACK;
+
+typedef struct HotPointStartACK
+{
+ uint8_t ack;
+ float32_t maxRadius;
+} HotpointStartACK;
+
+typedef struct WayPointDataACK
+{
+ uint8_t ack;
+ uint8_t index;
+} WayPointDataACK;
+
+typedef struct WayPointVelocityACK
+{
+ uint8_t ack;
+ 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
+typedef struct HotPointReadACK
+{
+ MissionACK ack;
+ HotPointData data;
+} HotpointReadACK;
+
+typedef struct WayPointInitACK
+{
+ uint8_t ack;
+ WayPointInitData data;
+} WayPointInitACK;
+
typedef struct QuaternionData
{
float32_t q0;
@@ -370,6 +493,7 @@ typedef struct TaskData
} TaskData;
//! @todo rename to a final version
+//! RTKData from the A3. This is not available on the M100.
typedef struct RTKData
{
uint32_t date;
@@ -391,6 +515,7 @@ typedef struct RTKData
} RTKData;
//! @todo rename to a final version
+//! Detailed GPSData from the A3. This is not available on the M100.
typedef struct GPSData
{
uint32_t date;
@@ -467,6 +592,24 @@ typedef struct VirtualRCData
uint32_t Channel_15;
} VirtualRCData;
+typedef struct ActivateData
+{
+ unsigned int ID;
+ unsigned int reserved;
+ unsigned int version;
+ unsigned char iosID[32];
+ char *encKey;
+} ActivateData;
+
+typedef struct VersionData
+{
+ unsigned short version_ack;
+ unsigned int version_crc;
+ char version_ID[11];
+ char version_name[32];
+ DJI::onboardSDK::Version version;
+} VersionData;
+
#pragma pack()
#ifdef SDK_DEV
#include "devtype.h"
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h
index af3f7c89..63fb0c8f 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h
@@ -1,9 +1,8 @@
-/*! @brief
- * @file DJI_Version.h
+/*! @file DJI_Version.h
* @version 3.1.7
* @date Jul 01 2016
*
- * @abstract
+ * @brief
* Drone/SDK Version definition for DJI onboardSDK library
* Officially Maintained
*
@@ -30,7 +29,7 @@ namespace DJI
{
namespace onboardSDK
{
-//! @todo better version control structure
+//! Different version strings define SDK/Drone combination. Only the ones listed below are available.
typedef uint32_t Version;
const Version versionM100_23 = (MAKE_VERSION(2, 3, 10, 0));
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_VirtualRC.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_VirtualRC.h
index 8bd36b00..c1de681d 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_VirtualRC.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_VirtualRC.h
@@ -1,9 +1,8 @@
-/** @brief
- * @file DJI_VirtualRC.h
+/**@file DJI_VirtualRC.h
* @version 3.1.7
* @date July 1st, 2016
*
- * @abstract
+ * @brief
* Virtual Radio Control API for DJI onboardSDK library
*
* @copyright 2016 DJI. All rights reserved.
@@ -74,7 +73,7 @@ class VirtualRC
*
* 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.
+ * This may result in a catastrophic crash.
*
* @note API "sendData();" need to be called above 2Hz, and not greater than 25hz.
* @note API "sendSafeModeData();" will lead your drone hover;
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h
index 695d91c4..77e324cf 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_WayPoint.h
@@ -1,22 +1,17 @@
-/*! @brief
- * @file DJI_WayPoint.h
- * @version 3.0
- * @date Dec 22, 2015
- *
- * @abstract
- * WayPoint API for DJI onboardSDK library
- *
- * @attention
- * Project configuration:
- *
- * @version features:
- * -* @version V3.0
- * -* DJI-onboard-SDK for Windows,QT,STM32,ROS,Cmake
- * -* @date Dec 16, 2015
- * -* @author william.wu
- *
- * */
+/** @brief
+* @file DJI_WayPoint.h
+* @version 3.1.7
+* @date July 1st, 2016
+*
+* @brief
+* Waypoint flight API for DJI onboardSDK library
+*
+* @copyright 2016 DJI. All right reserved.
+*
+*/
+
#include "DJI_Mission.h"
+#include
#ifndef DJI_WAYPOINT_H
#define DJI_WAYPOINT_H
@@ -26,72 +21,6 @@ namespace DJI
namespace onboardSDK
{
-class WayPoint;
-
-#pragma pack(1)
-typedef struct WayPointInitData
-{
- uint8_t indexNumber;
- float32_t maxVelocity;
- float32_t idleVelocity;
-
- uint8_t finishAction;
- uint8_t executiveTimes;
- uint8_t yawMode;
- uint8_t traceMode;
- uint8_t RCLostAction;
- uint8_t gimbalPitch;
- float64_t latitude; //! @note For Camera to recording
- float64_t longitude; //! not supported yet
- float32_t altitude;
-
- uint8_t reserved[16];
-} WayPointInitData;
-
-typedef struct WayPointData
-{
- uint8_t index;
-
- float64_t latitude;
- float64_t longitude;
- float32_t altitude;
- float32_t damping;
-
- int16_t yaw;
- int16_t gimbalPitch;
- uint8_t turnMode;
-
- uint8_t reserved[8];
- uint8_t hasAction;
- uint16_t actionTimeLimit;
-
- uint8_t actionNumber : 4;
- uint8_t actionRepeat : 4;
-
- uint8_t commandList[16];//! @note issues here list number is 15
- int16_t commandParameter[16];
-} WayPointData;
-
-typedef struct WayPointVelocityACK
-{
- uint8_t ack;
- float32_t idleVelocity;
-} WayPointVelocityACK;
-
-typedef struct WayPointInitACK
-{
- uint8_t ack;
- WayPointInitData data;
-} WayPointInitACK;
-
-typedef struct WayPointDataACK
-{
- uint8_t ack;
- uint8_t index;
-} WayPointDataACK;
-
-#pragma pack()
-
class WayPoint
{
public:
@@ -101,16 +30,21 @@ class WayPoint
WayPoint(WayPointData *list, uint8_t len, CoreAPI *ControlAPI = 0);
#endif // STATIC_MEMORY
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);
+ MissionACK start(int timer);
void stop(CallBack callback = 0, UserData userData = 0);
+ MissionACK stop(int timer);
//! @note true for pause, false for resume
void pause(bool isPause, CallBack callback = 0, UserData userData = 0);
+ MissionACK pause(bool isPause, int timer);
void readInitData(CallBack callback = 0, UserData userData = 0);//! @todo implement
void readIndexData(uint8_t index, CallBack callback = 0, UserData userData = 0); //! @todo implement
void readIdleVelocity(CallBack callback = 0, UserData userData = 0);
//! @todo uploadAll
//void uploadAll(CallBack callback = 0, UserData userData = 0);
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);
void updateIdleVelocity(float32_t meterPreSecond, CallBack callback = 0,
UserData userData = 0);
diff --git a/dji_sdk_lib/src/DJI_API.cpp b/dji_sdk_lib/src/DJI_API.cpp
index f40c06b6..8e1bd49b 100644
--- a/dji_sdk_lib/src/DJI_API.cpp
+++ b/dji_sdk_lib/src/DJI_API.cpp
@@ -38,7 +38,8 @@ void CoreAPI::init(HardDriver *sDevice, CallBackHandler userRecvCallback,
// serialDevice->init();
seq_num = 0;
- sessionStatus = 11;
+ ackFrameStatus = 11;
+ broadcastFrameStatus = false;
filter.recvIndex = 0;
filter.reuseCount = 0;
@@ -69,6 +70,7 @@ void CoreAPI::init(HardDriver *sDevice, CallBackHandler userRecvCallback,
wayPointData = false;
callbackThread = userCallbackThread;
+ ack_data = 99;
versionData.version = SDKVersion;
//! @todo simplify code above
@@ -165,6 +167,41 @@ void CoreAPI::getDroneVersion(CallBack callback, UserData userData)
retry_time, callback ? callback : CoreAPI::getDroneVersionCallback, userData);
}
+VersionData CoreAPI::getDroneVersion(int timeout)
+{
+ versionData.version_ack = ACK_COMMON_NO_RESPONSE;
+ versionData.version_crc = 0x0;
+ versionData.version_name[0] = 0;
+
+ unsigned cmd_timeout = 100; // unit is ms
+ unsigned retry_time = 3;
+ unsigned char cmd_data = 0;
+
+ send(2, 0, SET_ACTIVATION, CODE_GETVERSION, (unsigned char *)&cmd_data, 1, cmd_timeout,
+ retry_time, 0, 0);
+
+ // Wait for end of ACK frame to arrive
+ serialDevice->lockACK();
+ serialDevice->wait(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;
+ }
+ memcpy(versionData.version_name, version_ack_data, 32);
+
+ return versionData;
+}
+
void CoreAPI::activate(ActivateData *data, CallBack callback, UserData userData)
{
data->version = versionData.version;
@@ -179,6 +216,29 @@ void CoreAPI::activate(ActivateData *data, CallBack callback, UserData userData)
callback ? callback : CoreAPI::activateCallback, userData);
}
+unsigned short CoreAPI::activate(ActivateData *data, int timeout)
+{
+ data->version = versionData.version;
+ accountData = *data;
+ accountData.reserved = 2;
+
+ for (int i = 0; i < 32; ++i) accountData.iosID[i] = '0'; //! @note for ios verification
+ API_LOG(serialDevice, DEBUG_LOG, "version 0x%X/n", versionData.version);
+ API_LOG(serialDevice, DEBUG_LOG, "%.32s", accountData.iosID);
+ send(2, 0, SET_ACTIVATION, CODE_ACTIVATE, (unsigned char *)&accountData,
+ sizeof(accountData) - sizeof(char *), 1000, 3, 0, 0);
+
+ // Wait for end of ACK frame to arrive
+ serialDevice->lockACK();
+ serialDevice->wait(timeout);
+ serialDevice->freeACK();
+ ack_data = missionACKUnion.simpleACK;
+ if(ack_data == ACK_ACTIVE_SUCCESS && accountData.encKey)
+ setKey(accountData.encKey);
+
+ return ack_data;
+}
+
void CoreAPI::sendToMobile(uint8_t *data, uint8_t len, CallBack callback, UserData userData)
{
if (len > 100)
@@ -186,7 +246,7 @@ void CoreAPI::sendToMobile(uint8_t *data, uint8_t len, CallBack callback, UserDa
API_LOG(serialDevice, ERROR_LOG, "Too much data to send");
return;
}
- send(2, 0, SET_ACTIVATION, CODE_TOMOBILE, data, len, 500, 1,
+ send(0, 0, SET_ACTIVATION, CODE_TOMOBILE, data, len, 500, 1,
callback ? callback : CoreAPI::sendToMobileCallback, userData);
}
@@ -216,6 +276,144 @@ void CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback, UserData
callback ? callback : CoreAPI::setFrequencyCallback, userData);
}
+unsigned short CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, int timeout)
+{
+ //! @note see also enum BROADCAST_FREQ in DJI_API.h
+ for (int i = 0; i < 16; ++i)
+ {
+ if (versionData.version == versionM100_31)
+ if (i < 12)
+ {
+ dataLenIs16[i] = (dataLenIs16[i] > 5 ? 5 : dataLenIs16[i]);
+ }
+ else
+ dataLenIs16[i] = 0;
+ else
+ {
+ if (i < 14)
+ {
+ dataLenIs16[i] = (dataLenIs16[i] > 5 ? 5 : dataLenIs16[i]);
+ }
+ else
+ dataLenIs16[i] = 0;
+ }
+ }
+ send(2, 0, SET_ACTIVATION, CODE_FREQUENCY, dataLenIs16, 16, 100, 1, 0, 0);
+
+ // Wait for end of ACK frame to arrive
+ serialDevice->lockACK();
+ serialDevice->wait(timeout);
+ serialDevice->freeACK();
+
+ return missionACKUnion.simpleACK;
+}
+
+void CoreAPI::setBroadcastFreqDefaults()
+{
+ 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;
+
+ setBroadcastFreq(freq);
+}
+
+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
+ */
+
+ 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;
+
+ setBroadcastFreq(freq);
+}
+
+
+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;
+
+ return setBroadcastFreq(freq, timeout);
+}
+
TimeStampData CoreAPI::getTime() const { return broadcastData.timeStamp; }
FlightStatus CoreAPI::getFlightStatus() const { return broadcastData.status; }
@@ -225,6 +423,7 @@ void CoreAPI::setFromMobileCallback(CallBackHandler FromMobileEntrance)
fromMobileCallback = FromMobileEntrance;
}
+
ActivateData CoreAPI::getAccountData() const { return accountData; }
void CoreAPI::setAccountData(const ActivateData &value) { accountData = value; }
@@ -242,6 +441,19 @@ void CoreAPI::setControl(bool enable, CallBack callback, UserData userData)
callback ? callback : CoreAPI::setControlCallback, userData);
}
+unsigned short CoreAPI::setControl(bool enable, int timeout)
+{
+ unsigned char data = enable ? 1 : 0;
+ send(2, DJI::onboardSDK::encrypt, SET_CONTROL, CODE_SETCONTROL, &data, 1, 500, 2, 0, 0);
+
+ // Wait for end of ACK frame to arrive
+ serialDevice->lockACK();
+ serialDevice->wait(timeout);
+ serialDevice->freeACK();
+
+ return missionACKUnion.simpleACK;
+}
+
HardDriver *CoreAPI::getDriver() const { return serialDevice; }
void CoreAPI::setDriver(HardDriver *sDevice) { serialDevice = sDevice; }
@@ -347,6 +559,142 @@ void CoreAPI::sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserDat
protocolHeader->sessionID, protocolHeader->sequenceNumber);
}
}
+void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED)
+{
+ uint16_t mobile_data_id;
+
+ if (protocolHeader->length - EXC_DATA_SIZE <= 4)
+ {
+ mobile_data_id = *((unsigned char*)protocolHeader + sizeof(Header) + 2);
+
+ switch (mobile_data_id)
+ {
+ case 2:
+ if (obtainControlMobileCallback.callback)
+ {
+ obtainControlMobileCallback.callback(api, protocolHeader, obtainControlMobileCallback.userData);
+ }
+ else
+ {
+ obtainControlMobileCMD = true;
+ }
+ break;
+
+ case 3:
+ if (releaseControlMobileCallback.callback)
+ {
+ releaseControlMobileCallback.callback(api, protocolHeader, releaseControlMobileCallback.userData);
+ }
+ else
+ {
+ releaseControlMobileCMD = true;
+ }
+ break;
+
+ case 4:
+ if (activateMobileCallback.callback)
+ {
+ activateMobileCallback.callback(api, protocolHeader, activateMobileCallback.userData);
+ }
+ else
+ {
+ activateMobileCMD = true;
+ }
+ break;
+
+ case 5:
+ if (armMobileCallback.callback)
+ {
+ armMobileCallback.callback(api, protocolHeader, armMobileCallback.userData);
+ }
+ else
+ {
+ armMobileCMD = true;
+ }
+ break;
+
+ case 6:
+ if (disArmMobileCallback.callback)
+ {
+ disArmMobileCallback.callback(api, protocolHeader, disArmMobileCallback.userData);
+ }
+ else
+ {
+ disArmMobileCMD = true;
+ }
+ break;
+
+ case 7:
+ if (takeOffMobileCallback.callback)
+ {
+ takeOffMobileCallback.callback(api, protocolHeader, takeOffMobileCallback.userData);
+ }
+ else
+ {
+ takeOffMobileCMD = true;
+ }
+ break;
+
+ case 8:
+ if (landingMobileCallback.callback)
+ {
+ landingMobileCallback.callback(api, protocolHeader, landingMobileCallback.userData);
+ }
+ else
+ {
+ landingMobileCMD = true;
+ }
+ break;
+
+ case 9:
+ if (goHomeMobileCallback.callback)
+ {
+ goHomeMobileCallback.callback(api, protocolHeader, goHomeMobileCallback.userData);
+ }
+ else
+ {
+ goHomeMobileCMD = true;
+ }
+ break;
+
+ case 10:
+ if (takePhotoMobileCallback.callback)
+ {
+ takePhotoMobileCallback.callback(api, protocolHeader, takePhotoMobileCallback.userData);
+ }
+ else
+ {
+ takePhotoMobileCMD = true;
+ }
+ break;
+
+ case 11:
+ if (startVideoMobileCallback.callback)
+ {
+ startVideoMobileCallback.callback(api, protocolHeader, startVideoMobileCallback.userData);
+ }
+ else
+ {
+ startVideoMobileCMD = true;
+ }
+ break;
+
+ case 13:
+ if (stopVideoMobileCallback.callback)
+ {
+ stopVideoMobileCallback.callback(api, protocolHeader, stopVideoMobileCallback.userData);
+ }
+ else
+ {
+ stopVideoMobileCMD = true;
+ }
+ break;
+ case 68:
+ followMeMobileCMD = true;
+ }
+
+}
+}
void CoreAPI::setFrequencyCallback(CoreAPI *api __UNUSED, Header *protocolHeader,
UserData userData __UNUSED)
@@ -361,19 +709,20 @@ void CoreAPI::setFrequencyCallback(CoreAPI *api __UNUSED, Header *protocolHeader
switch (ack_data)
{
case 0x0000:
- API_LOG(api->serialDevice, STATUS_LOG, "Frequency set successfully");
+ API_LOG(api->serialDevice, STATUS_LOG, "Frequency set successfully\n");
break;
case 0x0001:
- API_LOG(api->serialDevice, ERROR_LOG, "Frequency parameter error");
+ API_LOG(api->serialDevice, ERROR_LOG, "Frequency parameter error\n");
break;
default:
if (!api->decodeACKStatus(ack_data))
{
- API_LOG(api->serialDevice, ERROR_LOG, "While calling this function");
+ API_LOG(api->serialDevice, ERROR_LOG, "While calling this function\n");
}
break;
}
}
+
Version CoreAPI::getSDKVersion() const { return versionData.version; }
SDKFilter CoreAPI::getFilter() const { return filter; }
diff --git a/dji_sdk_lib/src/DJI_App.cpp b/dji_sdk_lib/src/DJI_App.cpp
index 62fdc7be..e5c6a279 100644
--- a/dji_sdk_lib/src/DJI_App.cpp
+++ b/dji_sdk_lib/src/DJI_App.cpp
@@ -1,10 +1,9 @@
-/*! @brief
- * @file DJI_App.cpp
+/*! @file DJI_App.cpp
* @version 3.1.7
* @date Jul 01 2016
*
- * @abstract
- * Developer App support functionality for DJI onboardSDK library
+ * @brief
+ * Application layer support functionality for DJI onboardSDK library
*
* Copyright 2016 DJI. All right reserved.
*
@@ -52,6 +51,16 @@ BatteryData DJI::onboardSDK::CoreAPI::getBatteryCapacity() const
CtrlInfoData DJI::onboardSDK::CoreAPI::getCtrlInfo() const { return broadcastData.ctrlInfo; }
+void DJI::onboardSDK::CoreAPI::setBroadcastFrameStatus(bool isFrame)
+{
+ broadcastFrameStatus = isFrame;
+}
+
+bool DJI::onboardSDK::CoreAPI::getBroadcastFrameStatus()
+{
+ return broadcastFrameStatus;
+}
+
#ifdef SDK_DEV
#include "devApp.cpp"
#else
@@ -101,6 +110,12 @@ void DJI::onboardSDK::CoreAPI::broadcast(Header *protocolHeader)
sizeof(CtrlInfoData) - ((versionData.version == versionM100_23) ? 1 : 0), len);
serialDevice->freeMSG();
+ /**
+ * Set broadcast frame status
+ * @todo Implement proper notification mechanism
+ */
+ setBroadcastFrameStatus(true);
+
if (broadcastCallback.callback)
broadcastCallback.callback(this, protocolHeader, broadcastCallback.userData);
}
@@ -118,11 +133,15 @@ void DJI::onboardSDK::CoreAPI::recvReqData(Header *protocolHeader)
broadcast(protocolHeader);
break;
case CODE_FROMMOBILE:
+ API_LOG(serialDevice, STATUS_LOG, "Receive data from mobile\n");
if (fromMobileCallback.callback)
{
- API_LOG(serialDevice, STATUS_LOG, "Receive data from mobile\n")
fromMobileCallback.callback(this, protocolHeader, fromMobileCallback.userData);
}
+ else
+ {
+ parseFromMobileCallback(this, protocolHeader);
+ }
break;
case CODE_LOSTCTRL:
API_LOG(serialDevice, STATUS_LOG, "onboardSDK lost control\n");
diff --git a/dji_sdk_lib/src/DJI_Camera.cpp b/dji_sdk_lib/src/DJI_Camera.cpp
index c1f4f4e2..8aff386e 100644
--- a/dji_sdk_lib/src/DJI_Camera.cpp
+++ b/dji_sdk_lib/src/DJI_Camera.cpp
@@ -1,9 +1,8 @@
-/** @brief
- * @file DJI_Camera.cpp
+/** @file DJI_Camera.cpp
* @version 3.1.7
* @date July 1st, 2016
*
- * @abstract
+ * @brief
* Camera/Gimbal API for DJI onboardSDK library
*
* @copyright 2016 DJI. All rights reserved.
diff --git a/dji_sdk_lib/src/DJI_Codec.cpp b/dji_sdk_lib/src/DJI_Codec.cpp
index 850141a5..dbe9e34e 100644
--- a/dji_sdk_lib/src/DJI_Codec.cpp
+++ b/dji_sdk_lib/src/DJI_Codec.cpp
@@ -615,7 +615,7 @@ bool CoreAPI::decodeACKStatus(unsigned short ack)
API_LOG(serialDevice, ERROR_LOG, "Wrong encode Key, Activate again.");
return false;
case ACK_COMMON_NO_AUTHORIZATION:
- API_LOG(serialDevice, ERROR_LOG, "Pleasd obtain control and retry.");
+ API_LOG(serialDevice, ERROR_LOG, "Please obtain control and retry.");
return false;
case ACK_COMMON_NO_RIGHTS:
API_LOG(serialDevice, ERROR_LOG, "Need higher Level access.");
@@ -862,7 +862,7 @@ unsigned short DJI::onboardSDK::CoreAPI::encrypt(unsigned char *pdest,
if (filter.encode == 0 && is_enc)
{
API_LOG(serialDevice, ERROR_LOG,
- "Can not send encode data, Please active your device to get an available key.");
+ "Can not send encode data, Please activate your device to get an available key.\n");
return 0;
}
if (w_len == 0 || psrc == 0)
diff --git a/dji_sdk_lib/src/DJI_Flight.cpp b/dji_sdk_lib/src/DJI_Flight.cpp
index 34ceb3e9..1592da3a 100644
--- a/dji_sdk_lib/src/DJI_Flight.cpp
+++ b/dji_sdk_lib/src/DJI_Flight.cpp
@@ -43,6 +43,21 @@ void Flight::task(TASK taskname, CallBack TaskCallback, UserData userData)
100, 3, TaskCallback ? TaskCallback : Flight::taskCallback, userData);
}
+unsigned short Flight::task(TASK taskname, int timeout)
+{
+ taskData.cmdData = taskname;
+ taskData.cmdSequence++;
+
+ api->send(2, encrypt, SET_CONTROL, CODE_TASK, (unsigned char *)&taskData, sizeof(taskData),
+ 100, 3, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.simpleACK;
+}
+
void Flight::setArm(bool enable, CallBack ArmCallback, UserData userData)
{
uint8_t data = enable ? 1 : 0;
@@ -50,6 +65,19 @@ void Flight::setArm(bool enable, CallBack ArmCallback, UserData userData)
ArmCallback ? ArmCallback : Flight::armCallback, userData);
}
+unsigned short Flight::setArm(bool enable, int timeout)
+{
+ uint8_t data = enable ? 1 : 0;
+ api->send(2, encrypt, SET_CONTROL, CODE_SETARM, &data, 1, 0, 1, 0, 0);
+
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.simpleACK;
+}
+
void Flight::control(uint8_t flag, float32_t x, float32_t y, float32_t z, float32_t yaw)
{
FlightData data;
@@ -194,7 +222,7 @@ void Flight::taskCallback(CoreAPI *api, Header *protocolHeader, UserData userDat
(protocolHeader->length - EXC_DATA_SIZE));
API_LOG(api->getDriver(), STATUS_LOG, "Task running successfully,%d\n", ack_data);
}
- else
+ else
{
API_LOG(api->getDriver(), ERROR_LOG, "ACK is exception,session id %d,sequence %d\n",
protocolHeader->sessionID, protocolHeader->sequenceNumber);
diff --git a/dji_sdk_lib/src/DJI_Follow.cpp b/dji_sdk_lib/src/DJI_Follow.cpp
index fc055cdc..7d73eede 100644
--- a/dji_sdk_lib/src/DJI_Follow.cpp
+++ b/dji_sdk_lib/src/DJI_Follow.cpp
@@ -1,9 +1,8 @@
-/** @brief
- * @file DJI_Follow.cpp
+/** @file DJI_Follow.cpp
* @version 3.1.7
* @date July 1st, 2016
*
- * @abstract
+ * @brief
* Follow API for DJI onboardSDK library
*
* @copyright 2016 DJI. All right reserved.
@@ -42,6 +41,21 @@ void Follow::start(FollowData *Data, CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK Follow::start(FollowData *Data, int timeout)
+{
+ if (Data)
+ followData = *Data;
+ else
+ resetData();
+ api->send(2, encrypt, SET_MISSION, CODE_FOLLOW_START, &followData, sizeof(followData), 500, 2, 0,0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void Follow::stop(CallBack callback, UserData userData)
{
uint8_t zero = 0;
@@ -49,6 +63,18 @@ void Follow::stop(CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK Follow::stop(int timeout)
+{
+ uint8_t zero = 0;
+ api->send(2, encrypt, SET_MISSION, CODE_FOLLOW_STOP, &zero, sizeof(zero), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void Follow::pause(bool isPause, CallBack callback, UserData userData)
{
uint8_t followData = isPause ? 0 : 1;
@@ -56,6 +82,18 @@ void Follow::pause(bool isPause, CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK Follow::pause(bool isPause, int timeout)
+{
+ uint8_t followData = isPause ? 0 : 1;
+ api->send(2, encrypt, SET_MISSION, CODE_FOLLOW_SETPAUSE, &followData, sizeof(followData), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void Follow::updateTarget(FollowTarget target)
{
followData.target = target;
diff --git a/dji_sdk_lib/src/DJI_HardDriver.cpp b/dji_sdk_lib/src/DJI_HardDriver.cpp
index ab447ce6..6e523cc9 100644
--- a/dji_sdk_lib/src/DJI_HardDriver.cpp
+++ b/dji_sdk_lib/src/DJI_HardDriver.cpp
@@ -1,3 +1,14 @@
+/*! @file DJI_HardDriver.cpp
+ * @version 3.1.7
+ * @date Jul 01 2016
+ *
+ * @brief
+ * Serial device driver abstraction. See DJI_HardDriver.h for more info.
+ *
+ * @copyright
+ * 2016 DJI. All rights reserved.
+ * */
+
#include "DJI_HardDriver.h"
using namespace DJI::onboardSDK;
diff --git a/dji_sdk_lib/src/DJI_HotPoint.cpp b/dji_sdk_lib/src/DJI_HotPoint.cpp
index 6b5d09fc..ea5c76e4 100644
--- a/dji_sdk_lib/src/DJI_HotPoint.cpp
+++ b/dji_sdk_lib/src/DJI_HotPoint.cpp
@@ -1,15 +1,13 @@
-/** @brief
-* @file DJI_HotPoint.cpp
-* @version 3.1.7
-* @date July 1st, 2016
-*
-* @abstract
-* Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library
-*
-* @copyright 2016 DJI. All right reserved.
-*
-*/
-
+/** @file DJI_HotPoint.cpp
+ * @version 3.1.7
+ * @date July 1st, 2016
+ *
+ * @brief
+ * Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library
+ *
+ * @copyright 2016 DJI. All rights reserved.
+ *
+ */
#include "DJI_HotPoint.h"
#include
@@ -45,6 +43,17 @@ void HotPoint::start(CallBack callback, UserData userData)
callback ? callback : startCallback, userData);
}
+HotPointStartACK HotPoint::start(int timeout)
+{
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_START, &hotPointData, sizeof(hotPointData), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.hotpointStartACK;
+}
+
void HotPoint::stop(CallBack callback, UserData userData)
{
uint8_t zero = 0;
@@ -52,6 +61,18 @@ void HotPoint::stop(CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK HotPoint::stop(int timeout)
+{
+ uint8_t zero = 0;
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_STOP, &zero, sizeof(zero), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void HotPoint::pause(bool isPause, CallBack callback, UserData userData)
{
uint8_t data = isPause ? 0 : 1;
@@ -59,6 +80,18 @@ void HotPoint::pause(bool isPause, CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK HotPoint::pause(bool isPause, int timeout)
+{
+ uint8_t data = isPause ? 0 : 1;
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_SETPAUSE, &data, sizeof(data), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void HotPoint::updateYawRate(HotPoint::YawRate &Data, CallBack callback, UserData userData)
{
hotPointData.yawRate = Data.yawRate;
@@ -67,6 +100,19 @@ void HotPoint::updateYawRate(HotPoint::YawRate &Data, CallBack callback, UserDat
callback ? callback : missionCallback, userData);
}
+MissionACK HotPoint::updateYawRate(HotPoint::YawRate &Data, int timeout)
+{
+ hotPointData.yawRate = Data.yawRate;
+ hotPointData.clockwise = Data.clockwise ? 1 : 0;
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_YAWRATE, &Data, sizeof(Data), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void HotPoint::updateYawRate(float32_t yawRate, bool isClockwise, CallBack callback,
UserData userData)
{
@@ -82,6 +128,17 @@ void HotPoint::updateRadius(float32_t meter, CallBack callback, UserData userDat
callback ? callback : missionCallback, userData);
}
+MissionACK HotPoint::updateRadius(float32_t meter, int timeout)
+{
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_RADIUS, &meter, sizeof(meter), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void HotPoint::resetYaw(CallBack callback, UserData userData)
{
uint8_t zero = 0;
@@ -89,6 +146,18 @@ void HotPoint::resetYaw(CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK HotPoint::resetYaw(int timeout)
+{
+ uint8_t zero = 0;
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_SETYAW, &zero, sizeof(zero), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void HotPoint::readData(CallBack callback, UserData userData)
{
uint8_t zero = 0;
@@ -96,6 +165,18 @@ void HotPoint::readData(CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK HotPoint::readData(int timeout)
+{
+ uint8_t zero = 0;
+ api->send(2, encrypt, SET_MISSION, CODE_HOTPOINT_LOAD, &zero, sizeof(zero), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void HotPoint::setData(const HotPointData &value)
{
hotPointData = value;
@@ -130,8 +211,8 @@ HotPointData HotPoint::getData() const { return hotPointData; }
void HotPoint::startCallback(CoreAPI *api, Header *protocolHeader, UserData userdata __UNUSED)
{
- StartACK ack;
- if (protocolHeader->length - EXC_DATA_SIZE <= sizeof(StartACK))
+ HotPointStartACK ack;
+ if (protocolHeader->length - EXC_DATA_SIZE <= sizeof(HotPointStartACK))
{
memcpy((unsigned char *)&ack, (unsigned char *)protocolHeader + sizeof(Header),
(protocolHeader->length - EXC_DATA_SIZE));
@@ -150,8 +231,8 @@ void HotPoint::startCallback(CoreAPI *api, Header *protocolHeader, UserData user
void HotPoint::readCallback(CoreAPI *api, Header *protocolHeader, UserData userdata)
{
HotPoint *hp = (HotPoint *)userdata;
- ReadACK ack;
- if (protocolHeader->length - EXC_DATA_SIZE <= sizeof(ack))
+ HotPointReadACK ack;
+ if (protocolHeader->length - EXC_DATA_SIZE <= sizeof(HotPointReadACK))
{
memcpy((unsigned char *)&ack, (unsigned char *)protocolHeader + sizeof(Header),
(protocolHeader->length - EXC_DATA_SIZE));
diff --git a/dji_sdk_lib/src/DJI_Link.cpp b/dji_sdk_lib/src/DJI_Link.cpp
index 38b0870a..85c3d81f 100644
--- a/dji_sdk_lib/src/DJI_Link.cpp
+++ b/dji_sdk_lib/src/DJI_Link.cpp
@@ -55,16 +55,23 @@ void CoreAPI::appHandler(Header *protocolHeader)
callBack = CMDSessionTab[protocolHeader->sessionID].handler;
data = CMDSessionTab[protocolHeader->sessionID].userData;
freeSession(&CMDSessionTab[protocolHeader->sessionID]);
-
serialDevice->freeMemory();
+
+ // Notify caller end of ACK frame arrived
+ notifyCaller(protocolHeader);
+
if (callBack)
{
//! @todo new algorithm call in a thread
callBack(this, protocolHeader, data);
- //! End of session
- setSessionStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag);
+ /**
+ * Set end of ACK frame
+ * @todo Implement proper notification mechanism
+ */
+ // setACKFrameStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag);
}
+ setACKFrameStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag);
}
else
serialDevice->freeMemory();
@@ -104,7 +111,7 @@ void CoreAPI::appHandler(Header *protocolHeader)
p2protocolHeader = (Header *)ACKSessionTab[protocolHeader->sessionID - 1].mmu->pmem;
if (p2protocolHeader->sequenceNumber == protocolHeader->sequenceNumber)
{
- API_LOG(serialDevice, DEBUG_LOG, "repeat ACK to remote,session "
+ API_LOG(serialDevice, DEBUG_LOG, "Repeat ACK to remote,session "
"id=%d,seq_num=%d\n",
protocolHeader->sessionID, protocolHeader->sequenceNumber);
sendData(ACKSessionTab[protocolHeader->sessionID - 1].mmu->pmem);
@@ -113,7 +120,7 @@ void CoreAPI::appHandler(Header *protocolHeader)
else
{
API_LOG(serialDevice, DEBUG_LOG,
- "same session,but new seq_num pkg,session id=%d,"
+ "Same session,but new seq_num pkg,session id=%d,"
"pre seq_num=%d,cur seq_num=%d\n",
protocolHeader->sessionID, p2protocolHeader->sequenceNumber,
protocolHeader->sequenceNumber);
@@ -128,6 +135,27 @@ void CoreAPI::appHandler(Header *protocolHeader)
}
}
+void CoreAPI::notifyCaller(Header *protocolHeader)
+{
+ serialDevice->lockACK();
+
+ // In case of getDroneVersion? Should be only one case.
+ 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);
+ }
+
+ // Notify caller end of ACK frame arrived
+ serialDevice->notify();
+ serialDevice->freeACK();
+}
+
void CoreAPI::sendPoll()
{
unsigned char i;
@@ -160,7 +188,7 @@ void CoreAPI::sendPoll()
}
else
{
- API_LOG(serialDevice, DEBUG_LOG, "send once %d\n", i);
+ API_LOG(serialDevice, DEBUG_LOG, "Send once %d\n", i);
sendData(CMDSessionTab[i].mmu->pmem);
CMDSessionTab[i].preTimestamp = curTimestamp;
}
@@ -168,7 +196,7 @@ void CoreAPI::sendPoll()
}
else
{
- API_LOG(serialDevice, DEBUG_LOG, "timeout Session: %d \n", i);
+ API_LOG(serialDevice, DEBUG_LOG, "Timeout Session: %d \n", i);
}
}
}
@@ -213,14 +241,14 @@ void CoreAPI::setActivation(bool isActivated)
broadcastData.activation = 0;
}
-void DJI::onboardSDK::CoreAPI::setSessionStatus(uint32_t usageFlag)
+void DJI::onboardSDK::CoreAPI::setACKFrameStatus(uint32_t usageFlag)
{
- sessionStatus = usageFlag;
+ ackFrameStatus = usageFlag;
}
-uint32_t DJI::onboardSDK::CoreAPI::getSessionStatus()
+uint32_t DJI::onboardSDK::CoreAPI::getACKFrameStatus()
{
- return sessionStatus;
+ return ackFrameStatus;
}
void CoreAPI::setSyncFreq(uint32_t freqInHz)
diff --git a/dji_sdk_lib/src/DJI_Memory.cpp b/dji_sdk_lib/src/DJI_Memory.cpp
index 5be0eae5..8731469d 100644
--- a/dji_sdk_lib/src/DJI_Memory.cpp
+++ b/dji_sdk_lib/src/DJI_Memory.cpp
@@ -1,23 +1,18 @@
-/*! @brief
- * @file DJI_Memory.cpp
- * @version V2.0
- * @date Nov 11, 2015
- * @author wuyunwei,william.wu
+/** @file DJI_Memory.cpp
+ * @version 3.1.7
+ * @date July 1st, 2016
*
- * @abstract
- * This file mainly implement fuctions in DJI_API.h
+ * @brief
+ * Implement memory management for Core API of DJI onboardSDK library
+ *
+ * @copyright 2016 DJI. All right reserved.
*
- * 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
+ * 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.
+ *
*/
#include
diff --git a/dji_sdk_lib/src/DJI_Mission.cpp b/dji_sdk_lib/src/DJI_Mission.cpp
index 8c98fe7d..07c8f0be 100644
--- a/dji_sdk_lib/src/DJI_Mission.cpp
+++ b/dji_sdk_lib/src/DJI_Mission.cpp
@@ -18,7 +18,7 @@ namespace DJI
namespace onboardSDK
{
-MissionACKMap missionACK[] = {
+MissionACKMap missionACKMAP[] = {
//! @note common ACK code
{ 0x00, " 0x00 Success" },
{ 0x01, " 0x01 Wrong WayPoint Index" },
@@ -88,11 +88,11 @@ MissionACKMap missionACK[] = {
bool CoreAPI::decodeMissionStatus(uint8_t ack)
{
- for (uint8_t i = 0; i < sizeof(missionACK); ++i)
- if (missionACK[i].code == ack)
+ for (uint8_t i = 0; i < sizeof(missionACKMAP); ++i)
+ if (missionACKMAP[i].code == ack)
{
//! @todo Fix memory leak issue
- API_LOG(serialDevice, STATUS_LOG, "0x%X %s\n", missionACK[i].code, missionACK[i].meaning);
+ API_LOG(serialDevice, STATUS_LOG, "0x%X %s\n", missionACKMAP[i].code, missionACKMAP[i].meaning);
return true;
}
return false;
diff --git a/dji_sdk_lib/src/DJI_VirtualRC.cpp b/dji_sdk_lib/src/DJI_VirtualRC.cpp
index b88658cd..fdd27d49 100644
--- a/dji_sdk_lib/src/DJI_VirtualRC.cpp
+++ b/dji_sdk_lib/src/DJI_VirtualRC.cpp
@@ -1,9 +1,8 @@
-/** @brief
- * @file DJI_VirtualRC.cpp
+/**@file DJI_VirtualRC.cpp
* @version 3.1.7
* @date July 1st, 2016
*
- * @abstract
+ * @brief
* Virtual Radio Control API for DJI onboardSDK library
*
* @copyright 2016 DJI. All rights reserved.
diff --git a/dji_sdk_lib/src/DJI_WayPoint.cpp b/dji_sdk_lib/src/DJI_WayPoint.cpp
index 42edcffd..1a98fc71 100644
--- a/dji_sdk_lib/src/DJI_WayPoint.cpp
+++ b/dji_sdk_lib/src/DJI_WayPoint.cpp
@@ -3,14 +3,13 @@
* @version 3.1.7
* @date July 1st, 2016
*
-* @abstract
+* @brief
* Waypoint flight API for DJI onboardSDK library
*
* @copyright 2016 DJI. All right reserved.
*
*/
-
#include "DJI_WayPoint.h"
#include
@@ -41,6 +40,20 @@ void WayPoint::init(WayPointInitData *Info, CallBack callback, UserData userData
callback ? callback : missionCallback, userData);
}
+MissionACK WayPoint::init(WayPointInitData *Info, int timeout)
+{
+ if (Info)
+ setInfo(*Info);
+
+ api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_INIT, &info, sizeof(info), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void WayPoint::start(CallBack callback, UserData userData)
{
uint8_t start = 0;
@@ -49,6 +62,19 @@ void WayPoint::start(CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK WayPoint::start(int timeout)
+{
+ uint8_t start = 0;
+
+ api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_SETSTART, &start, sizeof(start), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void WayPoint::stop(CallBack callback, UserData userData)
{
uint8_t stop = 1;
@@ -57,6 +83,19 @@ void WayPoint::stop(CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK WayPoint::stop(int timeout)
+{
+ uint8_t stop = 1;
+
+ api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_SETSTART, &stop, sizeof(stop), 500, 2, 0,0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void WayPoint::pause(bool isPause, CallBack callback, UserData userData)
{
uint8_t data = isPause ? 0 : 1;
@@ -65,6 +104,19 @@ void WayPoint::pause(bool isPause, CallBack callback, UserData userData)
callback ? callback : missionCallback, userData);
}
+MissionACK WayPoint::pause(bool isPause, int timeout)
+{
+ uint8_t data = isPause ? 0 : 1;
+
+ api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_SETPAUSE, &data, sizeof(data), 500, 2, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.missionACK;
+}
+
void WayPoint::readIdleVelocity(CallBack callback, UserData userData)
{
uint8_t zero = 0;
@@ -93,6 +145,26 @@ bool WayPoint::uploadIndexData(uint8_t pos, CallBack callback, UserData userData
return true;
}
+WayPointDataACK WayPoint::uploadIndexData(WayPointData *data, int timeout)
+{
+ WayPointData wpData;
+
+ setIndex(data, data->index);
+
+ if (data->index < info.indexNumber)
+ wpData = index[data->index];
+ else
+ std::runtime_error("Range error.\n");
+
+ api->send(2, encrypt, SET_MISSION, CODE_WAYPOINT_ADDPOINT, &wpData, sizeof(wpData), 1000, 4, 0, 0);
+
+ api->serialDevice->lockACK();
+ api->serialDevice->wait(timeout);
+ api->serialDevice->freeACK();
+
+ return api->missionACKUnion.waypointDataACK;
+}
+
void WayPoint::updateIdleVelocity(float32_t meterPreSecond, CallBack callback,
UserData userData)
{
From 32f174c314228aff0dd768cda20180fb4c85e22f Mon Sep 17 00:00:00 2001
From: Arjun
Date: Fri, 5 Aug 2016 14:22:14 -0700
Subject: [PATCH 2/4] Added doxygen compliant updates to the code. Refere to
the previous commit for more information
---
.../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 +++++
254 files changed, 3564 insertions(+), 1153 deletions(-)
create mode 100644 dji_sdk_doc/doxygen/html/DJI__HardDriver_8cpp.html
create mode 100644 dji_sdk_doc/doxygen/html/DJI__Mission_8h.html
create mode 100644 dji_sdk_doc/doxygen/html/search/all_15.html
create mode 100644 dji_sdk_doc/doxygen/html/search/all_15.js
create mode 100644 dji_sdk_doc/doxygen/html/search/defines_4.html
create mode 100644 dji_sdk_doc/doxygen/html/search/defines_4.js
create mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_b.html
create mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_b.js
create mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_c.html
create mode 100644 dji_sdk_doc/doxygen/html/search/typedefs_c.js
create mode 100644 dji_sdk_doc/doxygen/html/search/variables_b.html
create mode 100644 dji_sdk_doc/doxygen/html/search/variables_b.js
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData-members.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK-members.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK-members.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData-members.html
create mode 100644 dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData.html
create mode 100644 dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion-members.html
create mode 100644 dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion.html
diff --git a/dji_sdk_doc/doxygen/html/DJICommonType_8h.html b/dji_sdk_doc/doxygen/html/DJICommonType_8h.html
index 3ef12d56..b9eef27c 100644
--- a/dji_sdk_doc/doxygen/html/DJICommonType_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJICommonType_8h.html
@@ -94,6 +94,9 @@
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.
@@ -127,11 +130,11 @@
typedef uint64_t
DJI::time_us
-typedef void * DJI::UserData
+typedef void *
DJI::UserData
+
This is used as the datatype for all data arguments in callbacks.
-typedef uint32_t DJI::Flag
-
This is used as the datatype for all data arguments in callbacks.
+typedef uint32_t
DJI::Flag
typedef uint8_t DJI::size8_t
@@ -155,14 +158,14 @@
-
Version 3.1.7
+
Common Type definition for DJI onboardSDK library. Officially Maintained.
+
Version 3.1.7
Date Jul 01 2016
-
Common Type definition for DJI onboardSDK library Officially Maintained
Copyright Copyright 2016 DJI . All rights reserved.
diff --git a/dji_sdk_doc/doxygen/html/DJICommonType_8h_source.html b/dji_sdk_doc/doxygen/html/DJICommonType_8h_source.html
index 343d6092..69191724 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. 28 typedef uint64_t time_ms;
29 typedef uint64_t time_us;
31 typedef void *UserData;
34 typedef uint8_t size8_t;
35 typedef uint16_t size16_t;
98 #endif // DJICOMMONTYPE Definition: DJICommonType.h:81
+
Go to the documentation of this file. 27 typedef uint64_t time_ms;
28 typedef uint64_t time_us;
32 typedef uint32_t Flag;
34 typedef uint8_t size8_t;
35 typedef uint16_t size16_t;
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 81c418ab..a85cc637 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 59cf5825..519b70a3 100644
--- a/dji_sdk_doc/doxygen/html/DJI__API_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__API_8h.html
@@ -116,7 +116,11 @@
-enum DJI::onboardSDK::ACK_COMMON_CODE {
+enum DJI::onboardSDK::ACK_ERROR_CODE { ACK_SUCCESS = 0x0000,
+ACK_PARAM_ERROR = 0x0001
+ }
+
+ enum ACK_COMMON_CODE {
ACK_COMMON_SUCCESS = 0x0000,
ACK_COMMON_KEYERROR = 0xFF00,
ACK_COMMON_NO_AUTHORIZATION = 0xFF01,
@@ -158,6 +162,10 @@
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,
@@ -261,16 +269,16 @@
Date July 1st, 2016
Copyright 2016 DJI . All rights reserved.
-
+
-
Todo: sort enum and move to a new file
+
Todo: sort enum and move to a new file
@@ -290,7 +298,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 ef04f305..6a926173 100644
--- a/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__API_8h_source.html
@@ -90,60 +90,73 @@
DJI_API.h
-
Go to the documentation of this file. 45 ACK_COMMON_SUCCESS = 0x0000,
46 ACK_COMMON_KEYERROR = 0xFF00,
47 ACK_COMMON_NO_AUTHORIZATION = 0xFF01,
48 ACK_COMMON_NO_RIGHTS = 0xFF02,
49 ACK_COMMON_NO_RESPONSE = 0xFFFF
54 ACK_ACTIVE_SUCCESS = 0x0000,
55 ACK_ACTIVE_PARAMETER_ERROR = 0x0001,
56 ACK_ACTIVE_ENCODE_ERROR = 0x0002,
57 ACK_ACTIVE_NEW_DEVICE = 0x0003,
58 ACK_ACTIVE_APP_NOT_CONNECTED = 0x0004,
59 ACK_ACTIVE_NO_INTERNET = 0x0005,
60 ACK_ACTIVE_SERVER_REFUSED = 0x0006,
61 ACK_ACTIVE_ACCESS_LEVEL_ERROR = 0x0007,
62 ACK_ACTIVE_VERSION_ERROR = 0x0008
65 enum ACK_SETCONTROL_CODE
67 ACK_SETCONTROL_NEED_MODE_F = 0x0000,
68 ACK_SETCONTROL_RELEASE_SUCCESS = 0x0001,
69 ACK_SETCONTROL_OBTAIN_SUCCESS = 0x0002,
70 ACK_SETCONTROL_OBTAIN_RUNNING = 0x0003,
71 ACK_SETCONTROL_RELEASE_RUNNING = 0x0004,
72 ACK_SETCONTROL_IOC = 0x00C9,
78 ACK_ARM_SUCCESS = 0x0000,
79 ACK_ARM_NEED_CONTROL = 0x0001,
80 ACK_ARM_ALREADY_ARMED = 0x0002,
81 ACK_ARM_IN_AIR = 0x0003,
88 SET_ACTIVATION = 0x00,
98 CODE_SYNC_BROADCAST = 0x00
103 CODE_HOTPOINT_START = 0x20,
104 CODE_HOTPOINT_STOP = 0x21,
105 CODE_HOTPOINT_SETPAUSE = 0x22,
106 CODE_HOTPOINT_YAWRATE = 0x23,
107 CODE_HOTPOINT_RADIUS = 0x24,
108 CODE_HOTPOINT_SETYAW = 0x25,
109 CODE_HOTPOINT_LOAD = 0x26
114 CODE_FOLLOW_START = 0x30,
115 CODE_FOLLOW_STOP = 0x31,
116 CODE_FOLLOW_SETPAUSE = 0X32,
117 CODE_FOLLOW_TARGET = 0X33
122 CODE_WAYPOINT_INIT = 0x10,
123 CODE_WAYPOINT_ADDPOINT = 0x11,
124 CODE_WAYPOINT_SETSTART = 0x12,
125 CODE_WAYPOINT_SETPAUSE = 0x13,
126 CODE_WAYPOINT_DOWNLOAD = 0x14,
127 CODE_WAYPOINT_INDEX = 0x15,
128 CODE_WAYPOINT_SETVELOCITY = 0x16,
129 CODE_WAYPOINT_GETVELOCITY = 0x17,
136 CODE_FREQUENCY = 0x10,
151 CODE_BROADCAST = 0x00,
152 CODE_LOSTCTRL = 0x01,
153 CODE_FROMMOBILE = 0x02,
160 CODE_VIRTUALRC_SETTINGS,
175 BROADCAST_FREQ_0HZ = 0,
176 BROADCAST_FREQ_1HZ = 1,
177 BROADCAST_FREQ_10HZ = 2,
178 BROADCAST_FREQ_50HZ = 3,
179 BROADCAST_FREQ_100HZ = 4,
180 BROADCAST_FREQ_HOLD = 5,
210 CallBack userRecvCallback = 0, UserData userData = 0);
212 bool userCallbackThread =
false );
214 void ack(
req_id_t req_id,
unsigned char *ackdata,
int len);
226 void send (
unsigned char session_mode,
unsigned char is_enc,
CMD_SET cmd_set,
227 unsigned char cmd_id,
void *pdata,
int len, CallBack ack_callback,
229 int timeout = 0,
int retry_time = 1);
230 void send (
unsigned char session_mode,
bool is_enc,
CMD_SET cmd_set,
unsigned char cmd_id,
231 void *pdata,
size_t len,
int timeout = 0,
int retry_time = 1,
232 CallBack ack_handler = 0,
234 UserData userData = 0);
250 void setControl(
bool enable, CallBack callback = 0, UserData userData = 0);
268 void sendToMobile(uint8_t *data, uint8_t len, CallBack callback = 0, UserData userData = 0);
289 void setBroadcastFreq (uint8_t *dataLenIs16, CallBack callback = 0, UserData userData = 0);
290 void setSessionStatus(uint32_t usageFlag);
291 uint32_t getSessionStatus();
292 void setSyncFreq(uint32_t freqInHz);
293 void setKey(
const char *key);
344 void setBroadcastCallback(
CallBackHandler callback) { broadcastCallback = callback; }
347 void setBroadcastCallback(CallBack handler, UserData userData = 0);
348 void setFromMobileCallback(CallBack handler, UserData userData = 0);
350 void setMisssionCallback(
CallBackHandler callback) { missionCallback = callback; }
351 void setHotPointCallback(
CallBackHandler callback) { hotPointCallback = callback; }
352 void setWayPointCallback(
CallBackHandler callback) { wayPointCallback = callback; }
353 void setFollowCallback(
CallBackHandler callback) { followCallback = callback; }
356 void setMisssionCallback(CallBack handler, UserData userData = 0);
357 void setHotPointCallback(CallBack handler, UserData userData = 0);
358 void setWayPointCallback(CallBack handler, UserData userData = 0);
359 void setFollowCallback(CallBack handler, UserData userData = 0);
360 void setWayPointEventCallback(CallBack handler, UserData userData = 0);
363 static void activateCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
364 static void getDroneVersionCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
365 static void setControlCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
366 static void sendToMobileCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
367 static void setFrequencyCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
371 uint32_t sessionStatus;
374 unsigned char encodeSendData[BUFFER_SIZE];
375 unsigned char encodeACK[ACK_SIZE];
391 unsigned short seq_num;
400 void recvReqData(
Header *protocolHeader);
401 void appHandler(
Header *protocolHeader);
402 void broadcast(
Header *protocolHeader);
404 int sendInterface(
Command *parameter);
405 int ackInterface(
Ack *parameter);
406 void sendData(
unsigned char *buf);
411 void setupSession(
void );
413 MMU_Tab *allocMemory(
unsigned short size);
416 CMDSession *allocSession(
unsigned short session_id,
unsigned short size);
419 ACKSession *allocACK(
unsigned short session_id,
unsigned short size);
424 ACKSession ACKSessionTab[SESSION_TABLE_NUM - 1];
425 unsigned char memory[MEMORY_SIZE];
428 unsigned short encrypt(
unsigned char *pdest,
const unsigned char *psrc,
429 unsigned short w_len,
unsigned char is_ack,
unsigned char is_enc,
430 unsigned char session_id,
unsigned short seq_num);
432 void streamHandler(
SDKFilter *p_filter,
unsigned char in_data);
437 void storeData(
SDKFilter *p_filter,
unsigned char in_data);
465 bool getFollowData()
const ;
493 #ifdef API_BUFFER_DATA 495 void setTotalRead(
const size_t &value) { totalRead = value; }
496 void setOnceRead(
const size_t &value) { onceRead = value; }
498 size_t getTotalRead()
const {
return totalRead; }
499 size_t getOnceRead()
const {
return onceRead; }
504 #endif // API_BUFFER_DATA TimeStampData getTime() const
Definition: DJI_API.cpp:219
-
void send(unsigned char session_mode, unsigned char is_enc, CMD_SET cmd_set, unsigned char cmd_id, void *pdata, int len, CallBack ack_callback, int timeout=0, int retry_time=1)
Definition: DJI_API.cpp:87
-
BroadcastData getBroadcastData() const
Definition: DJI_App.cpp:46
-
void getDroneVersion(CallBack callback=0, UserData userData=0)
Definition: DJI_API.cpp:154
-
HardDriver * getDriver() const
Definition: DJI_API.cpp:245
-
void setBroadcastFreq(uint8_t *dataLenIs16, CallBack callback=0, UserData userData=0)
Definition: DJI_API.cpp:193
-
void setWayPointData(bool value)
WayPoint Mission Control.
Definition: DJI_API.cpp:232
-
-
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:195
-
Definition: DJI_Type.h:345
-
Definition: DJI_HardDriver.h:31
-
Definition: DJI_Type.h:178
-
ACK_COMMON_CODE
Definition: DJI_API.h:43
-
-
ActivateData getAccountData() const
Activation Control.
Definition: DJI_API.cpp:228
-
Definition: DJI_Type.h:192
-
void setHotPointData(bool value)
HotPoint Mission Control.
Definition: DJI_API.cpp:231
-
-
bool getHotPointData() const
HotPoint Mission Control.
Definition: DJI_API.cpp:234
-
Definition: DJI_Type.h:170
-
uint32_t Version
Definition: DJI_Version.h:34
-
CMD_SET
Definition: DJI_API.h:86
-
Version 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
+
Go to the documentation of this file. 48 ACK_PARAM_ERROR = 0x0001
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
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
73 enum ACK_SETCONTROL_CODE
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,
86 ACK_ARM_SUCCESS = 0x0000,
87 ACK_ARM_NEED_CONTROL = 0x0001,
88 ACK_ARM_ALREADY_ARMED = 0x0002,
89 ACK_ARM_IN_AIR = 0x0003,
103 SET_ACTIVATION = 0x00,
105 SET_BROADCAST = 0x02,
113 CODE_SYNC_BROADCAST = 0x00
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
129 CODE_FOLLOW_START = 0x30,
130 CODE_FOLLOW_STOP = 0x31,
131 CODE_FOLLOW_SETPAUSE = 0X32,
132 CODE_FOLLOW_TARGET = 0X33
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,
151 CODE_FREQUENCY = 0x10,
166 CODE_BROADCAST = 0x00,
167 CODE_LOSTCTRL = 0x01,
168 CODE_FROMMOBILE = 0x02,
175 CODE_VIRTUALRC_SETTINGS,
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,
216 bool userCallbackThread =
false );
227 void ack(
req_id_t req_id,
unsigned char *ackdata,
int len);
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,
300 unsigned short setControl(
bool enable,
int timeout);
318 void sendToMobile(uint8_t *data, uint8_t len,
CallBack callback = 0,
UserData userData = 0);
364 void setBroadcastFreqToZero();
370 uint32_t getACKFrameStatus();
371 void setBroadcastFrameStatus(
bool isFrame);
372 bool getBroadcastFrameStatus();
374 void setSyncFreq(uint32_t freqInHz);
375 void setKey(
const char *key);
440 void setBroadcastCallback(
CallBackHandler callback) { broadcastCallback = callback; }
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; }
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;}
526 bool getFollowData()
const ;
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;}
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;}
579 uint32_t ackFrameStatus;
580 bool broadcastFrameStatus;
581 unsigned char encodeSendData[BUFFER_SIZE];
582 unsigned char encodeACK[ACK_SIZE];
608 bool obtainControlMobileCMD;
609 bool releaseControlMobileCMD;
610 bool activateMobileCMD;
612 bool disArmMobileCMD;
613 bool takeOffMobileCMD;
614 bool landingMobileCMD;
615 bool goHomeMobileCMD;
616 bool takePhotoMobileCMD;
617 bool startVideoMobileCMD;
618 bool stopVideoMobileCMD;
619 bool followMeMobileCMD;
624 unsigned short seq_num;
625 unsigned char *version_ack_data;
632 void recvReqData(
Header *protocolHeader);
633 void appHandler(
Header *protocolHeader);
634 void broadcast(
Header *protocolHeader);
636 int sendInterface(
Command *parameter);
637 int ackInterface(
Ack *parameter);
638 void sendData(
unsigned char *buf);
641 void setupSession(
void );
643 MMU_Tab *allocMemory(
unsigned short size);
646 CMDSession *allocSession(
unsigned short session_id,
unsigned short size);
649 ACKSession *allocACK(
unsigned short session_id,
unsigned short size);
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);
658 void streamHandler(
SDKFilter *p_filter,
unsigned char in_data);
663 void storeData(
SDKFilter *p_filter,
unsigned char in_data);
672 #ifdef API_BUFFER_DATA 674 void setTotalRead(
const size_t &value) { totalRead = value; }
675 void setOnceRead(
const size_t &value) { onceRead = value; }
677 size_t getTotalRead()
const {
return totalRead; }
678 size_t getOnceRead()
const {
return onceRead; }
683 #endif // API_BUFFER_DATA 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
+
+
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
void byteHandler(const uint8_t in_data)
Definition: DJI_Codec.cpp:761
-
void sendPoll(void)
Definition: DJI_Link.cpp:131
-
Definition: DJI_Type.h:200
-
BatteryData getBatteryCapacity() const
Definition: DJI_App.cpp:48
-
Definition: DJI_Type.h:145
+
void 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 byteStreamHandler(uint8_t *buffer, size_t size)
Definition: DJI_Codec.cpp:806
bool decodeACKStatus(unsigned short ack)
Definition: DJI_Codec.cpp:607
-
void callbackPoll(void)
Definition: DJI_Link.cpp:194
-
-
Definition: DJI_Type.h:139
-
-
FlightStatus getFlightStatus() const
Definition: DJI_API.cpp:221
+
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
+
+
FlightStatus getFlightStatus() const
Definition: DJI_API.cpp:419
bool decodeMissionStatus(uint8_t ack)
Definition: DJI_Mission.cpp:89
-
void setVersion(const Version &value)
Definition: DJI_API.cpp:381
-
void setDriver(HardDriver *value)
Definition: DJI_API.cpp:247
+
void setVersion(const Version &value)
Definition: DJI_API.cpp:730
+
Definition: DJI_Type.h:351
+
void setDriver(HardDriver *value)
Definition: DJI_API.cpp:459
Definition: DJI_Mission.cpp:16
-
bool getWayPointData() const
WayPoint Mission Control.
Definition: DJI_API.cpp:235
-
-
Definition: DJI_Type.h:412
-
void setActivation(bool isActivated)
Activation Control.
Definition: DJI_Link.cpp:208
-
-
Definition: DJI_Type.h:335
-
void setAccountData(const ActivateData &value)
Activation Control.
Definition: DJI_API.cpp:230
-
SDKFilter getFilter() const
Open Protocol Control.
Definition: DJI_API.cpp:379
+
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
diff --git a/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html
index 2e935b85..6ea828ac 100644
--- a/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__App_8cpp.html
@@ -92,6 +92,9 @@
DJI_App.cpp File Reference
+
+
Application layer support functionality for DJI onboardSDK library.
+More...
#include <string.h>
#include <stdio.h>
#include "DJI_App.h "
@@ -109,9 +112,9 @@
-Version 3.1.7
+
Application layer support functionality for DJI onboardSDK library.
+
Version 3.1.7
Date Jul 01 2016
-
Developer App support functionality for DJI onboardSDK library
Copyright 2016 DJI . All right reserved.
@@ -176,7 +179,7 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__App_8h.html b/dji_sdk_doc/doxygen/html/DJI__App_8h.html
index cc65f8d5..8a11a5e1 100644
--- a/dji_sdk_doc/doxygen/html/DJI__App_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__App_8h.html
@@ -88,12 +88,14 @@
+
+
Application layer support functionality for DJI onboardSDK library.
+More...
#include <stdint.h>
#include "DJI_Link.h "
#include "DJI_Type.h "
@@ -104,10 +106,6 @@
Classes
struct req_id_t
-
struct ActivateData
-
-
struct VersionData
-
@@ -138,38 +136,16 @@
#define STATUS_CMD_EXE_SUCCESS 0x0005
-
-
Version 3.1.7
+
Application layer support functionality for DJI onboardSDK library.
+
Version 3.1.7
Date Jul 1, 2016
-
Developer App support functionality for DJI onboardSDK library
Copyright 2016 DJI . All right reserved.
-
-
-
-
+
diff --git a/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html b/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html
index 7c488d82..36161fe0 100644
--- a/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__App_8h_source.html
@@ -90,17 +90,13 @@
DJI_App.h
-
Go to the documentation of this file. 21 #define MSG_ENABLE_FLAG_LEN 2 28 unsigned short sequence_number;
29 unsigned char session_id : 5;
30 unsigned char need_encrypt : 1;
31 unsigned char reserve : 2;
34 #define EXC_DATA_SIZE (16u) 35 #define SET_CMD_SIZE (2u) 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 53 unsigned int reserved;
55 unsigned char iosID[32];
61 unsigned short version_ack;
62 unsigned int version_crc;
64 char version_name[32];
-
-
-
uint32_t Version
Definition: DJI_Version.h:34
-
-
struct ActivateData ActivateData
-
+
Go to the documentation of this file. 20 #define MSG_ENABLE_FLAG_LEN 2 27 unsigned short sequence_number;
28 unsigned char session_id : 5;
29 unsigned char need_encrypt : 1;
30 unsigned char reserve : 2;
33 #define EXC_DATA_SIZE (16u) 34 #define SET_CMD_SIZE (2u) 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
+
Type definition for DJI onboardSDK library. Officially Maintained.
+
Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library...
diff --git a/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html
index 5efb64a8..4ad605e7 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Camera_8cpp.html
@@ -90,16 +90,19 @@
DJI_Camera.cpp File Reference
+
+
Camera/Gimbal API for DJI onboardSDK library.
+More...
-
Version 3.1.7
+
Camera/Gimbal API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Camera/Gimbal API for DJI onboardSDK library
Copyright 2016 DJI . All rights reserved.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html b/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html
index c13897c9..cf811bf9 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Camera_8h.html
@@ -93,6 +93,9 @@
DJI_Camera.h File Reference
+
+
Camera/Gimbal API for DJI onboardSDK library.
+More...
Go to the source code of this file.
@@ -100,6 +103,7 @@
class DJI::onboardSDK::Camera
+
Camera class for controlling camera and gimbal-related functions available through open protocol. More...
-
Version 3.1.7
+
Camera/Gimbal API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Camera/Gimbal API for DJI onboardSDK library
Copyright 2016 DJI . All rights reserved.
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 e288ffe6..8695372e 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. 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
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 ;
61 #endif // DJI_CAMERA_H Definition: DJI_Type.h:214
+
Go to the documentation of this file. 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
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 ;
61 #endif // DJI_CAMERA_H Definition: DJI_Type.h:222
Core API for DJI onboardSDK library.
-
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_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_Mission.cpp:16
-
void setCamera(CAMERA_CODE camera_cmd)
Definition: DJI_Camera.cpp:19
-
CoreAPI * getApi() const
Definition: DJI_Camera.cpp:66
+
void setCamera(CAMERA_CODE camera_cmd)
Definition: DJI_Camera.cpp:18
+
CoreAPI * getApi() const
Definition: DJI_Camera.cpp:65
diff --git a/dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Codec_8cpp.html
index f2b3c559..29ef56a3 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 @@
diff --git a/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html b/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html
index db46184d..7658fa42 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Codec_8h.html
@@ -93,6 +93,9 @@
DJI_Codec.h File Reference
+
+
Encoding/Message parsing features for DJI onboardSDK library.
+More...
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
@@ -141,29 +144,14 @@
-
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
+
Encoding/Message parsing features for DJI onboardSDK library.
+
Version 3.1.7
+
Date July 1st, 2016
+
Copyright 2016 DJI . All rights reserved.
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 ba6d0e8b..6e5c712d 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. 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) 38 #define _SDK_U32_SET(_addr, _val) (*((unsigned int *)(_addr)) = (_val)) 39 #define _SDK_U16_SET(_addr, _val) (*((unsigned short *)(_addr)) = (_val)) 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) 47 void transformTwoByte(
const char *pstr,
unsigned char *pdata);
+
Go to the documentation of this file. 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) 28 #define _SDK_U32_SET(_addr, _val) (*((unsigned int *)(_addr)) = (_val)) 29 #define _SDK_U16_SET(_addr, _val) (*((unsigned short *)(_addr)) = (_val)) 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) 37 void transformTwoByte(
const char *pstr,
unsigned char *pdata);
Type definition for DJI onboardSDK library. Officially Maintained.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Config_8h.html b/dji_sdk_doc/doxygen/html/DJI__Config_8h.html
index b0945ce4..7b48ceb0 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Config_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Config_8h.html
@@ -92,6 +92,9 @@
DJI_Config.h File Reference
+
+
Optional macro definitions for DJI Onboard SDK. Use for debugging.
+More...
#include <stdint.h>
#include "DJI_Version.h "
@@ -109,6 +112,7 @@
#define
ACK_SIZE 10
#define API_ERROR_DATA
+
Uncomment these macros to access various messages from the API. More...
#define API_STATUS_DATA
@@ -117,15 +121,10 @@
-
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
+
Optional macro definitions for DJI Onboard SDK. Use for debugging.
+
Version 3.1.7
+
Date Jul 01 2016
+
Copyright 2016 DJI . All rights reserved.
@@ -136,8 +135,10 @@
-
Note it means DJI onboardSDK library will not alloc memory from heap.
-
Todo: not available yet, only affect WayPoint
+
+
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.
@@ -150,14 +151,14 @@
-
Note if you do not want to use AES encrypt, comment this micro below
+
Note if you do NOT want to use AES encrypt, comment this macro 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 ccb101a8..a4a18b0f 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. 25 #define MEMORY_SIZE 1024 // unit is byte 26 #define BUFFER_SIZE 1024 37 #define API_ERROR_DATA 38 #define API_STATUS_DATA 46 #endif // DJI_CONFIG_H
+
Go to the documentation of this file. 16 #define MEMORY_SIZE 1024 // unit is byte 17 #define BUFFER_SIZE 1024 31 #define API_ERROR_DATA 32 #define API_STATUS_DATA 42 #endif // DJI_CONFIG_H Drone/SDK Version definition for DJI onboardSDK library Officially Maintained.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Flight_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Flight_8cpp.html
index ef7a61b1..f68f3c5e 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 bd5dcbb0..c8fb7b98 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 c5cb2eef..384bf13c 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Flight_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Flight_8h_source.html
@@ -90,29 +90,31 @@
DJI_Flight.h
-
Go to the documentation of this file. 46 VERTICAL_VELOCITY = 0x00,
47 VERTICAL_POSITION = 0x10,
48 VERTICAL_THRUST = 0x20,
53 HORIZONTAL_ANGLE = 0x00,
54 HORIZONTAL_VELOCITY = 0x40,
55 HORIZONTAL_POSITION = 0X80,
64 enum HorizontalCoordinate
66 HORIZONTAL_GROUND = 0x00,
67 HORIZONTAL_BODY = 0x02
79 SMOOTH_DISABLE = 0x00,
85 STATUS_GROUND_STANDBY = 1,
87 STATUS_SKY_STANDBY = 3,
89 STATUS_FINISHING_LANDING = 5,
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
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);
158 Device getControlDevice()
const ;
159 Status getStatus()
const ;
160 Mode getControlMode()
const ;
162 Angle getYaw()
const ;
163 Angle getRoll()
const ;
164 Angle getPitch()
const ;
167 static void armCallback(
CoreAPI *api,
Header *protoclHeader, UserData userData = 0);
168 static void taskCallback(
CoreAPI *api,
Header *protocolHeader, UserData userData = 0);
191 #ifdef USE_SIMULATION 193 bool isSimulating()
const ;
194 void setSimulating(
bool value);
201 #endif // USE_SIMULATION 206 #endif // DJI_FLIGHT_H Definition: DJICommonType.h:81
-
Definition: DJI_Type.h:309
+
Go to the documentation of this file. 46 VERTICAL_VELOCITY = 0x00,
47 VERTICAL_POSITION = 0x10,
48 VERTICAL_THRUST = 0x20,
53 HORIZONTAL_ANGLE = 0x00,
54 HORIZONTAL_VELOCITY = 0x40,
55 HORIZONTAL_POSITION = 0X80,
64 enum HorizontalCoordinate
66 HORIZONTAL_GROUND = 0x00,
67 HORIZONTAL_BODY = 0x02
79 SMOOTH_DISABLE = 0x00,
85 STATUS_GROUND_STANDBY = 1,
87 STATUS_SKY_STANDBY = 3,
89 STATUS_FINISHING_LANDING = 5,
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
141 unsigned short task(TASK taskname,
int timer);
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);
161 Device getControlDevice()
const ;
162 Status getStatus()
const ;
163 Mode getControlMode()
const ;
165 Angle getYaw()
const ;
166 Angle getRoll()
const ;
167 Angle getPitch()
const ;
194 #ifdef USE_SIMULATION 196 bool isSimulating()
const ;
197 void setSimulating(
bool value);
204 #endif // USE_SIMULATION 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
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:195
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded pl...
Definition: DJI_API.h:210
Definition: DJICommonType.h:60
-
Definition: DJI_Type.h:366
-
Definition: DJI_Type.h:269
+
Definition: DJI_Type.h:489
+
Definition: DJI_Type.h:392
Definition: DJI_Flight.h:22
-
Mode
Definition: DJI_Flight.h:100
+
Mode
Definition: DJI_Flight.h:101
double Angle
Definition: DJICommonType.h:78
SmoothMode
Definition: DJI_Flight.h:77
-
Definition: DJI_Type.h:259
-
+
Definition: DJI_Type.h:382
+
void * UserData
This is used as the datatype for all data arguments in callbacks.
Definition: DJICommonType.h:31
+
Flight class encapsulates all flight control related functions provided by the DJI OnboardSDK...
Definition: DJI_Flight.h:34
-
Definition: DJI_Type.h:234
+
Definition: DJI_Type.h:357
Definition: DJI_Mission.cpp:16
-
Definition: DJI_Type.h:243
+
Definition: DJI_Type.h:366
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 b991de94..5879865f 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Follow_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Follow_8cpp.html
@@ -90,16 +90,19 @@
DJI_Follow.cpp File Reference
+
+
Follow API for DJI onboardSDK library.
+More...
-
Version 3.1.7
+
Follow API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Follow API for DJI onboardSDK library
Copyright 2016 DJI . All right reserved.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html b/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html
index 2e3b6251..5cde6593 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Follow_8h.html
@@ -94,7 +94,10 @@
DJI_Follow.h File Reference
-
#include "DJI_Mission.h"
+
+
Follow API for DJI onboardSDK library.
+More...
+
Go to the source code of this file.
-
Version 3.1.7
+
Follow API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Follow API for DJI onboardSDK library
Copyright 2016 DJI . All right reserved.
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 dbbd0db9..2377596e 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Follow_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Follow_8h_source.html
@@ -90,17 +90,20 @@
DJI_Follow.h
-
Go to the documentation of this file. 16 #include "DJI_Mission.h" 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);
75 void updateTarget(float64_t latitude, float64_t longitude, uint16_t height,
80 void setMode(
const MODE mode);
82 void setYawType(
const YAW_TYPE type);
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
+
Go to the documentation of this file. 71 void stop(CallBack callback = 0,
UserData userData = 0);
74 void pause(
bool isPause, CallBack callback = 0,
UserData userData = 0);
77 void updateTarget(float64_t latitude, float64_t longitude, uint16_t height,
82 void setMode(
const MODE mode);
84 void setYawType(
const YAW_TYPE type);
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
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
new file mode 100644
index 00000000..e7524b8e
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8cpp.html
@@ -0,0 +1,110 @@
+
+
+
+
+
+
+
Onboard-SDK-ROS: dji_sdk_lib/src/DJI_HardDriver.cpp File Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Serial device driver abstraction. See DJI_HardDriver.h for more info.
+More...
+
+
Serial device driver abstraction. See DJI_HardDriver.h for more info.
+
Version 3.1.7
+
Date Jul 01 2016
+
Copyright 2016 DJI . All rights reserved.
+
+
+
+
+
diff --git a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html
index 2b0c955b..fef3ade9 100644
--- a/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__HardDriver_8h.html
@@ -93,6 +93,9 @@
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 "
@@ -110,19 +113,14 @@
-
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
+
Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms.
+
Version 3.1.7
+
Date Jul 01 2016
+
Copyright 2016 DJI . All rights reserved.
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 fa638043..ba243c11 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. 19 #ifndef DJI_HARDDRIVER_H 20 #define DJI_HARDDRIVER_H 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;
90 virtual void lockMemory() = 0;
91 virtual void freeMemory() = 0;
93 virtual void lockMSG() = 0;
94 virtual void freeMSG() = 0;
97 virtual void displayLog(
const char *buf = 0);
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
-
+
Go to the documentation of this file. 12 #ifndef DJI_HARDDRIVER_H 13 #define DJI_HARDDRIVER_H 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;
87 virtual void lockMemory() = 0;
88 virtual void freeMemory() = 0;
90 virtual void lockMSG() = 0;
91 virtual void freeMSG() = 0;
93 virtual void lockACK() = 0;
94 virtual void freeACK() = 0;
96 virtual void notify() = 0;
97 virtual void wait(
int timeout) = 0;
100 virtual void displayLog(
const char *buf = 0);
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.
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 1cc81c2e..544e9eea 100644
--- a/dji_sdk_doc/doxygen/html/DJI__HotPoint_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__HotPoint_8cpp.html
@@ -90,17 +90,20 @@
DJI_HotPoint.cpp File Reference
-
#include "DJI_HotPoint.h "
+
+
Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library.
+More...
+
#include "DJI_HotPoint.h"
#include <string.h>
-
Version 3.1.7
+
Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library
-
Copyright 2016 DJI . All right reserved.
+
Copyright 2016 DJI . All rights reserved.
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 b58c20d6..e17e98e8 100644
--- a/dji_sdk_doc/doxygen/html/DJI__HotPoint_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__HotPoint_8h_source.html
@@ -90,19 +90,24 @@
DJI_HotPoint.h
-
Go to the documentation of this file. 20 #ifndef DJI_HOTPOINT_H 21 #define DJI_HOTPOINT_H 23 #include "DJI_Mission.h" 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);
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);
113 void readData(CallBack callback = 0, UserData userData = 0);
118 void setHotPoint(float64_t longtitude, float64_t latitude, float64_t altitude);
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);
129 static void startCallback(
CoreAPI *api,
Header *protocolHeader, UserData userdata = 0);
130 static void readCallback(
CoreAPI *api,
Header *protoclHeader, UserData userdata);
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_HotPoint.h:67
+
12 #ifndef DJI_HOTPOINT_H 13 #define DJI_HOTPOINT_H 71 void updateYawRate(float32_t yawRate,
bool isClockwise,
CallBack callback = 0,
73 void updateRadius(float32_t meter,
CallBack callback = 0,
UserData userData = 0);
74 MissionACK updateRadius(float32_t meter,
int timer);
84 void setHotPoint(float64_t longtitude, float64_t latitude, float64_t altitude);
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);
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
+
Definition: DJI_Mission.cpp:16
-
Definition: DJI_Type.h:326
+
void start(CallBack callback=0, UserData userData=0)
Definition: DJI_HotPoint.cpp:40
+
Definition: DJI_Type.h:449
diff --git a/dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Link_8cpp.html
index ecffde3d..83c6689b 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 ff0ac69b..3a110913 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Link_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Link_8h.html
@@ -92,6 +92,9 @@
DJI_Link.h File Reference
+
+
Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library.
+More...
Go to the source code of this file.
@@ -121,21 +124,15 @@
-
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
+
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
+
Copyright 2016 DJI . All right reserved.
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 2534ff5c..4a78a628 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. 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 34 #define POLL_TICK 20 // unit is ms
+
Go to the documentation of this file. 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 23 #define POLL_TICK 20 // unit is ms Type definition for DJI onboardSDK library. Officially Maintained.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html
index 46c1f4d5..76841da3 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Memory_8cpp.html
@@ -92,6 +92,9 @@
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"
@@ -104,16 +107,15 @@
-
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
+
Implement memory management for Core API of DJI onboardSDK library.
+
Version 3.1.7
+
Date July 1st, 2016
+
Copyright 2016 DJI . All right reserved.
+
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.
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 af540f82..61ef7355 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
-
+
17 #endif // DJI_MEMORY_H Type definition for DJI onboardSDK library. Officially Maintained.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Mission_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__Mission_8cpp.html
index 096f3469..66f6f630 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>
DJI::onboardSDK::missionCallback (CoreAPI *api, Header *protocolHeader, UserData userdata __UNUSED )
-
-MissionACKMap DJI::onboardSDK::missionACK []
-
+
+MissionACKMap DJI::onboardSDK::missionACKMAP []
+
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
new file mode 100644
index 00000000..ebc9702a
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/DJI__Mission_8h.html
@@ -0,0 +1,164 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: dji_sdk_lib/include/dji_sdk_lib/DJI_Mission.h File Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Mission Framework for DJI onboardSDK library.
+More...
+
#include "DJI_Config.h "
+
#include "DJI_API.h "
+
+
Go to the source code of this file.
+
+
+
+void DJI::onboardSDK::missionCallback (CoreAPI *api, Header *protocolHeader, UserData userdata __UNUSED )
+
+
+
+
Mission Framework for DJI onboardSDK library.
+
Version 3.1.7
+
Date July 1st, 2016
+
Copyright 2016 DJI . All right reserved.
+
+
+
+
+
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 af2eeae1..51b8b18f 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Mission_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Mission_8h_source.html
@@ -90,18 +90,19 @@
DJI_Mission.h
-
59 void missionCallback(
CoreAPI *api,
Header *protocolHeader, UserData userdata = 0);
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
-
+
Go to the documentation of this file. 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
+
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 2d294718..fc1e02ad 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Type_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Type_8h.html
@@ -96,6 +96,9 @@
DJI_Type.h File Reference
+
+
Type definition for DJI onboardSDK library. Officially Maintained.
+More...
#include "DJI_Config.h "
#include "DJICommonType.h "
#include <stdio.h>
@@ -105,8 +108,10 @@
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
@@ -124,6 +129,24 @@
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
@@ -162,6 +185,10 @@
struct DJI::onboardSDK::VirtualRCData
+
struct DJI::onboardSDK::ActivateData
+
+
struct DJI::onboardSDK::VersionData
+
@@ -173,12 +200,14 @@
#define NAME (x) #x
-#define __UNUSED
+#define __UNUSED
+ Define the UNUSED macro to suppress compiler warnings about unused arguments.
#define __DELETE (x) delete x
#define API_LOG (driver, title, fmt, ...)
+ This is the default status printing mechanism. More...
#define DEBUG_LOG 0
@@ -205,13 +234,16 @@
-typedef struct DJI::onboardSDK::Header DJI::onboardSDK::Header
+typedef struct DJI::onboardSDK::Header DJI::onboardSDK::Header
+ The Header struct is meant to handle the open protocol header.
-typedef void(* DJI::onboardSDK::CallBack ) (DJI::onboardSDK::CoreAPI *, Header *, UserData)
+typedef void(* DJI::onboardSDK::CallBack ) (DJI::onboardSDK::CoreAPI *, Header *, UserData)
+ The CallBack function pointer is used as an argument in api->send calls.
-typedef struct DJI::onboardSDK::CallBackHandler DJI::onboardSDK::CallBackHandler
+typedef struct DJI::onboardSDK::CallBackHandler DJI::onboardSDK::CallBackHandler
+ The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.
typedef struct DJI::onboardSDK::Command DJI::onboardSDK::Command
@@ -232,11 +264,7 @@
typedef uint8_t DJI::onboardSDK::BatteryData
-
-typedef uint8_t DJI::onboardSDK::MissionACK
-
-
-typedef struct DJI::onboardSDK::GimbalAngleData DJI::onboardSDK::GimbalAngleData
+typedef struct DJI::onboardSDK::GimbalAngleData DJI::onboardSDK::GimbalAngleData
typedef struct DJI::onboardSDK::GimbalSpeedData DJI::onboardSDK::GimbalSpeedData
@@ -247,6 +275,36 @@
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
@@ -297,6 +355,12 @@
typedef struct DJI::onboardSDK::VirtualRCData DJI::onboardSDK::VirtualRCData
+
+typedef struct DJI::onboardSDK::ActivateData DJI::onboardSDK::ActivateData
+
+
+typedef struct DJI::onboardSDK::VersionData DJI::onboardSDK::VersionData
+
-
Version 3.1.7
+
Type definition for DJI onboardSDK library. Officially Maintained.
+
Version 3.1.7
Date Jul 01 2016
-
Type definition for DJI onboardSDK library Officially Maintained
Copyright Copyright 2016 DJI . All rights reserved.
@@ -360,7 +424,9 @@
-
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.
+
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.
@@ -377,7 +443,7 @@
-
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.
+
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.
@@ -391,7 +457,7 @@
@@ -406,6 +472,19 @@
+
+
+
@@ -417,7 +496,7 @@
-
Todo: rename to a final version
+
Todo: rename to a final version Detailed GPSData from the A3. This is not available on the M100.
@@ -432,6 +511,19 @@
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.
+
+
+
+
@@ -458,6 +550,19 @@
+
+
+
@@ -508,7 +613,7 @@
-
Todo: rename to a final version
+
Todo: rename to a final version RTKData from the A3. This is not available on the M100.
@@ -536,12 +641,25 @@
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 d143b4cb..b075a79b 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Type_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Type_8h_source.html
@@ -90,60 +90,77 @@
DJI_Type.h
-
Go to the documentation of this file. 30 #define __UNUSED __attribute__((__unused__)) 31 #define __DELETE(x) delete (char *) x 34 #define __DELETE(x) delete x 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) 50 #define __func__ __FUNCTION__ 53 #define API_LOG(driver, title, fmt, ...) \ 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(); \ 61 (driver)->displayLog("ERROR: log printer inner fault\n"); \ 64 #define DEBUG_LOG "DEBUG" 70 #define ERROR_LOG "ERROR" 75 #ifdef API_BUFFER_DATA 76 #define BUFFER_LOG "BUFFER" 81 #ifdef API_STATUS_DATA 82 #define STATUS_LOG "STATUS" 87 #ifdef API_MISSION_DATA 88 #define MISSION_LOG "MISSION" 94 #define RTK_LOG "MISSION" 109 const size_t bufsize = 1024;
110 extern char buffer[];
111 extern uint8_t encrypt;
113 const size_t SESSION_TABLE_NUM = 32;
114 const size_t CALLBACK_LIST_NUM = 10;
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;
128 unsigned int padding : 5;
129 unsigned int enc : 3;
133 unsigned int sequenceNumber : 16;
134 unsigned int crc : 16;
147 unsigned short sessionMode : 2;
148 unsigned short encrypt : 1;
149 unsigned short retry : 13;
150 unsigned short timeout;
160 unsigned short reuseIndex;
161 unsigned short reuseCount;
162 unsigned short recvIndex;
163 unsigned char recvBuf[BUFFER_SIZE];
165 unsigned char sdkKey[32];
166 unsigned char encode;
172 unsigned int tabIndex : 8;
173 unsigned int usageFlag : 8;
174 unsigned int memSize : 16;
180 uint32_t sessionID : 5;
181 uint32_t usageFlag : 1;
184 uint32_t timeout : 16;
189 time_ms preTimestamp;
194 uint32_t sessionID : 5;
195 uint32_t sessionStatus : 2;
202 uint16_t sessionID : 8;
203 uint16_t encrypt : 8;
211 typedef uint8_t BatteryData;
212 typedef uint8_t MissionACK;
231 typedef float float32_t;
232 typedef double float64_t;
265 uint8_t sensorID : 4;
339 uint8_t deviceStatus : 3;
340 uint8_t flightStatus : 1;
341 uint8_t vrcStatus : 1;
342 uint8_t reserved : 3;
358 uint8_t pitchLimit : 1;
359 uint8_t rollLimit : 1;
360 uint8_t yawLimit : 1;
361 uint8_t reserved : 5;
364 typedef uint8_t FlightStatus;
368 unsigned char cmdSequence;
369 unsigned char cmdData;
382 float32_t velocityNorth;
383 float32_t velocityEast;
403 float32_t velocityNorth;
404 float32_t velocityEast;
414 unsigned short dataFlag;
444 uint8_t reserved : 6;
477 #define PRO_PURE_DATA_MAX_SIZE 1007 // 2^10 - header size 478 const size_t MMU_TABLE_NUM = 32;
-
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
-
-
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:373
-
Definition: DJI_Type.h:234
+
Go to the documentation of this file. 30 #define __UNUSED __attribute__((__unused__)) 31 #define __DELETE(x) delete (char *) x 34 #define __DELETE(x) delete x 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) 50 #define __func__ __FUNCTION__ 55 #define API_LOG(driver, title, fmt, ...) \ 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(); \ 63 (driver)->displayLog("ERROR: log printer inner fault\n"); \ 66 #define DEBUG_LOG "DEBUG" 72 #define ERROR_LOG "ERROR" 77 #ifdef API_BUFFER_DATA 78 #define BUFFER_LOG "BUFFER" 83 #ifdef API_STATUS_DATA 84 #define STATUS_LOG "STATUS" 89 #ifdef API_MISSION_DATA 90 #define MISSION_LOG "MISSION" 96 #define RTK_LOG "MISSION" 111 const size_t bufsize = 1024;
112 extern char buffer[];
113 extern uint8_t encrypt;
115 const size_t SESSION_TABLE_NUM = 32;
116 const size_t CALLBACK_LIST_NUM = 10;
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;
132 unsigned int padding : 5;
133 unsigned int enc : 3;
137 unsigned int sequenceNumber : 16;
138 unsigned int crc : 16;
153 unsigned short sessionMode : 2;
154 unsigned short encrypt : 1;
155 unsigned short retry : 13;
156 unsigned short timeout;
166 unsigned short reuseIndex;
167 unsigned short reuseCount;
168 unsigned short recvIndex;
169 unsigned char recvBuf[BUFFER_SIZE];
171 unsigned char sdkKey[32];
172 unsigned char encode;
178 unsigned int tabIndex : 8;
179 unsigned int usageFlag : 8;
180 unsigned int memSize : 16;
186 uint32_t sessionID : 5;
187 uint32_t usageFlag : 1;
190 uint32_t timeout : 16;
195 time_ms preTimestamp;
200 uint32_t sessionID : 5;
201 uint32_t sessionStatus : 2;
208 uint16_t sessionID : 8;
209 uint16_t encrypt : 8;
217 typedef uint8_t BatteryData;
239 typedef float float32_t;
240 typedef double float64_t;
259 uint8_t reserved[11];
268 float32_t maxVelocity;
269 float32_t idleVelocity;
271 uint8_t finishAction;
272 uint8_t executiveTimes;
275 uint8_t RCLostAction;
281 uint8_t reserved[16];
299 uint16_t actionTimeLimit;
301 uint8_t actionNumber : 4;
302 uint8_t actionRepeat : 4;
304 uint8_t commandList[16];
305 int16_t commandParameter[16];
313 typedef uint32_t SimpleACK;
330 float32_t idleVelocity;
336 uint8_t raw_ack_array[5];
337 MissionACK missionACK;
388 uint8_t sensorID : 4;
462 uint8_t deviceStatus : 3;
463 uint8_t flightStatus : 1;
464 uint8_t vrcStatus : 1;
465 uint8_t reserved : 3;
481 uint8_t pitchLimit : 1;
482 uint8_t rollLimit : 1;
483 uint8_t yawLimit : 1;
484 uint8_t reserved : 5;
487 typedef uint8_t FlightStatus;
491 unsigned char cmdSequence;
492 unsigned char cmdData;
506 float32_t velocityNorth;
507 float32_t velocityEast;
528 float32_t velocityNorth;
529 float32_t velocityEast;
539 unsigned short dataFlag;
569 uint8_t reserved : 6;
598 unsigned int reserved;
599 unsigned int version;
600 unsigned char iosID[32];
606 unsigned short version_ack;
607 unsigned int version_crc;
609 char version_name[32];
620 #define PRO_PURE_DATA_MAX_SIZE 1007 // 2^10 - header size 621 const size_t MMU_TABLE_NUM = 32;
+
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
+
+
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
+
+
Definition: DJI_Type.h:351
+
Definition: DJI_Type.h:497
+
Definition: DJI_Type.h:327
+
Definition: DJI_Type.h:357
Definition: DJI_Mission.cpp:16
-
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
-
+
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.
diff --git a/dji_sdk_doc/doxygen/html/DJI__Version_8h.html b/dji_sdk_doc/doxygen/html/DJI__Version_8h.html
index 499fd6d5..d08eab02 100644
--- a/dji_sdk_doc/doxygen/html/DJI__Version_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__Version_8h.html
@@ -95,6 +95,9 @@
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.
@@ -111,7 +114,9 @@
-
Version 3.1.7
+
Drone/SDK Version definition for DJI onboardSDK library Officially Maintained.
+
Version 3.1.7
Date Jul 01 2016
-
Drone/SDK Version definition for DJI onboardSDK library Officially Maintained
Copyright Copyright 2016 DJI . All rights reserved.
@@ -172,26 +177,12 @@
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.
-
-
-
-
-
-
-
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 4b103d52..615b3e8b 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. 25 #define MAKE_VERSION(a, b, c, d) \ 26 (((a << 24) & 0xff000000) | ((b << 16) & 0x00ff0000) | ((c << 8) & 0x0000ff00) | \ 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;
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
+
Go to the documentation of this file. 24 #define MAKE_VERSION(a, b, c, d) \ 25 (((a << 24) & 0xff000000) | ((b << 16) & 0x00ff0000) | ((c << 8) & 0x0000ff00) | \ 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;
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
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 616a9910..bbd03977 100644
--- a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8cpp.html
@@ -90,16 +90,19 @@
DJI_VirtualRC.cpp File Reference
+
+
Virtual Radio Control API for DJI onboardSDK library.
+More...
-
Version 3.1.7
+
Virtual Radio Control API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Virtual Radio Control API for DJI onboardSDK library
Copyright 2016 DJI . All rights reserved.
diff --git a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html
index 6e52ea6e..610f0b14 100644
--- a/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__VirtualRC_8h.html
@@ -93,6 +93,9 @@
DJI_VirtualRC.h File Reference
+
+
Virtual Radio Control API for DJI onboardSDK library.
+More...
Go to the source code of this file.
@@ -109,14 +112,14 @@
-
Version 3.1.7
+
Virtual Radio Control API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Virtual Radio Control API for DJI onboardSDK library
Copyright 2016 DJI . All rights reserved.
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 336537d1..d2b3b3ca 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. 14 #ifndef DJI_VIRTUALRC_H 15 #define DJI_VIRTUALRC_H 83 void setControl (
bool enable, CutOff cutoffType);
98 bool isVirtualRC()
const ;
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
+
Go to the documentation of this file. 13 #ifndef DJI_VIRTUALRC_H 14 #define DJI_VIRTUALRC_H 82 void setControl (
bool enable, CutOff cutoffType);
97 bool isVirtualRC()
const ;
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
Core API for DJI onboardSDK library.
-
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
+
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
Definition: DJI_Mission.cpp:16
-
void sendSafeModeData()
This function will be deprecated in the future. Please use neutralVRCSticks() instead.
Definition: DJI_VirtualRC.cpp:67
+
void sendSafeModeData()
This function will be deprecated in the future. Please use neutralVRCSticks() instead.
Definition: DJI_VirtualRC.cpp:66
diff --git a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html
index 5cf446d7..c099ebb8 100644
--- a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html
+++ b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8cpp.html
@@ -90,17 +90,20 @@
DJI_WayPoint.cpp File Reference
+
+
Waypoint flight API for DJI onboardSDK library.
+More...
#include "DJI_WayPoint.h "
#include <string.h>
-
Version 3.1.7
+
Waypoint flight API for DJI onboardSDK library.
+
Version 3.1.7
Date July 1st, 2016
-
Waypoint flight API for DJI onboardSDK library
Copyright 2016 DJI . All right reserved.
diff --git a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html
index ce321659..566e1a06 100644
--- a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html
+++ b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h.html
@@ -88,28 +88,21 @@
-
#include "DJI_Mission.h"
+
+
Waypoint flight API for DJI onboardSDK library.
+More...
+
#include "DJI_Mission.h "
+
#include <stdexcept>
Go to the source code of this file.
@@ -117,39 +110,16 @@
Namespaces
DJI
-
-
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
+
Waypoint flight API for DJI onboardSDK library.
+
Version 3.1.7
+
Date July 1st, 2016
+
Copyright 2016 DJI . All right reserved.
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 4c9b11e2..1ac4f95b 100644
--- a/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h_source.html
+++ b/dji_sdk_doc/doxygen/html/DJI__WayPoint_8h_source.html
@@ -90,21 +90,26 @@
DJI_WayPoint.h
-
Go to the documentation of this file. 19 #include "DJI_Mission.h" 21 #ifndef DJI_WAYPOINT_H 22 #define DJI_WAYPOINT_H 35 float32_t maxVelocity;
36 float32_t idleVelocity;
39 uint8_t executiveTimes;
66 uint16_t actionTimeLimit;
68 uint8_t actionNumber : 4;
69 uint8_t actionRepeat : 4;
71 uint8_t commandList[16];
72 int16_t commandParameter[16];
78 float32_t idleVelocity;
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);
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);
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);
137 #endif // STATIC_MEMORY 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_WayPoint.h:81
-
Definition: DJI_WayPoint.h:75
+
Go to the documentation of this file. 16 #ifndef DJI_WAYPOINT_H 17 #define DJI_WAYPOINT_H 31 #endif // STATIC_MEMORY 49 void updateIdleVelocity(float32_t meterPreSecond,
CallBack callback = 0,
71 #endif // STATIC_MEMORY 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
+
Definition: DJI_Mission.cpp:16
-
float32_t altitude
not supported yet
Definition: DJI_WayPoint.h:46
-
float64_t longitude
Definition: DJI_WayPoint.h:45
-
Definition: DJI_WayPoint.h:32
+
bool uploadIndexData(WayPointData *data, CallBack callback=0, UserData userData=0)
Definition: DJI_WayPoint.cpp:128
+
Definition: DJI_Type.h:265
diff --git a/dji_sdk_doc/doxygen/html/annotated.html b/dji_sdk_doc/doxygen/html/annotated.html
index 9b7f8912..1bb546d8 100644
--- a/dji_sdk_doc/doxygen/html/annotated.html
+++ b/dji_sdk_doc/doxygen/html/annotated.html
@@ -93,72 +93,73 @@
▼ N onboardSDK
C Ack
C ACKSession
-
C BroadcastData
-
C CallBackHandler
-
C Camera
-
C CMDSession
-
C Command
-
C CommonData
-
C CoreAPI CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform
-
C CtrlInfoData
-
C Flight Flight class encapsulates all flight control related functions provided by the DJI OnboardSDK
-
C FlightData
-
C Follow Follow class encapsulates all follow control related functions provided by the DJI OnboardSDK
-
C FollowData
-
C FollowTarget
-
C GimbalAngleData
-
C GimbalData
-
C GimbalSpeedData
-
C GPSData
-
C GPSPositionData
-
C GSPushData
-
C HardDriver
-
C Header
-
▼ C HotPoint
-
C ReadACK
-
C StartACK
-
C YawRate
-
C HotPointACKData
-
C HotPointData
-
C MagData
-
C MagnetData
-
C MissionACKMap
-
C MMU_Tab
-
C PositionData
-
C QuaternionData
-
C RadioData
-
C RCData
-
C RTKData
-
C SDKFilter
-
C TaskData
-
C TimeStampData
-
C Vector3fData
-
C VelocityData
-
C VirtualRC VirtualRC class has all the methods to mimic the RC functionality via OnboardSDK
-
C VirtualRCData
-
C VirtualRCSetting
-
C WayPoint
-
C WayPointData
-
C WayPointDataACK
-
C WayPointInitACK
-
C WayPointInitData
-
C WayPointVelocityACK
-
C EulerAngle
-
C EulerianAngle
-
C Measure
-
C Measurement
-
C SpaceVector
-
C Vector3dData
-
C ActivateData
-
C req_id_t
-
C tagAES256Context
-
C VersionData
+
C ActivateData
+
C BroadcastData
+
C CallBackHandler The CallBackHandler struct allows users to encapsulate callbacks and data in one struct
+
C Camera Camera class for controlling camera and gimbal-related functions available through open protocol
+
C CMDSession
+
C Command
+
C CommonData
+
C CoreAPI CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform
+
C CtrlInfoData
+
C Flight Flight class encapsulates all flight control related functions provided by the DJI OnboardSDK
+
C FlightData
+
C Follow Follow class encapsulates all follow control related functions provided by the DJI OnboardSDK
+
C FollowData
+
C FollowTarget
+
C GimbalAngleData
+
C GimbalData
+
C GimbalSpeedData
+
C GPSData
+
C GPSPositionData
+
C GSPushData
+
C HardDriver
+
C Header The Header struct is meant to handle the open protocol header
+
▼ C HotPoint
+
C YawRate
+
C HotPointACKData
+
C HotPointData
+
C HotPointReadACK
+
C HotPointStartACK
+
C MagData
+
C MagnetData
+
C MissionACKMap
+
C MissionACKUnion
+
C MMU_Tab
+
C PositionData
+
C QuaternionData
+
C RadioData
+
C RCData
+
C RTKData
+
C SDKFilter
+
C TaskData
+
C TimeStampData
+
C Vector3fData
+
C VelocityData
+
C VersionData
+
C VirtualRC VirtualRC class has all the methods to mimic the RC functionality via OnboardSDK
+
C VirtualRCData
+
C VirtualRCSetting
+
C WayPoint
+
C WayPointData
+
C WayPointDataACK
+
C WayPointInitACK
+
C WayPointInitData
+
C WayPointVelocityACK
+
C EulerAngle
+
C EulerianAngle
+
C Measure
+
C Measurement
+
C SpaceVector
+
C Vector3dData
+
C req_id_t
+
C tagAES256Context
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 4a1dda19..1b77f12d 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 ca703835..921f5938 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,6 +95,11 @@
DJI::onboardSDK::Camera Class Reference
+
+
Camera class for controlling camera and gimbal-related functions available through open protocol.
+ More...
+
+
#include <DJI_Camera.h >
@@ -149,7 +154,9 @@
void setApi (CoreAPI *value)
-
+
+
Camera class for controlling camera and gimbal-related functions available through open protocol.
+
@@ -190,7 +197,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 0a0758fb..8c8fcbce 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,7 +95,9 @@
This is the complete list of members for DJI::onboardSDK::CoreAPI , including all inherited members.
ack (req_id_t req_id, unsigned char *ackdata, int len) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
- activate (ActivateData *data, CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
+ ack_data DJI::onboardSDK::CoreAPI
+ activate (ActivateData *data, CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
+ activate (ActivateData *data, int timeout)DJI::onboardSDK::CoreAPI
activateCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI static
byteHandler (const uint8_t in_data)DJI::onboardSDK::CoreAPI
byteStreamHandler (uint8_t *buffer, size_t size)DJI::onboardSDK::CoreAPI
@@ -105,20 +107,38 @@
decodeACKStatus (unsigned short ack)DJI::onboardSDK::CoreAPI
decodeMissionStatus (uint8_t ack)DJI::onboardSDK::CoreAPI
getAccountData () const DJI::onboardSDK::CoreAPI
- getBatteryCapacity () const DJI::onboardSDK::CoreAPI
- getBroadcastData () const DJI::onboardSDK::CoreAPI
+ getACKFrameStatus () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
+ getActivateMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getArmMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getBatteryCapacity () const DJI::onboardSDK::CoreAPI
+ getBroadcastData () const DJI::onboardSDK::CoreAPI
+ getBroadcastFrameStatus () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
getCtrlInfo () const (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
- getDriver () const DJI::onboardSDK::CoreAPI
- getDroneVersion (CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
+ getDisArmMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getDriver () const DJI::onboardSDK::CoreAPI
+ getDroneVersion (CallBack callback=0, UserData userData=0)DJI::onboardSDK::CoreAPI
+ getDroneVersion (int timeout)DJI::onboardSDK::CoreAPI
getDroneVersionCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI static
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::CoreAPI inline
+ getGoHomeMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
getHotPointData () const DJI::onboardSDK::CoreAPI
- getSDKVersion () const DJI::onboardSDK::CoreAPI
- getSessionStatus () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
+ getLandingMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getObtainControlMobileCMD ()DJI::onboardSDK::CoreAPI inline
+ getReleaseControlMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getSDKVersion () const DJI::onboardSDK::CoreAPI
+ getStartVideoMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getStopVideoMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getTakeOffMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ getTakePhotoMobileCMD () (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
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
@@ -126,38 +146,70 @@
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::CoreAPI static
- setAccountData (const ActivateData &value)DJI::onboardSDK::CoreAPI
+ 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::CoreAPI inline
+ setActivateMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setActivation (bool isActivated)DJI::onboardSDK::CoreAPI
+ setArmMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setArmMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setBroadcastCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setBroadcastCallback (CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )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
+ 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
setControlCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI static
+ setDisArmMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setDisArmMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setDriver (HardDriver *value)DJI::onboardSDK::CoreAPI
setFollowCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setFollowCallback (CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
setFollowData (bool value)DJI::onboardSDK::CoreAPI
- setFrequencyCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI static
- 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::CoreAPI inline
- 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::CoreAPI inline
- 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
+ setFollowMeMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setFrequencyCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI static
+ 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::CoreAPI inline
+ setGoHomeMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setHotPointCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ 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::CoreAPI inline
+ setLandingMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setMisssionCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setMisssionCallback (CallBack handler, UserData userData=0) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
+ setObtainControlMobileCallback (CallBackHandler callback)DJI::onboardSDK::CoreAPI inline
+ setObtainControlMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setReleaseControlMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setReleaseControlMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setStartVideoMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setStartVideoMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setStopVideoMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setStopVideoMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setSyncFreq (uint32_t freqInHz) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI
+ setTakeOffMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setTakeOffMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setTakePhotoMobileCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
+ setTakePhotoMobileCMD (bool userInput) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
setVersion (const Version &value)DJI::onboardSDK::CoreAPI
setWayPointCallback (CallBackHandler callback) (defined in DJI::onboardSDK::CoreAPI )DJI::onboardSDK::CoreAPI inline
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
+ stopCond DJI::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 9e0c68d7..496e6a52 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,6 +90,7 @@
@@ -103,6 +104,12 @@
+
+ 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)
@@ -114,42 +121,61 @@
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 activate (ActivateData *data, CallBack callback=0, UserData userData=0)
+
+void notifyCaller (Header *protocolHeader)
+ Notify caller ACK frame arrived.
+
+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)
+void 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)
+void setAccountData (const ActivateData &value)
Activation Control.
-void sendToMobile (uint8_t *data, uint8_t len, CallBack callback=0, UserData userData=0)
+void 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)
-
-void setSessionStatus (uint32_t usageFlag)
-
-
-uint32_t getSessionStatus ()
-
+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 setSyncFreq (uint32_t freqInHz)
@@ -167,10 +193,10 @@
void setFromMobileCallback (CallBackHandler FromMobileEntrance)
-void setBroadcastCallback (CallBack handler, UserData userData=0)
+void setBroadcastCallback (CallBack handler, UserData userData=0)
-void setFromMobileCallback (CallBack handler, UserData userData=0)
+void setFromMobileCallback (CallBack handler, UserData userData=0)
void setMisssionCallback (CallBackHandler callback)
@@ -188,20 +214,54 @@
void setWayPointEventCallback (CallBackHandler callback)
-void setMisssionCallback (CallBack handler, UserData userData=0)
+void setMisssionCallback (CallBack handler, UserData userData=0)
-void setHotPointCallback (CallBack handler, UserData userData=0)
+void setHotPointCallback (CallBack handler, UserData userData=0)
-void setWayPointCallback (CallBack handler, UserData userData=0)
+void setWayPointCallback (CallBack handler, UserData userData=0)
-void setFollowCallback (CallBack handler, UserData userData=0)
+void setFollowCallback (CallBack handler, UserData userData=0)
-void setWayPointEventCallback (CallBack handler, UserData userData=0)
+void 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)
@@ -236,16 +296,90 @@
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
@@ -261,20 +395,39 @@
-static void activateCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
+static void activateCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
-static void getDroneVersionCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
+static void getDroneVersionCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
-static void setControlCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
+static void setControlCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
-static void sendToMobileCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
+static void sendToMobileCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
-static void setFrequencyCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
+static void setFrequencyCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
+
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform.
@@ -296,7 +449,7 @@
void CoreAPI::activate
(
- ActivateData *
+ ActivateData *
data ,
@@ -308,7 +461,7 @@
- UserData
+ UserData
userData = 0
@@ -327,6 +480,43 @@
Proceed to programming if activation successful.
Note for ios verification
+
+
+
+
+
+
+
+ unsigned short CoreAPI::activate
+ (
+ ActivateData *
+ data ,
+
+
+
+
+ int
+ timeout
+
+
+
+ )
+
+
+
+
+
+
Blocking API Control.
+
+
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
+
@@ -342,7 +532,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
@@ -380,7 +570,7 @@
-
Todo: Implement stream handler
+
Todo: Implement stream handler
@@ -397,8 +587,8 @@
-
Todo: Implement callback poll handler
-
Todo: Implement callback poll here
+
Todo: Implement callback poll handler
+
Todo: Implement callback poll here
@@ -433,7 +623,7 @@
@@ -442,7 +632,7 @@
- ActivateData CoreAPI::getAccountData
+ ActivateData CoreAPI::getAccountData
(
)
const
@@ -517,7 +707,7 @@
- UserData
+ UserData
userData = 0
@@ -530,6 +720,27 @@
Get aircraft version.
Note You can query your flight controller prior to activation.
+
+
+
+
+
+
+
+ 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
+
@@ -564,6 +775,30 @@
Get flight status at any time during a flight mission.
+
+
+
+
+
+
+
+
+
+
+ bool DJI::onboardSDK::CoreAPI::getObtainControlMobileCMD
+ (
+ )
+
+
+
+
+
+inline
+
+
+
+
Setters and getters for Mobile CMD variables
+
@@ -598,6 +833,39 @@
Note Make sure you are using appropriate timestamp broadcast frequency. See setBroadcastFreq
function for more details.
+
+
+
+
+
+
+
+ void CoreAPI::parseFromMobileCallback
+ (
+ CoreAPI *
+ api ,
+
+
+
+
+ Header *
+ protocolHeader ,
+
+
+
+
+ UserData userData
+ __UNUSED = 0
+
+
+
+ )
+
+
+
+
+
MOS Protocol parsing lirbary functions. Default MOS Protocol Parser. Calls other callback functions based on data
+
@@ -742,7 +1010,7 @@
- UserData
+ UserData
userData = 0
@@ -794,6 +1062,23 @@
Note Add auto resendpoll
+
+
+
+
+
+
+
+ void DJI::onboardSDK::CoreAPI::setACKFrameStatus
+ (
+ uint32_t
+ usageFlag )
+
+
+
+
+
Let user know when ACK and Broadcast messages processed
+
@@ -834,7 +1119,7 @@
- UserData
+ UserData
userData = 0
@@ -862,6 +1147,102 @@
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.
+
+
Obtain control
+
Returns ACK from flight controller
+
Todo: Implement high resolution timer to catch ACK timeout
+
@@ -879,6 +1260,31 @@
Initialize serial device
+
+
+
+
+
+
+
+
+
+
+ void DJI::onboardSDK::CoreAPI::setObtainControlMobileCallback
+ (
+ CallBackHandler
+ callback )
+
+
+
+
+
+inline
+
+
+
+
Mobile Callback handler functions
+
@@ -896,6 +1302,33 @@
+
+
+
+
+
+
+
+ uint32_t DJI::onboardSDK::CoreAPI::ack_data
+
+
+
+
+
+
+
+
+
+ bool DJI::onboardSDK::CoreAPI::stopCond
+
+
+
The documentation for this class was generated from the following files:
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 76b4a4cb..b018f5db 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,19 +149,21 @@
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
- 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
+ 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
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
@@ -182,7 +184,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 d603f344..dd30c22d 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,11 +188,17 @@
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)
@@ -244,10 +250,10 @@
-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)
+static void taskCallback (CoreAPI *api, Header *protocolHeader, UserData userData=0)
static EulerianAngle toEulerianAngle (QuaternionData data)
@ deprecated Use toEulerAngle instead. More...
@@ -271,7 +277,7 @@
@@ -344,7 +350,7 @@
- UserData userData
+ UserData userData
__UNUSED = 0
@@ -511,7 +517,7 @@
- UserData
+ UserData
userData = 0
@@ -560,7 +566,7 @@
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 d2a50c0e..6f7cf06e 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,27 +101,30 @@
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
- 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
+ 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
stop (CallBack callback=0, UserData userData=0) (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
+ 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
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 feed470a..e98d2896 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,13 +127,22 @@
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)
-void pause (bool isPause, CallBack callback=0, UserData userData=0)
+
+MissionACK stop (int timer)
+
+void pause (bool isPause, CallBack callback=0, UserData userData=0)
+
+MissionACK pause (bool isPause, int timer)
+
void updateTarget (FollowTarget target)
@@ -214,7 +223,7 @@
- UserData
+ UserData
userData = 0
@@ -291,7 +300,7 @@
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 eb7b3512..7500f1d8 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,19 +95,23 @@
This is the complete list of members for DJI::onboardSDK::HardDriver , including all inherited members.
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 f43b7e11..d3fcf7de 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,6 +121,18 @@
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)
@@ -156,20 +168,21 @@
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 2d805291..32617086 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,10 +98,12 @@
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
- ReadACK typedef (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint
+ pause (bool isPause, int timer) (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint
readCallback (CoreAPI *api, Header *protoclHeader, UserData userdata) (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint static
readData (CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint
- resetYaw (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
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
@@ -111,29 +113,32 @@
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
- StartACK typedef (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint
+ start (int timer) (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint
startCallback (CoreAPI *api, Header *protocolHeader, UserData userdata=0) (defined in DJI::onboardSDK::HotPoint )DJI::onboardSDK::HotPoint static
stop (CallBack callback=0, UserData userData=0) (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
+ 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
updateYawRate (YawRate &Data, CallBack callback=0, UserData userData=0) (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 (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
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 5c2f229f..a3c225fe 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,10 +100,6 @@
@@ -147,29 +137,50 @@
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)
+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 updateYawRate (YawRate &Data, CallBack callback=0, UserData userData=0)
+void 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)
+void updateYawRate (float32_t yawRate, bool isClockwise, CallBack callback=0, UserData userData=0)
-void updateRadius (float32_t meter, CallBack callback=0, UserData userData=0)
+void 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)
+void resetYaw (CallBack callback=0, UserData userData=0)
+
+MissionACK resetYaw (int timer)
+
-void readData (CallBack callback=0, UserData userData=0)
+void readData (CallBack callback=0, UserData userData=0)
+
+MissionACK readData (int timer)
+
void setData (const HotPointData &value)
@@ -200,10 +211,10 @@
-static void startCallback (CoreAPI *api, Header *protocolHeader, UserData userdata=0)
+static void startCallback (CoreAPI *api, Header *protocolHeader, UserData userdata=0)
-static void readCallback (CoreAPI *api, Header *protoclHeader, UserData userdata)
+static void readCallback (CoreAPI *api, Header *protoclHeader, UserData userdata)
@@ -237,7 +248,7 @@
- UserData
+ UserData
userData = 0
@@ -259,7 +270,7 @@
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 30b307be..d5477332 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 ede7131a..1049da76 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(); Somehow, you will never get your drone back in one pice, if this tragedy happend.
+When your drone lose signal, it will keep the recent command sent by your API: myAPIToSetupDataFromGroundStation(); This may result in a catastrophic crash.
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 42913ad0..16580443 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,7 +99,9 @@
getInfo () const (defined in DJI::onboardSDK::WayPoint )DJI::onboardSDK::WayPoint
idleVelocityCallback (CoreAPI *api, Header *protocolHeader, UserData wpapi) (defined in DJI::onboardSDK::WayPoint )DJI::onboardSDK::WayPoint static
init (WayPointInitData *Info=0, CallBack callback=0, UserData userData=0) (defined in DJI::onboardSDK::WayPoint )DJI::onboardSDK::WayPoint
- pause (bool isPause, CallBack callback=0, UserData userData=0)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
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
@@ -107,16 +109,19 @@
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
- stop (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
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 (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::WayPoint static
- WayPoint (CoreAPI *ControlAPI=0) (defined in DJI::onboardSDK::WayPoint )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::WayPoint static
+ 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 62ac6ff3..48402654 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,29 +102,44 @@
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)
-void pause (bool isPause, CallBack callback=0, UserData userData=0)
+
+MissionACK stop (int timer)
+
+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)
-bool uploadIndexData (uint8_t pos, CallBack callback=0, UserData userData=0)
+
+WayPointDataACK uploadIndexData (WayPointData *data, int timer)
+
+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)
@@ -144,13 +159,13 @@
-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)
@@ -173,7 +188,7 @@
- UserData
+ UserData
userData = 0
@@ -200,7 +215,7 @@
- UserData
+ UserData
userData = 0
@@ -210,7 +225,7 @@
@@ -233,7 +248,7 @@
- UserData
+ UserData
userData = 0
@@ -243,7 +258,7 @@
@@ -260,7 +275,7 @@
-
Todo: set information for way point
+
Todo: set information for way point
@@ -283,7 +298,7 @@
- UserData
+ UserData
userData = 0
@@ -293,7 +308,7 @@
@@ -316,7 +331,7 @@
- UserData
+ UserData
userData = 0
@@ -337,7 +352,7 @@
diff --git a/dji_sdk_doc/doxygen/html/classes.html b/dji_sdk_doc/doxygen/html/classes.html
index 1320ff5f..3c4c6e8e 100644
--- a/dji_sdk_doc/doxygen/html/classes.html
+++ b/dji_sdk_doc/doxygen/html/classes.html
@@ -90,51 +90,51 @@
diff --git a/dji_sdk_doc/doxygen/html/deprecated.html b/dji_sdk_doc/doxygen/html/deprecated.html
index d79fae51..1cb1d531 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 2851f2ca..2e2f6bac 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 0e451296..8811acb9 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 e71f967e..4ce87506 100644
--- a/dji_sdk_doc/doxygen/html/dir_d6adb40f961893fe77ad1c93ece9fa6b.html
+++ b/dji_sdk_doc/doxygen/html/dir_d6adb40f961893fe77ad1c93ece9fa6b.html
@@ -97,8 +97,10 @@
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.
@@ -107,26 +109,34 @@
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 b262cb55..20e2967a 100644
--- a/dji_sdk_doc/doxygen/html/dir_df193617b4317ea26407acd6acb5749e.html
+++ b/dji_sdk_doc/doxygen/html/dir_df193617b4317ea26407acd6acb5749e.html
@@ -97,39 +97,52 @@
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]
-
-file DJI_HotPoint.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_Mission.h [code]
+ Mission Framework for DJI onboardSDK library.
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 d1f56fef..07b4a0f9 100644
--- a/dji_sdk_doc/doxygen/html/files.html
+++ b/dji_sdk_doc/doxygen/html/files.html
@@ -92,41 +92,42 @@
▼ include
▼ dji_sdk_lib
DJI_API.h Core API for DJI onboardSDK library
- DJI_App.h
- DJI_Camera.h
- DJI_Codec.h
- DJI_Config.h
+ DJI_App.h Application layer support functionality for DJI onboardSDK library
+ DJI_Camera.h Camera/Gimbal API for DJI onboardSDK library
+ DJI_Codec.h Encoding/Message parsing features for DJI onboardSDK library
+ DJI_Config.h Optional macro definitions for DJI Onboard SDK. Use for debugging
DJI_Flight.h Flight Control API for DJI onboardSDK library
- DJI_Follow.h
- DJI_HardDriver.h
- DJI_HotPoint.h
- DJI_Link.h
+ DJI_Follow.h Follow API for DJI onboardSDK library
+ DJI_HardDriver.h Serial device driver abstraction. Provided as an abstract class. Please inherit and implement for individual platforms
+ DJI_HotPoint.h
+ DJI_Link.h Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library
DJI_Memory.h
- DJI_Mission.h
- DJI_Type.h
- DJI_Version.h
- DJI_VirtualRC.h
- DJI_WayPoint.h
- DJICommonType.h
+ DJI_Mission.h Mission Framework for DJI onboardSDK library
+ DJI_Type.h Type definition for DJI onboardSDK library. Officially Maintained
+ DJI_Version.h Drone/SDK Version definition for DJI onboardSDK library Officially Maintained
+ DJI_VirtualRC.h Virtual Radio Control API for DJI onboardSDK library
+ DJI_WayPoint.h Waypoint flight API for DJI onboardSDK library
+ DJICommonType.h Common Type definition for DJI onboardSDK library. Officially Maintained
▼ src
DJI_API.cpp Core API for DJI onboardSDK library
- DJI_App.cpp
- DJI_Camera.cpp
+ DJI_App.cpp Application layer support functionality for DJI onboardSDK library
+ DJI_Camera.cpp Camera/Gimbal API for DJI onboardSDK library
DJI_Codec.cpp Encoding/Message parsing features for DJI onboardSDK library
DJI_Flight.cpp Flight Control API for DJI onboardSDK library
- DJI_Follow.cpp
- DJI_HotPoint.cpp
- DJI_Link.cpp Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library
- DJI_Memory.cpp
- DJI_Mission.cpp Mission Framework for DJI onboardSDK library
- DJI_VirtualRC.cpp
- DJI_WayPoint.cpp
+ DJI_Follow.cpp Follow API for DJI onboardSDK library
+ DJI_HardDriver.cpp Serial device driver abstraction. See DJI_HardDriver.h for more info
+ DJI_HotPoint.cpp Hotpoint (Point of Interest) flight Control API for DJI onboardSDK library
+ DJI_Link.cpp Implement send/read, app handling and data link layer for Core API of DJI onboardSDK library
+ DJI_Memory.cpp Implement memory management for Core API of DJI onboardSDK library
+ DJI_Mission.cpp Mission Framework for DJI onboardSDK library
+ DJI_VirtualRC.cpp Virtual Radio Control API for DJI onboardSDK library
+ DJI_WayPoint.cpp Waypoint flight API for DJI onboardSDK library
diff --git a/dji_sdk_doc/doxygen/html/functions.html b/dji_sdk_doc/doxygen/html/functions.html
index d8fcb06a..6b346d2e 100644
--- a/dji_sdk_doc/doxygen/html/functions.html
+++ b/dji_sdk_doc/doxygen/html/functions.html
@@ -121,8 +121,11 @@ - a -
a
: DJI::onboardSDK::BroadcastData
+ack_data
+: DJI::onboardSDK::CoreAPI
+
activate()
-: DJI::onboardSDK::CoreAPI
+: DJI::onboardSDK::CoreAPI
activation
: DJI::onboardSDK::BroadcastData
@@ -216,6 +219,9 @@ - g -
getMagnet()
: DJI::onboardSDK::Flight
+getObtainControlMobileCMD()
+: DJI::onboardSDK::CoreAPI
+
getQuaternion()
: DJI::onboardSDK::Flight
@@ -285,10 +291,16 @@ - n -
- p -
+parseFromMobileCallback()
+: DJI::onboardSDK::CoreAPI
+
pause()
: DJI::onboardSDK::Follow
, DJI::onboardSDK::WayPoint
@@ -343,17 +355,24 @@ - 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::VirtualRC
+: DJI::onboardSDK::CoreAPI
+, DJI::onboardSDK::VirtualRC
setData()
: DJI::onboardSDK::Follow
@@ -374,6 +393,9 @@ - s -
diff --git a/dji_sdk_doc/doxygen/html/functions_enum.html b/dji_sdk_doc/doxygen/html/functions_enum.html
index 5d4025b1..e97b23a9 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 f0697e5c..436ad99a 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 e67a0fe8..d7c758e1 100644
--- a/dji_sdk_doc/doxygen/html/functions_func.html
+++ b/dji_sdk_doc/doxygen/html/functions_func.html
@@ -190,6 +190,9 @@ - g -
diff --git a/dji_sdk_doc/doxygen/html/namespaceDJI.html b/dji_sdk_doc/doxygen/html/namespaceDJI.html
index a5cf239a..6a9a9902 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
+typedef void * UserData
+ This is used as the datatype for all data arguments in callbacks.
-typedef uint32_t Flag
- This is used as the datatype for all data arguments in callbacks.
+typedef uint32_t Flag
typedef uint8_t size8_t
@@ -143,7 +143,7 @@
Note for ARMCC-5.0 compiler
-
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.
+
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.
@@ -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 d1f42a44..226b8488 100644
--- a/dji_sdk_doc/doxygen/html/namespacemembers.html
+++ b/dji_sdk_doc/doxygen/html/namespacemembers.html
@@ -98,9 +98,6 @@
EulerianAngle
: DJI
-Flag
-: DJI
-
Measure
: DJI
@@ -110,6 +107,9 @@
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 af44311c..41cbeb70 100644
--- a/dji_sdk_doc/doxygen/html/namespacemembers_type.html
+++ b/dji_sdk_doc/doxygen/html/namespacemembers_type.html
@@ -98,9 +98,6 @@
EulerianAngle
: DJI
-Flag
-: DJI
-
Measure
: DJI
@@ -110,6 +107,9 @@
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 bd716650..4dad3dcc 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 c2f4aeb2..0d4c67db 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 f7f3e011..660e9976 100644
--- a/dji_sdk_doc/doxygen/html/search/all_0.js
+++ b/dji_sdk_doc/doxygen/html/search/all_0.js
@@ -1,16 +1,4 @@
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_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']]]
+ ['_5f_5funused',['__UNUSED',['../DJI__Type_8h.html#a6c30d490cd2302ff05d355f3ec844c1f',1,'DJI_Type.h']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_1.js b/dji_sdk_doc/doxygen/html/search/all_1.js
index c6baee2a..1dcb3474 100644
--- a/dji_sdk_doc/doxygen/html/search/all_1.js
+++ b/dji_sdk_doc/doxygen/html/search/all_1.js
@@ -1,8 +1,17 @@
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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_10.js b/dji_sdk_doc/doxygen/html/search/all_10.js
index 0a9246e3..ce7df6ba 100644
--- a/dji_sdk_doc/doxygen/html/search/all_10.js
+++ b/dji_sdk_doc/doxygen/html/search/all_10.js
@@ -1,11 +1,32 @@
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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_11.js b/dji_sdk_doc/doxygen/html/search/all_11.js
index cc1211ca..0a9246e3 100644
--- a/dji_sdk_doc/doxygen/html/search/all_11.js
+++ b/dji_sdk_doc/doxygen/html/search/all_11.js
@@ -1,6 +1,11 @@
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']]]
+ ['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_12.js b/dji_sdk_doc/doxygen/html/search/all_12.js
index 5feb3043..d232de67 100644
--- a/dji_sdk_doc/doxygen/html/search/all_12.js
+++ b/dji_sdk_doc/doxygen/html/search/all_12.js
@@ -1,14 +1,7 @@
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',['../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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_13.js b/dji_sdk_doc/doxygen/html/search/all_13.js
index 425788bc..820e68d6 100644
--- a/dji_sdk_doc/doxygen/html/search/all_13.js
+++ b/dji_sdk_doc/doxygen/html/search/all_13.js
@@ -1,10 +1,14 @@
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',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html',1,'DJI::onboardSDK']]],
- ['waypointvelocityack',['WayPointVelocityACK',['../structDJI_1_1onboardSDK_1_1WayPointVelocityACK.html',1,'DJI::onboardSDK']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_14.js b/dji_sdk_doc/doxygen/html/search/all_14.js
index 0ba44595..42fd4f18 100644
--- a/dji_sdk_doc/doxygen/html/search/all_14.js
+++ b/dji_sdk_doc/doxygen/html/search/all_14.js
@@ -1,5 +1,11 @@
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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_15.html b/dji_sdk_doc/doxygen/html/search/all_15.html
new file mode 100644
index 00000000..1331c0d7
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/all_15.html
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
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
new file mode 100644
index 00000000..0ba44595
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/all_15.js
@@ -0,0 +1,5 @@
+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 7dbb0bfa..c6baee2a 100644
--- a/dji_sdk_doc/doxygen/html/search/all_2.js
+++ b/dji_sdk_doc/doxygen/html/search/all_2.js
@@ -1,14 +1,8 @@
var searchData=
[
- ['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']]]
+ ['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_3.js b/dji_sdk_doc/doxygen/html/search/all_3.js
index 34358254..242c4cdb 100644
--- a/dji_sdk_doc/doxygen/html/search/all_3.js
+++ b/dji_sdk_doc/doxygen/html/search/all_3.js
@@ -1,35 +1,16 @@
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_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,'']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_4.js b/dji_sdk_doc/doxygen/html/search/all_4.js
index 4f3265b5..28b554f6 100644
--- a/dji_sdk_doc/doxygen/html/search/all_4.js
+++ b/dji_sdk_doc/doxygen/html/search/all_4.js
@@ -1,7 +1,36 @@
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']]]
+ ['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,'']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_5.js b/dji_sdk_doc/doxygen/html/search/all_5.js
index 6a743cdc..4f3265b5 100644
--- a/dji_sdk_doc/doxygen/html/search/all_5.js
+++ b/dji_sdk_doc/doxygen/html/search/all_5.js
@@ -1,10 +1,7 @@
var searchData=
[
- ['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']]]
+ ['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_6.js b/dji_sdk_doc/doxygen/html/search/all_6.js
index a0bb227e..3a7aeea5 100644
--- a/dji_sdk_doc/doxygen/html/search/all_6.js
+++ b/dji_sdk_doc/doxygen/html/search/all_6.js
@@ -1,29 +1,9 @@
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']]],
- ['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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_7.js b/dji_sdk_doc/doxygen/html/search/all_7.js
index 736a4b42..f124ad39 100644
--- a/dji_sdk_doc/doxygen/html/search/all_7.js
+++ b/dji_sdk_doc/doxygen/html/search/all_7.js
@@ -1,10 +1,32 @@
var searchData=
[
- ['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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_8.js b/dji_sdk_doc/doxygen/html/search/all_8.js
index 8cca925b..5c29fbbe 100644
--- a/dji_sdk_doc/doxygen/html/search/all_8.js
+++ b/dji_sdk_doc/doxygen/html/search/all_8.js
@@ -1,4 +1,14 @@
var searchData=
[
- ['init',['init',['../classDJI_1_1onboardSDK_1_1HardDriver.html#a4bd7d6bcbb708b905e6296f3d1ac9eab',1,'DJI::onboardSDK::HardDriver']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_9.js b/dji_sdk_doc/doxygen/html/search/all_9.js
index da874a3f..8cca925b 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=
[
- ['longitude',['longitude',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#a5829cb39abac8750ab507796e50d1639',1,'DJI::onboardSDK::WayPointInitData']]]
+ ['init',['init',['../classDJI_1_1onboardSDK_1_1HardDriver.html#a4bd7d6bcbb708b905e6296f3d1ac9eab',1,'DJI::onboardSDK::HardDriver']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_a.js b/dji_sdk_doc/doxygen/html/search/all_a.js
index a90147bd..da874a3f 100644
--- a/dji_sdk_doc/doxygen/html/search/all_a.js
+++ b/dji_sdk_doc/doxygen/html/search/all_a.js
@@ -1,18 +1,4 @@
var searchData=
[
- ['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']]]
+ ['longitude',['longitude',['../structDJI_1_1onboardSDK_1_1WayPointInitData.html#a5829cb39abac8750ab507796e50d1639',1,'DJI::onboardSDK::WayPointInitData']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_b.js b/dji_sdk_doc/doxygen/html/search/all_b.js
index f07e543f..862ddfa0 100644
--- a/dji_sdk_doc/doxygen/html/search/all_b.js
+++ b/dji_sdk_doc/doxygen/html/search/all_b.js
@@ -1,5 +1,20 @@
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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_c.js b/dji_sdk_doc/doxygen/html/search/all_c.js
index 2380ee96..593b57f9 100644
--- a/dji_sdk_doc/doxygen/html/search/all_c.js
+++ b/dji_sdk_doc/doxygen/html/search/all_c.js
@@ -1,7 +1,6 @@
var searchData=
[
- ['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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_d.js b/dji_sdk_doc/doxygen/html/search/all_d.js
index e62b455b..403a87b0 100644
--- a/dji_sdk_doc/doxygen/html/search/all_d.js
+++ b/dji_sdk_doc/doxygen/html/search/all_d.js
@@ -1,4 +1,8 @@
var searchData=
[
- ['quaterniondata',['QuaternionData',['../structDJI_1_1onboardSDK_1_1QuaternionData.html',1,'DJI::onboardSDK']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/all_e.js b/dji_sdk_doc/doxygen/html/search/all_e.js
index ea5c4e08..e62b455b 100644
--- a/dji_sdk_doc/doxygen/html/search/all_e.js
+++ b/dji_sdk_doc/doxygen/html/search/all_e.js
@@ -1,18 +1,4 @@
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']]],
- ['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']]]
+ ['quaterniondata',['QuaternionData',['../structDJI_1_1onboardSDK_1_1QuaternionData.html',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 6cfa91d2..6e281d3c 100644
--- a/dji_sdk_doc/doxygen/html/search/all_f.js
+++ b/dji_sdk_doc/doxygen/html/search/all_f.js
@@ -1,29 +1,17 @@
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']]],
- ['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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/classes_0.js b/dji_sdk_doc/doxygen/html/search/classes_0.js
index 104fffda..79e6b8f3 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',['../structActivateData.html',1,'']]]
+ ['activatedata',['ActivateData',['../structDJI_1_1onboardSDK_1_1ActivateData.html',1,'DJI::onboardSDK']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/classes_6.js b/dji_sdk_doc/doxygen/html/search/classes_6.js
index e3bc6b1c..0517ddf2 100644
--- a/dji_sdk_doc/doxygen/html/search/classes_6.js
+++ b/dji_sdk_doc/doxygen/html/search/classes_6.js
@@ -4,5 +4,7 @@ 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']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/classes_7.js b/dji_sdk_doc/doxygen/html/search/classes_7.js
index f94013a4..3f4667b8 100644
--- a/dji_sdk_doc/doxygen/html/search/classes_7.js
+++ b/dji_sdk_doc/doxygen/html/search/classes_7.js
@@ -5,5 +5,6 @@ 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 ffb4e0b1..de349f56 100644
--- a/dji_sdk_doc/doxygen/html/search/classes_a.js
+++ b/dji_sdk_doc/doxygen/html/search/classes_a.js
@@ -2,7 +2,6 @@ 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 8bfd7aa8..95b02ede 100644
--- a/dji_sdk_doc/doxygen/html/search/classes_b.js
+++ b/dji_sdk_doc/doxygen/html/search/classes_b.js
@@ -1,6 +1,5 @@
var searchData=
[
['sdkfilter',['SDKFilter',['../structDJI_1_1onboardSDK_1_1SDKFilter.html',1,'DJI::onboardSDK']]],
- ['spacevector',['SpaceVector',['../structDJI_1_1SpaceVector.html',1,'DJI']]],
- ['startack',['StartACK',['../structDJI_1_1onboardSDK_1_1HotPoint_1_1StartACK.html',1,'DJI::onboardSDK::HotPoint']]]
+ ['spacevector',['SpaceVector',['../structDJI_1_1SpaceVector.html',1,'DJI']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/classes_d.js b/dji_sdk_doc/doxygen/html/search/classes_d.js
index c5142806..e9b64725 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',['../structVersionData.html',1,'']]],
+ ['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']]]
diff --git a/dji_sdk_doc/doxygen/html/search/defines_0.js b/dji_sdk_doc/doxygen/html/search/defines_0.js
index fe29a21c..660e9976 100644
--- a/dji_sdk_doc/doxygen/html/search/defines_0.js
+++ b/dji_sdk_doc/doxygen/html/search/defines_0.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']]]
+ ['_5f_5funused',['__UNUSED',['../DJI__Type_8h.html#a6c30d490cd2302ff05d355f3ec844c1f',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 9b8dbad1..fe29a21c 100644
--- a/dji_sdk_doc/doxygen/html/search/defines_1.js
+++ b/dji_sdk_doc/doxygen/html/search/defines_1.js
@@ -1,4 +1,5 @@
var searchData=
[
- ['make_5fversion',['MAKE_VERSION',['../DJI__Version_8h.html#a45b1a7ff62105593af4bf5f37b9010f6',1,'DJI_Version.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_2.js b/dji_sdk_doc/doxygen/html/search/defines_2.js
index a6a3f145..9b8dbad1 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=
[
- ['name',['NAME',['../DJI__Type_8h.html#a14111ac8f43949172b152e50dc720aba',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_3.js b/dji_sdk_doc/doxygen/html/search/defines_3.js
index 8ed92867..a6a3f145 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=
[
- ['use_5fencrypt',['USE_ENCRYPT',['../DJI__Config_8h.html#ab711b1ed161a4ec825c22523cda3dc6d',1,'DJI_Config.h']]]
+ ['name',['NAME',['../DJI__Type_8h.html#a14111ac8f43949172b152e50dc720aba',1,'DJI_Type.h']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/defines_4.html b/dji_sdk_doc/doxygen/html/search/defines_4.html
new file mode 100644
index 00000000..c6864f75
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/defines_4.html
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
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
new file mode 100644
index 00000000..8ed92867
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/defines_4.js
@@ -0,0 +1,4 @@
+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 b7262b4e..4cc26aaa 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_5fcommon_5fcode',['ACK_COMMON_CODE',['../DJI__API_8h.html#aec259c8a8cf384789e0726ecf0773cbd',1,'DJI::onboardSDK']]]
+ ['ack_5ferror_5fcode',['ACK_ERROR_CODE',['../DJI__API_8h.html#ae9b83ce82c2006a3c98b5564354985c9',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 ebd782ed..4f7ec9d7 100644
--- a/dji_sdk_doc/doxygen/html/search/files_0.js
+++ b/dji_sdk_doc/doxygen/html/search/files_0.js
@@ -13,13 +13,14 @@ 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 db3eba94..2dd78883 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',['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)']]],
['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 ccffffba..a870979f 100644
--- a/dji_sdk_doc/doxygen/html/search/functions_5.js
+++ b/dji_sdk_doc/doxygen/html/search/functions_5.js
@@ -6,11 +6,12 @@ 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',['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']]],
diff --git a/dji_sdk_doc/doxygen/html/search/functions_7.js b/dji_sdk_doc/doxygen/html/search/functions_7.js
index 6c25840b..6eaee52e 100644
--- a/dji_sdk_doc/doxygen/html/search/functions_7.js
+++ b/dji_sdk_doc/doxygen/html/search/functions_7.js
@@ -1,4 +1,5 @@
var searchData=
[
- ['neutralvrcsticks',['neutralVRCSticks',['../classDJI_1_1onboardSDK_1_1VirtualRC.html#a5a7974a1d812e1ed38b8bb9a092bebfc',1,'DJI::onboardSDK::VirtualRC']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/functions_8.js b/dji_sdk_doc/doxygen/html/search/functions_8.js
index ef174973..1d3012da 100644
--- a/dji_sdk_doc/doxygen/html/search/functions_8.js
+++ b/dji_sdk_doc/doxygen/html/search/functions_8.js
@@ -1,5 +1,6 @@
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 d5326e06..64c71484 100644
--- a/dji_sdk_doc/doxygen/html/search/functions_a.js
+++ b/dji_sdk_doc/doxygen/html/search/functions_a.js
@@ -5,16 +5,19 @@ 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',['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_1VirtualRC.html#a561e25be8d98214360affe7907b52f63',1,'DJI::onboardSDK::VirtualRC']]],
+ ['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']]],
['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 44b1fbcb..40fc1bce 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: "abcdhlmrtvw",
- 6: "abcefgmprsv",
+ 5: "abcdhlmrstvw",
+ 6: "abceghmprsuvw",
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 5ea9fcd0..4d548e2d 100644
--- a/dji_sdk_doc/doxygen/html/search/typedefs_0.js
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_0.js
@@ -1,5 +1,4 @@
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 7f6b0e64..45ae38d1 100644
--- a/dji_sdk_doc/doxygen/html/search/typedefs_2.js
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_2.js
@@ -1,4 +1,6 @@
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 2ff8b7cf..30cb2e66 100644
--- a/dji_sdk_doc/doxygen/html/search/typedefs_4.js
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_4.js
@@ -1,4 +1,7 @@
var searchData=
[
- ['flag',['Flag',['../namespaceDJI.html#ac46082a5ea8919b47fb64283edc5bc18',1,'DJI']]]
+ ['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']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_5.js b/dji_sdk_doc/doxygen/html/search/typedefs_5.js
index 357fac3e..0389cdcc 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=
[
- ['gpsdata',['GPSData',['../DJI__Type_8h.html#ad6db26bb74dcd881f93c0031bae5e914',1,'DJI::onboardSDK']]],
- ['gpspositiondata',['GPSPositionData',['../DJI__Type_8h.html#a4cf179a160f63b28aa3d622aa3f73fb2',1,'DJI::onboardSDK']]]
+ ['header',['Header',['../DJI__Type_8h.html#a14ecda64c265b3dd655ce82b06ce8456',1,'DJI::onboardSDK']]],
+ ['hotpointdata',['HotPointData',['../DJI__Type_8h.html#a1448a5d001a91235c5e08145d7f6a6a4',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 622ddd34..d082fd3a 100644
--- a/dji_sdk_doc/doxygen/html/search/typedefs_6.js
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_6.js
@@ -4,5 +4,6 @@ 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 772f4573..123fe8a7 100644
--- a/dji_sdk_doc/doxygen/html/search/typedefs_a.js
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_a.js
@@ -1,6 +1,4 @@
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']]]
+ ['userdata',['UserData',['../namespaceDJI.html#a0988c6a482e73ea79bc55aac26729302',1,'DJI']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/typedefs_b.html b/dji_sdk_doc/doxygen/html/search/typedefs_b.html
new file mode 100644
index 00000000..dac1e0f2
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_b.html
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
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
new file mode 100644
index 00000000..772f4573
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_b.js
@@ -0,0 +1,6 @@
+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
new file mode 100644
index 00000000..966e7e27
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_c.html
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
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
new file mode 100644
index 00000000..1e607a8d
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/typedefs_c.js
@@ -0,0 +1,4 @@
+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 dcca7664..36a6c12a 100644
--- a/dji_sdk_doc/doxygen/html/search/variables_0.js
+++ b/dji_sdk_doc/doxygen/html/search/variables_0.js
@@ -1,6 +1,7 @@
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_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()']]]
+ ['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()']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/variables_8.js b/dji_sdk_doc/doxygen/html/search/variables_8.js
index 64e04ccb..e64e809c 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=
[
- ['time',['time',['../structDJI_1_1onboardSDK_1_1TimeStampData.html#aea9d03bc043adf819a0529665db64fa8',1,'DJI::onboardSDK::TimeStampData']]]
+ ['stopcond',['stopCond',['../classDJI_1_1onboardSDK_1_1CoreAPI.html#a0b5f3dbc0a3113b89ffec5f9bc47609b',1,'DJI::onboardSDK::CoreAPI']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/variables_9.js b/dji_sdk_doc/doxygen/html/search/variables_9.js
index 3a6e03fe..64e04ccb 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=
[
- ['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()']]]
+ ['time',['time',['../structDJI_1_1onboardSDK_1_1TimeStampData.html#aea9d03bc043adf819a0529665db64fa8',1,'DJI::onboardSDK::TimeStampData']]]
];
diff --git a/dji_sdk_doc/doxygen/html/search/variables_a.js b/dji_sdk_doc/doxygen/html/search/variables_a.js
index 3ddcbded..3a6e03fe 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=
[
- ['w',['w',['../structDJI_1_1onboardSDK_1_1BroadcastData.html#a04c82cbd21eb9903984de09a4b770b88',1,'DJI::onboardSDK::BroadcastData']]]
+ ['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_b.html b/dji_sdk_doc/doxygen/html/search/variables_b.html
new file mode 100644
index 00000000..c98ef41d
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/variables_b.html
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
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
new file mode 100644
index 00000000..3ddcbded
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/search/variables_b.js
@@ -0,0 +1,4 @@
+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 fd54894d..e6710989 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 7ba88191..010329e1 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 c73572fe..4bacfffa 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 b3555014..deeaad8f 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 f22ab0c3..df80a26b 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 fb7e7a21..0922f6da 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 140a6746..96b82731 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 841293db..d097b46d 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 b0119edb..f50e5752 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 98128973..b4402641 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 @@
-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 5e5da22c..bf8bfc00 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 106e8e32..f70bd4cb 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 471fff5b..d9e59f0a 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 012f2b8f..941505a0 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 350c0fd9..1684cf28 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 f5f10282..89b8ed1b 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
new file mode 100644
index 00000000..3b7cab79
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData-members.html
@@ -0,0 +1,110 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: Member List
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
This is the complete list of members for DJI::onboardSDK::ActivateData , including all inherited members.
+
+
+
+
+
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
new file mode 100644
index 00000000..33fa54ca
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1ActivateData.html
@@ -0,0 +1,127 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: DJI::onboardSDK::ActivateData Struct Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+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 cd07db08..a8fbe70c 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 23d9061a..efddb6aa 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 @@
-Todo:
+
@@ -180,7 +180,7 @@
@@ -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 6c1e71da..0fcdedc2 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 f6b41b6e..6f755ead 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 536f8df9..67b55eda 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 829c3314..0357def3 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,6 +94,11 @@
DJI::onboardSDK::CallBackHandler Struct Reference
+
+
The CallBackHandler struct allows users to encapsulate callbacks and data in one struct.
+ More...
+
+
#include <DJI_Type.h >
@@ -101,16 +106,18 @@
CallBack callback
-UserData userData
+UserData userData
-
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 0cb70c49..1b926baf 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 9684f766..637240db 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:
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 057d2d07..9711098e 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 8a99f035..fd393a26 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 73512f83..1e7e5b1b 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 46f713be..e6efcdf1 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 @@
-
Todo: mode remote to enums
+
Todo: mode remote to enums
@@ -132,7 +132,7 @@
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 ed252a30..ef82ba09 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 707faf7e..7f84cb2f 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 d7536fe4..71632c2d 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 2c700a5b..6ce48074 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 add03449..ade10638 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 4ed0fb32..eaa94503 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 9890e270..f92d00b3 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 f36af176..b3b444e1 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 @@
-Todo: rename to a final version
+
Todo: rename to a final version Detailed GPSData from the A3. This is not available on the M100.
@@ -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 217b17c7..3636cabb 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 d93e0b56..840c7ab1 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 47bb9f85..b460d704 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 ae2346a4..9ec1a0fe 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 @@
-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 8b30cebe..d679c143 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 f80b58dc..7379a938 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,6 +94,8 @@
DJI::onboardSDK::GimbalAngleData Struct Reference
+
+
#include <DJI_Type.h >
@@ -113,13 +115,15 @@
uint8_t duration
-
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 2d01f735..d007cf19 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 73345e44..817f6d26 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 b27f70c7..830d09f7 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 d1f1e7d4..dcf6cdc8 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 05865f70..d0c0bdaa 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 0c1d967e..78653d52 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,6 +94,11 @@
DJI::onboardSDK::Header Struct Reference
+
+
The Header struct is meant to handle the open protocol header.
+ More...
+
+
#include <DJI_Type.h >
@@ -129,7 +134,9 @@
unsigned int crc : 16
-
+
+
The Header struct is meant to handle the open protocol header.
+
@@ -162,7 +169,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 77f56e7e..86b98a6c 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 575c52d8..7770d10d 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 b3d00217..7567777b 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 dc7eb59b..b23a7af3 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,6 +94,8 @@
DJI::onboardSDK::HotPointData Struct Reference
+
+
#include <DJI_Type.h >
@@ -128,13 +130,15 @@
uint8_t reserved [11]
-
The documentation for this struct was generated from the following file:
-dji_sdk_lib/include/dji_sdk_lib/DJI_HotPoint.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
new file mode 100644
index 00000000..1159ff85
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK-members.html
@@ -0,0 +1,107 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: Member List
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
This is the complete list of members for DJI::onboardSDK::HotPointReadACK , including all inherited members.
+
+
+
+
+
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
new file mode 100644
index 00000000..64e2f778
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointReadACK.html
@@ -0,0 +1,118 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: DJI::onboardSDK::HotPointReadACK Struct Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
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
new file mode 100644
index 00000000..93eeb07b
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK-members.html
@@ -0,0 +1,107 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: Member List
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
This is the complete list of members for DJI::onboardSDK::HotPointStartACK , including all inherited members.
+
+
+
+
+
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
new file mode 100644
index 00000000..8f098190
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1HotPointStartACK.html
@@ -0,0 +1,118 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: DJI::onboardSDK::HotPointStartACK Struct Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+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 f507baaf..85cf8bca 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 dec37f9e..ed945062 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 411cd4be..8f9c399f 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 4ce2946e..692aac2b 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 23f53aba..59e11b6e 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 735a271f..b9bc0a9e 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 cdc1b7a4..de17ca8f 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 fe9c6ba7..efdbd830 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 172176e1..7246c505 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 37422778..a799759e 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 5be970a8..01afee73 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 352c63db..c73cc562 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 @@
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 1a996150..19712435 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 7d5c25fb..ada57b02 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 a94f7870..3e3cf7e7 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 f3928a8d..469d88a8 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 a8ae4d7d..851de404 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 d3847359..316abf25 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 @@
-Todo: rename to a final version
+
Todo: rename to a final version RTKData from the A3. This is not available on the M100.
@@ -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 2ec80b40..6cc7e35a 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 f06c11f5..3bf27aad 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 5f91526a..88303725 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 1d04a3a2..81e31ddd 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 3be56880..2992cde1 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 2f121546..315e9849 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 f505dc80..0248c66b 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 f52bba33..d8b4b34b 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 @@
@@ -126,7 +126,7 @@
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 2802c0ce..e8d7743b 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 277be433..39d21c1f 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 e109fe46..a0d8e6e8 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 8a2a5c7d..6a343042 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
new file mode 100644
index 00000000..0fd8e32b
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData-members.html
@@ -0,0 +1,110 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: Member List
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
This is the complete list of members for DJI::onboardSDK::VersionData , including all inherited members.
+
+
+
+
+
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
new file mode 100644
index 00000000..b09716b5
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/structDJI_1_1onboardSDK_1_1VersionData.html
@@ -0,0 +1,127 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: DJI::onboardSDK::VersionData Struct Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+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 f9a08396..bf502460 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 b4b16ad1..0872ebab 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 @@
Note this is default mapping data structure for virtual remote controller.
-
Todo: channel mapping
+
Todo: channel mapping
@@ -166,7 +166,7 @@
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 f50c1f49..2f145ad6 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 568c5b06..e3d61e4e 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 fceaf1e3..84b51495 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 7a8f4453..0afcaa2f 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 @@
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 bd0ee5a6..803870f9 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 bf5fa795..2c4afcad 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 e963ea99..bf52a89b 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 84060130..b246177a 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 178ca09b..97b60df8 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 fdb721ba..e0850617 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,6 +94,8 @@
DJI::onboardSDK::WayPointInitData Struct Reference
+
+
#include <DJI_Type.h >
@@ -137,7 +139,9 @@
uint8_t reserved [16]
-
+
+
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 b629d696..60314645 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 262fdd38..6347d85d 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 0d2606fa..7e97fa91 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 2509946f..7697c27b 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 9f6cb26e..36f164db 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 bc7b86af..9ad02c87 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 c5b4598a..2e122614 100644
--- a/dji_sdk_doc/doxygen/html/todo.html
+++ b/dji_sdk_doc/doxygen/html/todo.html
@@ -81,63 +81,65 @@
- Member ActivateData
-move to type.h
- Member API_ERROR_DATA
-not available yet, only affect WayPoint
- Member API_LOG (driver, title, fmt,...)
+ Member API_ERROR_DATA
+Not supported in this release.
+ 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_COMMON_CODE
+ Member DJI::onboardSDK::ACK_ERROR_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::byteHandler (const uint8_t in_data)
+ 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)
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::CtrlInfoData::deviceStatus
+ 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
mode remote to enums
- Member DJI::onboardSDK::Flight::Mode
+ Member DJI::onboardSDK::Flight::Mode
rename
- Member DJI::onboardSDK::GPSData
-rename to a final version
- Class DJI::onboardSDK::GSPushData
+ 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
unify the naming style
- Member DJI::onboardSDK::RTKData
-rename to a final version
- Member DJI::onboardSDK::TimeStampData::time
+ 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
type modify
- Member DJI::onboardSDK::Version
-better version control structure
- Member DJI::onboardSDK::VirtualRCData::roll
+ 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
new file mode 100644
index 00000000..b9a8e216
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion-members.html
@@ -0,0 +1,111 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: Member List
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
This is the complete list of members for DJI::onboardSDK::MissionACKUnion , including all inherited members.
+
+
+
+
+
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
new file mode 100644
index 00000000..5612fa35
--- /dev/null
+++ b/dji_sdk_doc/doxygen/html/unionDJI_1_1onboardSDK_1_1MissionACKUnion.html
@@ -0,0 +1,130 @@
+
+
+
+
+
+
+Onboard-SDK-ROS: DJI::onboardSDK::MissionACKUnion Union Reference
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ Onboard-SDK-ROS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
The documentation for this union was generated from the following file:
+
+
+
+
+
From f9510ccb5ef8f91e01da1636e1acabe059249b19 Mon Sep 17 00:00:00 2001
From: Arjun
Date: Fri, 14 Oct 2016 20:32:55 -0700
Subject: [PATCH 3/4] Sync with onboardSDK Core library commit which has
improvements. Refer to OnboardSDK documentation for details at
https://developer.dji.com/onboard-sdk/documentation/quick-start/index.html.
No new features added
---
.catkin_workspace | 1 +
CMakeLists.txt | 1 +
dji_sdk_demo/src/client.cpp | 8 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_API.h | 56 ++++-
dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h | 1 +
dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h | 2 +-
.../include/dji_sdk_lib/DJI_HardDriver.h | 10 +
dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h | 3 +
dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h | 47 ++++
dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h | 11 +
dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h | 1 -
dji_sdk_lib/src/DJI_API.cpp | 209 +++++++++++++++++-
dji_sdk_lib/src/DJI_App.cpp | 4 +-
dji_sdk_lib/src/DJI_Link.cpp | 80 ++++++-
dji_sdk_lib/src/DJI_Logging.cpp | 79 +++++++
15 files changed, 488 insertions(+), 25 deletions(-)
create mode 100644 .catkin_workspace
create mode 120000 CMakeLists.txt
create mode 100644 dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h
create mode 100644 dji_sdk_lib/src/DJI_Logging.cpp
diff --git a/.catkin_workspace b/.catkin_workspace
new file mode 100644
index 00000000..52fd97e7
--- /dev/null
+++ b/.catkin_workspace
@@ -0,0 +1 @@
+# This file currently only serves to mark the location of a catkin workspace for tool integration
diff --git a/CMakeLists.txt b/CMakeLists.txt
new file mode 120000
index 00000000..581e61db
--- /dev/null
+++ b/CMakeLists.txt
@@ -0,0 +1 @@
+/opt/ros/kinetic/share/catkin/cmake/toplevel.cmake
\ No newline at end of file
diff --git a/dji_sdk_demo/src/client.cpp b/dji_sdk_demo/src/client.cpp
index 4ac8ef39..49e6d820 100644
--- a/dji_sdk_demo/src/client.cpp
+++ b/dji_sdk_demo/src/client.cpp
@@ -67,7 +67,7 @@ static void Display_Main_Menu(void)
printf("| [18] Disarm the Drone | [37] Enter Mobile commands mode |\n");
printf("| [19] Virtual RC Test \n");
printf("+-----------------------------------------------------------------+\n");
- printf("input a/b/c etc..then press enter key\r\n");
+ printf("input 1/2/3 etc..then press enter key\r\n");
printf("use `rostopic echo` to query drone status\r\n");
printf("----------------------------------------\r\n");
}
@@ -137,7 +137,11 @@ int main(int argc, char *argv[])
{
ros::spinOnce();
std::cout << "Enter Input Val: ";
- std::cin >> temp32;
+ while(!(std::cin >> temp32)){
+ std::cin.clear();
+ std::cin.ignore(std::numeric_limits::max(), '\n');
+ std::cout << "Invalid input. Try again: ";
+ }
if(temp32>0 && temp32<38)
{
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 88669fc0..965dba94 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
@@ -217,7 +217,7 @@ class CoreAPI
void sendPoll(void);
void readPoll(void);
//! @todo Implement callback poll handler
- void callbackPoll(void);
+ void callbackPoll(CoreAPI *api);
//! @todo Pipeline refactoring
void byteHandler(const uint8_t in_data);
@@ -229,6 +229,9 @@ class CoreAPI
//! Notify caller ACK frame arrived
void notifyCaller(Header *protocolHeader);
+ void notifyNonBlockingCaller(Header *protocolHeader);
+
+
//@{
/**
* @remark
@@ -401,6 +404,8 @@ class CoreAPI
/**Get broadcasted data values from flight controller.*/
BroadcastData getBroadcastData() const;
+ bool nonBlockingCBThreadEnable;
+
/**
* Get timestamp from flight controller.
*
@@ -433,6 +438,7 @@ class CoreAPI
*/
HardDriver *getDriver() const;
+ SimpleACK getSimpleACK() const;
/**
* Get SDK version
*/
@@ -545,8 +551,16 @@ class CoreAPI
void setVersion(const Version &value);
/**
+<<<<<<< HEAD
* Setters and getters for Mobile CMD variables
*/
+=======
+ * Setters and getters for Mobile CMD variables - these are used
+ * when interacting with a Data Transparent Transmission App
+ */
+
+ /** Core functions - getters */
+>>>>>>> master
bool getObtainControlMobileCMD() {return obtainControlMobileCMD;}
bool getReleaseControlMobileCMD() {return releaseControlMobileCMD;}
bool getActivateMobileCMD() {return activateMobileCMD;}
@@ -558,8 +572,19 @@ class CoreAPI
bool getTakePhotoMobileCMD() {return takePhotoMobileCMD;}
bool getStartVideoMobileCMD() {return startVideoMobileCMD;}
bool getStopVideoMobileCMD() {return stopVideoMobileCMD;}
- bool getFollowMeMobileCMD() {return followMeMobileCMD;}
+ /** Custom missions - getters */
+ bool getDrawCirMobileCMD() {return drawCirMobileCMD;}
+ bool getDrawSqrMobileCMD() {return drawSqrMobileCMD;}
+ bool getAttiCtrlMobileCMD() {return attiCtrlMobileCMD;}
+ bool getGimbalCtrlMobileCMD() {return gimbalCtrlMobileCMD;}
+ bool getWayPointTestMobileCMD() {return wayPointTestMobileCMD;}
+ bool getLocalNavTestMobileCMD() {return localNavTestMobileCMD;}
+ bool getGlobalNavTestMobileCMD() {return globalNavTestMobileCMD;}
+ bool getVRCTestMobileCMD() {return VRCTestMobileCMD;}
+ bool getLocalMissionPlanCMD() {return localMissionPlanCMD;}
+
+ /** Core functions - setters */
void setObtainControlMobileCMD(bool userInput) {obtainControlMobileCMD = userInput;}
void setReleaseControlMobileCMD(bool userInput) {releaseControlMobileCMD= userInput;}
void setActivateMobileCMD(bool userInput) {activateMobileCMD= userInput;}
@@ -571,8 +596,17 @@ class CoreAPI
void setTakePhotoMobileCMD(bool userInput) {takePhotoMobileCMD= userInput;}
void setStartVideoMobileCMD(bool userInput) {startVideoMobileCMD= userInput;}
void setStopVideoMobileCMD(bool userInput) {stopVideoMobileCMD= userInput;}
- void setFollowMeMobileCMD(bool userInput) {followMeMobileCMD= userInput;}
+ /** Custom missions - setters */
+ void setDrawCirMobileCMD(bool userInput) {drawCirMobileCMD = userInput;}
+ void setDrawSqrMobileCMD(bool userInput) {drawSqrMobileCMD = userInput;}
+ void setAttiCtrlMobileCMD(bool userInput) {attiCtrlMobileCMD = userInput;}
+ void setGimbalCtrlMobileCMD(bool userInput) {gimbalCtrlMobileCMD = userInput;}
+ void setWayPointTestMobileCMD(bool userInput) {wayPointTestMobileCMD = userInput;}
+ void setLocalNavTestMobileCMD(bool userInput) {localNavTestMobileCMD = userInput;}
+ void setGlobalNavTestMobileCMD(bool userInput) {globalNavTestMobileCMD = userInput;}
+ void setVRCTestMobileCMD(bool userInput) {VRCTestMobileCMD = userInput;}
+ void setLocalMissionPlanCMD(bool userInput) {localMissionPlanCMD = userInput;}
private:
BroadcastData broadcastData;
@@ -581,9 +615,8 @@ class CoreAPI
unsigned char encodeSendData[BUFFER_SIZE];
unsigned char encodeACK[ACK_SIZE];
-// uint8_t cblistTail;
-// CallBackHandler cbList[CALLBACK_LIST_NUM];
+ //! Mobile Data Transparent Transmission - callbacks
CallBackHandler fromMobileCallback;
CallBackHandler broadcastCallback;
CallBackHandler hotPointCallback;
@@ -605,6 +638,8 @@ class CoreAPI
CallBackHandler startVideoMobileCallback;
CallBackHandler stopVideoMobileCallback;
+ //! Mobile Data Transparent Transmission - flags
+
bool obtainControlMobileCMD;
bool releaseControlMobileCMD;
bool activateMobileCMD;
@@ -616,8 +651,15 @@ class CoreAPI
bool takePhotoMobileCMD;
bool startVideoMobileCMD;
bool stopVideoMobileCMD;
- bool followMeMobileCMD;
-
+ bool drawCirMobileCMD;
+ bool drawSqrMobileCMD;
+ bool attiCtrlMobileCMD;
+ bool gimbalCtrlMobileCMD;
+ bool wayPointTestMobileCMD;
+ bool localNavTestMobileCMD;
+ bool globalNavTestMobileCMD;
+ bool VRCTestMobileCMD;
+ bool localMissionPlanCMD;
VersionData versionData;
ActivateData accountData;
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 73d4d38e..c6fa971d 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h
@@ -25,6 +25,7 @@
//! Uncomment these macros to access various messages from the API.
//#define API_MISSION_DATA
+//#define API_TRACE_DATA
//#define API_DEBUG_DATA
//#define API_BUFFER_DATA
//#define API_RTK_DEBUG
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
index 3796d753..e975339a 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
@@ -67,7 +67,7 @@ class Follow
Follow(CoreAPI *ControlAPI = 0);
void resetData();
void start(FollowData *Data = 0, CallBack callback = 0, UserData userData = 0);
- MissionACK start(FollowData *Data = 0, int timer = 0);
+ MissionACK start(FollowData *Data, int timeout);
void stop(CallBack callback = 0, UserData userData = 0);
MissionACK stop(int timer);
//! @note true for pause, false for resume
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
index ed5e0a8f..cf0bcc59 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
@@ -82,6 +82,7 @@ class HardDriver
virtual time_ms getTimeStamp() = 0;
virtual size_t send(const uint8_t *buf, size_t len) = 0;
virtual size_t readall(uint8_t *buf, size_t maxlen) = 0;
+ virtual bool getDeviceStatus() {return true;}
public:
virtual void lockMemory() = 0;
@@ -96,6 +97,15 @@ class HardDriver
virtual void notify() = 0;
virtual void wait(int timeout) = 0;
+ virtual void lockProtocolHeader() {;}
+ virtual void freeProtocolHeader() {;}
+
+ virtual void lockNonBlockCBAck() {;}
+ virtual void freeNonBlockCBAck() {;}
+
+ virtual void notifyNonBlockCBAckRecv() {;}
+ virtual void nonBlockWait() {;}
+
public:
virtual void displayLog(const char *buf = 0);
};
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
index c6aad6c3..78a189f8 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
@@ -24,4 +24,7 @@
#include "DJI_Type.h"
+
+
#endif // DJI_LINK_H
+
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h
new file mode 100644
index 00000000..842a6878
--- /dev/null
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h
@@ -0,0 +1,47 @@
+/** @file DJI_Logging.h
+ * @version 3.1.9
+ * @date August 15th, 2016
+ *
+ * @brief
+ * Implement logging functions for the SDK.
+ *
+ * @copyright 2016 DJI. All right reserved.
+ *
+ */
+
+#ifndef ONBOARDSDK_DJI_LOGGING_H
+#define ONBOARDSDK_DJI_LOGGING_H
+
+#include "DJI_API.h"
+#include "DJI_Type.h"
+
+namespace DJI {
+namespace onboardSDK {
+
+typedef struct __Command {
+ uint8_t set_id;
+ uint8_t id;
+} __Command;
+
+typedef struct __ActivationGetProtocolVersionCommand {
+ uint8_t set_id;
+ uint8_t id;
+ uint8_t val;
+} __ActivationGetProtocolVersionCommand;
+
+enum __ActivationGetProtocolVersionAckCodes {
+ AUTOPILOT_ACTIVATED = 0x0000,
+ AUTOPILOT_NOT_ACTIVATED = 0xFF01
+};
+
+typedef struct __ActivationGetProtocolVersionAck {
+ __ActivationGetProtocolVersionAckCodes status;
+ uint32_t crc;
+ uint8_t version[32];
+} __ActivationGetProtocolVersionAck;
+
+void printFrame(HardDriver *hardDriver, Header *header, bool toAircraft);
+}
+}
+
+#endif // ONBOARDSDK_DJI_LOGGING_H
diff --git a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
index 6ad0d3f8..40a91a05 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
@@ -62,6 +62,13 @@
else \
(driver)->displayLog("ERROR: log printer inner fault\n"); \
}
+
+#ifdef API_TRACE_DATA
+#define TRACE_LOG "TRACE"
+#else
+#define TRACE_LOG 0
+#endif
+
#ifdef API_DEBUG_DATA
#define DEBUG_LOG "DEBUG"
#else
@@ -310,7 +317,11 @@ typedef struct WayPointData
*/
typedef uint8_t MissionACK;
+<<<<<<< HEAD
typedef uint32_t SimpleACK;
+=======
+typedef uint16_t SimpleACK;
+>>>>>>> master
typedef struct HotPointStartACK
{
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 63fb0c8f..87169fb4 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h
@@ -35,7 +35,6 @@ 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 SDK_VERSION = versionM100_31;
#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 8e1bd49b..2e1ef573 100644
--- a/dji_sdk_lib/src/DJI_API.cpp
+++ b/dji_sdk_lib/src/DJI_API.cpp
@@ -70,6 +70,7 @@ void CoreAPI::init(HardDriver *sDevice, CallBackHandler userRecvCallback,
wayPointData = false;
callbackThread = userCallbackThread;
+ nonBlockingCBThreadEnable = false;
ack_data = 99;
versionData.version = SDKVersion;
@@ -214,6 +215,33 @@ void CoreAPI::activate(ActivateData *data, CallBack callback, UserData userData)
send(2, 0, SET_ACTIVATION, CODE_ACTIVATE, (unsigned char *)&accountData,
sizeof(accountData) - sizeof(char *), 1000, 3,
callback ? callback : CoreAPI::activateCallback, userData);
+
+ ack_data = missionACKUnion.simpleACK;
+ if(ack_data == ACK_ACTIVE_SUCCESS && accountData.encKey)
+ setKey(accountData.encKey);
+}
+
+unsigned short CoreAPI::activate(ActivateData *data, int timeout)
+{
+ data->version = versionData.version;
+ accountData = *data;
+ accountData.reserved = 2;
+
+ for (int i = 0; i < 32; ++i) accountData.iosID[i] = '0'; //! @note for ios verification
+ API_LOG(serialDevice, DEBUG_LOG, "version 0x%X/n", versionData.version);
+ API_LOG(serialDevice, DEBUG_LOG, "%.32s", accountData.iosID);
+ send(2, 0, SET_ACTIVATION, CODE_ACTIVATE, (unsigned char *)&accountData,
+ sizeof(accountData) - sizeof(char *), 1000, 3, 0, 0);
+
+ // Wait for end of ACK frame to arrive
+ serialDevice->lockACK();
+ serialDevice->wait(timeout);
+ serialDevice->freeACK();
+ ack_data = missionACKUnion.simpleACK;
+ if(ack_data == ACK_ACTIVE_SUCCESS && accountData.encKey)
+ setKey(accountData.encKey);
+
+ return ack_data;
}
unsigned short CoreAPI::activate(ActivateData *data, int timeout)
@@ -304,7 +332,6 @@ unsigned short CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, int timeout)
serialDevice->lockACK();
serialDevice->wait(timeout);
serialDevice->freeACK();
-
return missionACKUnion.simpleACK;
}
@@ -362,6 +389,7 @@ void CoreAPI::setBroadcastFreqToZero()
* 11 - Control Information
*/
+<<<<<<< HEAD
freq[0] = BROADCAST_FREQ_1HZ;
freq[1] = BROADCAST_FREQ_10HZ;
freq[2] = BROADCAST_FREQ_50HZ;
@@ -374,6 +402,20 @@ void CoreAPI::setBroadcastFreqToZero()
freq[9] = BROADCAST_FREQ_100HZ;
freq[10] = BROADCAST_FREQ_50HZ;
freq[11] = BROADCAST_FREQ_10HZ;
+=======
+ freq[0] = BROADCAST_FREQ_0HZ;
+ freq[1] = BROADCAST_FREQ_0HZ;
+ freq[2] = BROADCAST_FREQ_0HZ;
+ freq[3] = BROADCAST_FREQ_0HZ;
+ freq[4] = BROADCAST_FREQ_0HZ;
+ freq[5] = BROADCAST_FREQ_0HZ;
+ freq[6] = BROADCAST_FREQ_0HZ;
+ freq[7] = BROADCAST_FREQ_0HZ;
+ freq[8] = BROADCAST_FREQ_0HZ;
+ freq[9] = BROADCAST_FREQ_0HZ;
+ freq[10] = BROADCAST_FREQ_0HZ;
+ freq[11] = BROADCAST_FREQ_0HZ;
+>>>>>>> master
setBroadcastFreq(freq);
}
@@ -456,6 +498,8 @@ unsigned short CoreAPI::setControl(bool enable, int timeout)
HardDriver *CoreAPI::getDriver() const { return serialDevice; }
+SimpleACK CoreAPI::getSimpleACK () const { return missionACKUnion.simpleACK; }
+
void CoreAPI::setDriver(HardDriver *sDevice) { serialDevice = sDevice; }
void CoreAPI::getDroneVersionCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED)
@@ -696,6 +740,169 @@ void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, User
}
}
+//! Mobile Data Transparent Transmission Input Servicing
+void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED)
+{
+ uint16_t mobile_data_id;
+
+ if (protocolHeader->length - EXC_DATA_SIZE <= 4)
+ {
+ mobile_data_id = *((unsigned char*)protocolHeader + sizeof(Header) + 2);
+
+ switch (mobile_data_id)
+ {
+ case 2:
+ if (obtainControlMobileCallback.callback)
+ {
+ obtainControlMobileCallback.callback(api, protocolHeader, obtainControlMobileCallback.userData);
+ }
+ else
+ {
+ obtainControlMobileCMD = true;
+ }
+ break;
+
+ case 3:
+ if (releaseControlMobileCallback.callback)
+ {
+ releaseControlMobileCallback.callback(api, protocolHeader, releaseControlMobileCallback.userData);
+ }
+ else
+ {
+ releaseControlMobileCMD = true;
+ }
+ break;
+
+ case 4:
+ if (activateMobileCallback.callback)
+ {
+ activateMobileCallback.callback(api, protocolHeader, activateMobileCallback.userData);
+ }
+ else
+ {
+ activateMobileCMD = true;
+ }
+ break;
+
+ case 5:
+ if (armMobileCallback.callback)
+ {
+ armMobileCallback.callback(api, protocolHeader, armMobileCallback.userData);
+ }
+ else
+ {
+ armMobileCMD = true;
+ }
+ break;
+
+ case 6:
+ if (disArmMobileCallback.callback)
+ {
+ disArmMobileCallback.callback(api, protocolHeader, disArmMobileCallback.userData);
+ }
+ else
+ {
+ disArmMobileCMD = true;
+ }
+ break;
+
+ case 7:
+ if (takeOffMobileCallback.callback)
+ {
+ takeOffMobileCallback.callback(api, protocolHeader, takeOffMobileCallback.userData);
+ }
+ else
+ {
+ takeOffMobileCMD = true;
+ }
+ break;
+
+ case 8:
+ if (landingMobileCallback.callback)
+ {
+ landingMobileCallback.callback(api, protocolHeader, landingMobileCallback.userData);
+ }
+ else
+ {
+ landingMobileCMD = true;
+ }
+ break;
+
+ case 9:
+ if (goHomeMobileCallback.callback)
+ {
+ goHomeMobileCallback.callback(api, protocolHeader, goHomeMobileCallback.userData);
+ }
+ else
+ {
+ goHomeMobileCMD = true;
+ }
+ break;
+
+ case 10:
+ if (takePhotoMobileCallback.callback)
+ {
+ takePhotoMobileCallback.callback(api, protocolHeader, takePhotoMobileCallback.userData);
+ }
+ else
+ {
+ takePhotoMobileCMD = true;
+ }
+ break;
+
+ case 11:
+ if (startVideoMobileCallback.callback)
+ {
+ startVideoMobileCallback.callback(api, protocolHeader, startVideoMobileCallback.userData);
+ }
+ else
+ {
+ startVideoMobileCMD = true;
+ }
+ break;
+
+ case 13:
+ if (stopVideoMobileCallback.callback)
+ {
+ stopVideoMobileCallback.callback(api, protocolHeader, stopVideoMobileCallback.userData);
+ }
+ else
+ {
+ stopVideoMobileCMD = true;
+ }
+ break;
+ //! The next few are only polling based and do not use callbacks. See usage in Linux Sample.
+ case 61:
+ drawCirMobileCMD = true;
+ break;
+ case 62:
+ drawSqrMobileCMD = true;
+ break;
+ case 63:
+ attiCtrlMobileCMD = true;
+ break;
+ case 64:
+ gimbalCtrlMobileCMD = true;
+ break;
+ case 65:
+ wayPointTestMobileCMD = true;
+ break;
+ case 66:
+ localNavTestMobileCMD = true;
+ break;
+ case 67:
+ globalNavTestMobileCMD = true;
+ break;
+ case 68:
+ VRCTestMobileCMD = true;
+ break;
+ case 69:
+ localMissionPlanCMD = true;
+ break;
+ }
+ }
+}
+
void CoreAPI::setFrequencyCallback(CoreAPI *api __UNUSED, Header *protocolHeader,
UserData userData __UNUSED)
{
diff --git a/dji_sdk_lib/src/DJI_App.cpp b/dji_sdk_lib/src/DJI_App.cpp
index e5c6a279..44a202d3 100644
--- a/dji_sdk_lib/src/DJI_App.cpp
+++ b/dji_sdk_lib/src/DJI_App.cpp
@@ -96,9 +96,9 @@ void DJI::onboardSDK::CoreAPI::broadcast(Header *protocolHeader)
passData(*enableFlag, DATA_FLAG, &broadcastData.gps, pdata, sizeof(GPSData), len);
passData(*enableFlag, DATA_FLAG, &broadcastData.rtk, pdata, sizeof(RTKData), len);
if (((*enableFlag) & 0x0040))
- API_LOG(serialDevice, RTK_LOG, "receive GPS data %lld\n", serialDevice->getTimeStamp());
+ API_LOG(serialDevice, RTK_LOG, "receive GPS data %llu\n", (unsigned long long)serialDevice->getTimeStamp());
if (((*enableFlag) & 0x0080))
- API_LOG(serialDevice, RTK_LOG, "receive RTK data %lld\n", serialDevice->getTimeStamp());
+ API_LOG(serialDevice, RTK_LOG, "receive RTK data %llu\n", (unsigned long long)serialDevice->getTimeStamp());
}
passData(*enableFlag, DATA_FLAG, &broadcastData.mag, pdata, sizeof(MagnetData), len);
passData(*enableFlag, DATA_FLAG, &broadcastData.rc, pdata, sizeof(RadioData), len);
diff --git a/dji_sdk_lib/src/DJI_Link.cpp b/dji_sdk_lib/src/DJI_Link.cpp
index 85c3d81f..a527a73f 100644
--- a/dji_sdk_lib/src/DJI_Link.cpp
+++ b/dji_sdk_lib/src/DJI_Link.cpp
@@ -21,12 +21,23 @@
#include "DJI_Codec.h"
#include "DJI_API.h"
+#include "DJI_Logging.h"
+
using namespace DJI::onboardSDK;
+CallBack callBack = 0;
+void* data = 0;
+Header *protHeader = 0;
+
void CoreAPI::sendData(unsigned char *buf)
{
size_t ans;
Header *pHeader = (Header *)buf;
+
+#ifdef API_TRACE_DATA
+ printFrame(serialDevice, pHeader, true);
+#endif
+
ans = serialDevice->send(buf, pHeader->length);
if (ans == 0)
API_LOG(serialDevice, STATUS_LOG, "Port not send");
@@ -36,9 +47,13 @@ void CoreAPI::sendData(unsigned char *buf)
void CoreAPI::appHandler(Header *protocolHeader)
{
+#ifdef API_TRACE_DATA
+ printFrame(serialDevice, protocolHeader, false);
+#endif
+
Header *p2protocolHeader;
- CallBack callBack = 0;
- UserData data = 0;
+
+
if (protocolHeader->isAck == 1)
{
if (protocolHeader->sessionID > 1 && protocolHeader->sessionID < 32)
@@ -56,21 +71,27 @@ 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);
+ }
+ }
- // Notify caller end of ACK frame arrived
- notifyCaller(protocolHeader);
-
- if (callBack)
+ else
{
- //! @todo new algorithm call in a thread
- callBack(this, protocolHeader, data);
+ // Notify caller end of ACK frame arrived
+ notifyCaller(protocolHeader);
+ }
/**
* Set end of ACK frame
* @todo Implement proper notification mechanism
*/
// setACKFrameStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag);
- }
+
setACKFrameStatus((&CMDSessionTab[protocolHeader->sessionID])->usageFlag);
}
else
@@ -156,6 +177,35 @@ void CoreAPI::notifyCaller(Header *protocolHeader)
serialDevice->freeACK();
}
+void CoreAPI::notifyNonBlockingCaller(Header *protocolHeader)
+{
+
+ serialDevice->lockNonBlockCBAck();
+ //! 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);
+ }
+ //! 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.
+ protHeader = protocolHeader;
+ serialDevice->freeNonBlockCBAck();
+
+ serialDevice->lockProtocolHeader();
+ serialDevice->notifyNonBlockCBAckRecv();
+ serialDevice->freeProtocolHeader();
+
+}
+
void CoreAPI::sendPoll()
{
unsigned char i;
@@ -219,7 +269,15 @@ void CoreAPI::readPoll()
}
//! @todo Implement callback poll here
-void CoreAPI::callbackPoll(){}
+void CoreAPI::callbackPoll(CoreAPI *api)
+{
+ serialDevice->lockNonBlockCBAck();
+ serialDevice->nonBlockWait();
+//! The protHeader is being passed to the Callback function for legacy purposes and is not thread safe.
+//! Ack is already avaialble to you in the callback via the mission ACK Union.
+ callBack(api,protHeader,data);
+ serialDevice->freeNonBlockCBAck();
+}
void CoreAPI::setup()
{
@@ -318,7 +376,7 @@ int CoreAPI::sendInterface(Command *parameter)
CMDSession *cmdSession = (CMDSession *)NULL;
if (parameter->length > PRO_PURE_DATA_MAX_SIZE)
{
- API_LOG(serialDevice, ERROR_LOG, "ERROR,length=%d is over-sized\n", parameter->length);
+ API_LOG(serialDevice, ERROR_LOG, "ERROR,length=%lu is over-sized\n", parameter->length);
return -1;
}
diff --git a/dji_sdk_lib/src/DJI_Logging.cpp b/dji_sdk_lib/src/DJI_Logging.cpp
new file mode 100644
index 00000000..e78dbd76
--- /dev/null
+++ b/dji_sdk_lib/src/DJI_Logging.cpp
@@ -0,0 +1,79 @@
+/** @file DJI_Logging.cpp
+ * @version 3.1.9
+ * @date August 15th, 2016
+ *
+ * @brief
+ * Implement logging functions for the SDK.
+ *
+ * @copyright 2016 DJI. All right reserved.
+ *
+ */
+
+#include "DJI_Logging.h"
+#include "DJI_API.h"
+#include "DJI_Link.h"
+#include "DJI_Type.h"
+#include
+
+namespace DJI {
+namespace onboardSDK {
+
+ pthread_mutex_t _logging_lock = PTHREAD_MUTEX_INITIALIZER;
+
+void printFrame(HardDriver *serialDevice, Header *header, bool onboardToAircraft) {
+ pthread_mutex_lock(&_logging_lock);
+
+ uint32_t *crc32 = (uint32_t*) ((uint8_t*)header + header->length - 4);
+
+ if (!header->isAck) {
+ __Command* command = (__Command*)((uint8_t*)header + sizeof(Header));
+
+ if (!onboardToAircraft && command->set_id == SET_BROADCAST) {
+ pthread_mutex_unlock(&_logging_lock);
+ return;
+ }
+
+ API_LOG(serialDevice, DEBUG_LOG, "\n\n");
+ if (onboardToAircraft) {
+ API_LOG(serialDevice, DEBUG_LOG, "|---------------------Sending To Aircraft-------------------------------------------------------------|\n");
+ } else {
+ API_LOG(serialDevice, DEBUG_LOG, "|---------------------Received From Aircraft-----------------------------------------------------------|\n");
+ }
+
+ API_LOG(serialDevice, DEBUG_LOG,
+ "|<---------------------Header-------------------------------->|<---CMD frame data--->|<--Tail-->|\n");
+ API_LOG(serialDevice, DEBUG_LOG,
+ "|SOF |LEN |VER|SESSION|ACK|RES0|PADDING|ENC|RES1|SEQ |CRC16 |CMD SET|CMD ID|CMD VAL| CRC32 |\n");
+ API_LOG(serialDevice, DEBUG_LOG,
+ "|0x%2X|%4d|%3d|%7d|%3d|%4d|%7d|%3d|%4d|%6d|0x%04X| 0x%02X | 0x%02X | |0x%08X|\n", header->sof,
+ header->length, header->version, header->sessionID, header->isAck,
+ header->reversed0, header->padding, header->enc, header->reversed1,
+ header->sequenceNumber, header->crc, command->set_id, command->id, *crc32);
+
+ if (command->set_id == SET_ACTIVATION && command->id == 0x00) {
+// API_LOG(serialDevice, DEBUG_LOG,
+// "command\tset: %d %s\ncommand id:");
+// __ActivationGetProtocolVersionCommand aCommand = (__ActivationGetProtocolVersionCommand) &command;
+ }
+ } else {
+ API_LOG(serialDevice, DEBUG_LOG, "\n\n");
+ if (onboardToAircraft) {
+ API_LOG(serialDevice, DEBUG_LOG, "|---------------------Sending To Aircraft-------------------------------------------------------------|\n");
+ } else {
+ API_LOG(serialDevice, DEBUG_LOG, "|---------------------Received From Aircraft-----------------------------------------------------------|\n");
+ }
+
+ API_LOG(serialDevice, DEBUG_LOG,
+ "|<---------------------Header-------------------------------->|<-ACK frame data->|<--Tail-->|\n");
+ API_LOG(serialDevice, DEBUG_LOG,
+ "|SOF |LEN |VER|SESSION|ACK|RES0|PADDING|ENC|RES1|SEQ |CRC16 | ACK VAL | CRC32 |\n");
+ API_LOG(serialDevice, DEBUG_LOG,
+ "|0x%2X|%4d|%3d|%7d|%3d|%4d|%7d|%3d|%4d|%6d|0x%04X| ACK VAL |0x%08X|\n", header->sof,
+ header->length, header->version, header->sessionID, header->isAck,
+ header->reversed0, header->padding, header->enc, header->reversed1,
+ header->sequenceNumber, header->crc, *crc32);
+ }
+ pthread_mutex_unlock(&_logging_lock);
+}
+}
+}
\ No newline at end of file
From 2f9cf17956ac54f418fd8f904c624505a1eb5f0b Mon Sep 17 00:00:00 2001
From: Arjun
Date: Fri, 14 Oct 2016 20:59:46 -0700
Subject: [PATCH 4/4] Merge conflicts resolved. Please refer to the previous
commit for details of this release
---
dji_sdk_lib/include/dji_sdk_lib/DJI_API.h | 6 +-
dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h | 4 -
dji_sdk_lib/src/DJI_API.cpp | 173 ---------------------
3 files changed, 1 insertion(+), 182 deletions(-)
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 965dba94..e2b13eb9 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
@@ -551,16 +551,12 @@ class CoreAPI
void setVersion(const Version &value);
/**
-<<<<<<< HEAD
- * Setters and getters for Mobile CMD variables
- */
-=======
+
* Setters and getters for Mobile CMD variables - these are used
* when interacting with a Data Transparent Transmission App
*/
/** Core functions - getters */
->>>>>>> master
bool getObtainControlMobileCMD() {return obtainControlMobileCMD;}
bool getReleaseControlMobileCMD() {return releaseControlMobileCMD;}
bool getActivateMobileCMD() {return activateMobileCMD;}
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 40a91a05..3366e076 100644
--- a/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
+++ b/dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
@@ -317,11 +317,7 @@ typedef struct WayPointData
*/
typedef uint8_t MissionACK;
-<<<<<<< HEAD
-typedef uint32_t SimpleACK;
-=======
typedef uint16_t SimpleACK;
->>>>>>> master
typedef struct HotPointStartACK
{
diff --git a/dji_sdk_lib/src/DJI_API.cpp b/dji_sdk_lib/src/DJI_API.cpp
index 2e1ef573..3ffed111 100644
--- a/dji_sdk_lib/src/DJI_API.cpp
+++ b/dji_sdk_lib/src/DJI_API.cpp
@@ -244,28 +244,6 @@ unsigned short CoreAPI::activate(ActivateData *data, int timeout)
return ack_data;
}
-unsigned short CoreAPI::activate(ActivateData *data, int timeout)
-{
- data->version = versionData.version;
- accountData = *data;
- accountData.reserved = 2;
-
- for (int i = 0; i < 32; ++i) accountData.iosID[i] = '0'; //! @note for ios verification
- API_LOG(serialDevice, DEBUG_LOG, "version 0x%X/n", versionData.version);
- API_LOG(serialDevice, DEBUG_LOG, "%.32s", accountData.iosID);
- send(2, 0, SET_ACTIVATION, CODE_ACTIVATE, (unsigned char *)&accountData,
- sizeof(accountData) - sizeof(char *), 1000, 3, 0, 0);
-
- // Wait for end of ACK frame to arrive
- serialDevice->lockACK();
- serialDevice->wait(timeout);
- serialDevice->freeACK();
- ack_data = missionACKUnion.simpleACK;
- if(ack_data == ACK_ACTIVE_SUCCESS && accountData.encKey)
- setKey(accountData.encKey);
-
- return ack_data;
-}
void CoreAPI::sendToMobile(uint8_t *data, uint8_t len, CallBack callback, UserData userData)
{
@@ -389,20 +367,6 @@ void CoreAPI::setBroadcastFreqToZero()
* 11 - Control Information
*/
-<<<<<<< HEAD
- 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;
-=======
freq[0] = BROADCAST_FREQ_0HZ;
freq[1] = BROADCAST_FREQ_0HZ;
freq[2] = BROADCAST_FREQ_0HZ;
@@ -415,7 +379,6 @@ void CoreAPI::setBroadcastFreqToZero()
freq[9] = BROADCAST_FREQ_0HZ;
freq[10] = BROADCAST_FREQ_0HZ;
freq[11] = BROADCAST_FREQ_0HZ;
->>>>>>> master
setBroadcastFreq(freq);
}
@@ -603,142 +566,6 @@ void CoreAPI::sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserDat
protocolHeader->sessionID, protocolHeader->sequenceNumber);
}
}
-void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED)
-{
- uint16_t mobile_data_id;
-
- if (protocolHeader->length - EXC_DATA_SIZE <= 4)
- {
- mobile_data_id = *((unsigned char*)protocolHeader + sizeof(Header) + 2);
-
- switch (mobile_data_id)
- {
- case 2:
- if (obtainControlMobileCallback.callback)
- {
- obtainControlMobileCallback.callback(api, protocolHeader, obtainControlMobileCallback.userData);
- }
- else
- {
- obtainControlMobileCMD = true;
- }
- break;
-
- case 3:
- if (releaseControlMobileCallback.callback)
- {
- releaseControlMobileCallback.callback(api, protocolHeader, releaseControlMobileCallback.userData);
- }
- else
- {
- releaseControlMobileCMD = true;
- }
- break;
-
- case 4:
- if (activateMobileCallback.callback)
- {
- activateMobileCallback.callback(api, protocolHeader, activateMobileCallback.userData);
- }
- else
- {
- activateMobileCMD = true;
- }
- break;
-
- case 5:
- if (armMobileCallback.callback)
- {
- armMobileCallback.callback(api, protocolHeader, armMobileCallback.userData);
- }
- else
- {
- armMobileCMD = true;
- }
- break;
-
- case 6:
- if (disArmMobileCallback.callback)
- {
- disArmMobileCallback.callback(api, protocolHeader, disArmMobileCallback.userData);
- }
- else
- {
- disArmMobileCMD = true;
- }
- break;
-
- case 7:
- if (takeOffMobileCallback.callback)
- {
- takeOffMobileCallback.callback(api, protocolHeader, takeOffMobileCallback.userData);
- }
- else
- {
- takeOffMobileCMD = true;
- }
- break;
-
- case 8:
- if (landingMobileCallback.callback)
- {
- landingMobileCallback.callback(api, protocolHeader, landingMobileCallback.userData);
- }
- else
- {
- landingMobileCMD = true;
- }
- break;
-
- case 9:
- if (goHomeMobileCallback.callback)
- {
- goHomeMobileCallback.callback(api, protocolHeader, goHomeMobileCallback.userData);
- }
- else
- {
- goHomeMobileCMD = true;
- }
- break;
-
- case 10:
- if (takePhotoMobileCallback.callback)
- {
- takePhotoMobileCallback.callback(api, protocolHeader, takePhotoMobileCallback.userData);
- }
- else
- {
- takePhotoMobileCMD = true;
- }
- break;
-
- case 11:
- if (startVideoMobileCallback.callback)
- {
- startVideoMobileCallback.callback(api, protocolHeader, startVideoMobileCallback.userData);
- }
- else
- {
- startVideoMobileCMD = true;
- }
- break;
-
- case 13:
- if (stopVideoMobileCallback.callback)
- {
- stopVideoMobileCallback.callback(api, protocolHeader, stopVideoMobileCallback.userData);
- }
- else
- {
- stopVideoMobileCMD = true;
- }
- break;
- case 68:
- followMeMobileCMD = true;
- }
-
-}
-}
//! Mobile Data Transparent Transmission Input Servicing
void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED)