CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform. More...
#include <DJI_API.h>
CoreAPI implements core Open Protocol communication between M100/M600/A3 and your onboard embedded platform.
CoreAPI::CoreAPI | ( | HardDriver * | Driver = 0 , |
Version | SDKVersion = 0 , |
||
bool | userCallbackThread = false , |
||
CallBack | userRecvCallback = 0 , |
||
UserData | userData = 0 |
||
) |
Definition at line 25 of file DJI_API.cpp.
CoreAPI::CoreAPI | ( | HardDriver * | Driver, |
Version | SDKVersion, | ||
CallBackHandler | userRecvCallback, | ||
bool | userCallbackThread = false |
||
) |
Definition at line 83 of file DJI_API.cpp.
void CoreAPI::ack | ( | req_id_t | req_id, |
unsigned char * | ackdata, | ||
int | len | ||
) |
Definition at line 142 of file DJI_API.cpp.
int CoreAPI::ackInterface | ( | Ack * | parameter | ) | [private] |
Definition at line 327 of file DJI_Link.cpp.
void CoreAPI::activate | ( | ActivateData * | data, |
CallBack | callback = 0 , |
||
UserData | userData = 0 |
||
) |
Activation Control.
Send activation request 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.
Definition at line 211 of file DJI_API.cpp.
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.
Definition at line 229 of file DJI_API.cpp.
void CoreAPI::activateCallback | ( | CoreAPI * | api, |
Header * | protocolHeader, | ||
UserData userData | __UNUSED = 0 |
||
) | [static] |
Definition at line 607 of file DJI_API.cpp.
ACKSession * DJI::onboardSDK::CoreAPI::allocACK | ( | unsigned short | session_id, |
unsigned short | size | ||
) | [private] |
Definition at line 236 of file DJI_Memory.cpp.
void CoreAPI::allocateACK | ( | Header * | protocolHeader | ) |
Notify caller ACK frame arrived.
Definition at line 162 of file DJI_Link.cpp.
MMU_Tab * DJI::onboardSDK::CoreAPI::allocMemory | ( | unsigned short | size | ) | [private] |
Definition at line 52 of file DJI_Memory.cpp.
CMDSession * DJI::onboardSDK::CoreAPI::allocSession | ( | unsigned short | session_id, |
unsigned short | size | ||
) | [private] |
Definition at line 187 of file DJI_Memory.cpp.
void CoreAPI::appHandler | ( | Header * | protocolHeader | ) | [private] |
Non-blocking callback thread
Set end of ACK frame
Definition at line 48 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::broadcast | ( | Header * | protocolHeader | ) | [private] |
Set broadcast frame status
Definition at line 67 of file DJI_App.cpp.
void DJI::onboardSDK::CoreAPI::byteHandler | ( | const uint8_t | in_data | ) |
[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
[123456HH------------------D1234567===HHHH]
Use the buffer high part to re-loop, try to find a new command
if new cmd also fail, and buf like below
[56HHD1234567----------------------===HHHH]
throw one byte, buf looks like
[6HHD123-----------------------4567===HHHH]
the command tail part move to buffer right
Definition at line 761 of file DJI_Codec.cpp.
void CoreAPI::byteStreamHandler | ( | uint8_t * | buffer, |
size_t | size | ||
) |
Definition at line 806 of file DJI_Codec.cpp.
void DJI::onboardSDK::CoreAPI::callApp | ( | SDKFilter * | p_filter | ) | [private] |
Definition at line 598 of file DJI_Codec.cpp.
void CoreAPI::callbackPoll | ( | CoreAPI * | api | ) |
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.
Definition at line 272 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::checkStream | ( | SDKFilter * | p_filter | ) | [private] |
Definition at line 735 of file DJI_Codec.cpp.
bool CoreAPI::decodeACKStatus | ( | unsigned short | ack | ) |
ACK decoder.
Definition at line 607 of file DJI_Codec.cpp.
bool DJI::onboardSDK::CoreAPI::decodeMissionStatus | ( | uint8_t | ack | ) |
unsigned short DJI::onboardSDK::CoreAPI::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 | ||
) | [private] |
Definition at line 849 of file DJI_Codec.cpp.
void DJI::onboardSDK::CoreAPI::freeACK | ( | ACKSession * | session | ) | [private] |
Definition at line 259 of file DJI_Memory.cpp.
void DJI::onboardSDK::CoreAPI::freeSession | ( | CMDSession * | session | ) | [private] |
Definition at line 226 of file DJI_Memory.cpp.
ActivateData CoreAPI::getAccountData | ( | ) | const |
uint32_t DJI::onboardSDK::CoreAPI::getACKFrameStatus | ( | ) |
Definition at line 307 of file DJI_Link.cpp.
bool DJI::onboardSDK::CoreAPI::getActivateMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getArmMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getAttiCtrlMobileCMD | ( | ) | [inline] |
Get battery capacity.
Definition at line 47 of file DJI_App.cpp.
Get broadcasted data values from flight controller.
Definition at line 45 of file DJI_App.cpp.
Definition at line 59 of file DJI_App.cpp.
Definition at line 52 of file DJI_App.cpp.
bool DJI::onboardSDK::CoreAPI::getDisArmMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getDrawCirMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getDrawSqrMobileCMD | ( | ) | [inline] |
HardDriver * CoreAPI::getDriver | ( | ) | const |
Get serial device handler.
Definition at line 567 of file DJI_API.cpp.
void CoreAPI::getDroneVersion | ( | CallBack | callback = 0 , |
UserData | userData = 0 |
||
) |
Get aircraft version.
Definition at line 157 of file DJI_API.cpp.
VersionData CoreAPI::getDroneVersion | ( | int | timeout | ) |
Get drone version from flight controller block until ACK arrives from flight controller.
Blocking API Control
Definition at line 171 of file DJI_API.cpp.
void CoreAPI::getDroneVersionCallback | ( | CoreAPI * | api, |
Header * | protocolHeader, | ||
UserData userData | __UNUSED = 0 |
||
) | [static] |
Definition at line 573 of file DJI_API.cpp.
SDKFilter CoreAPI::getFilter | ( | ) | const |
Open Protocol Control.
Get Open Protocol packet information.
Definition at line 877 of file DJI_API.cpp.
FlightStatus CoreAPI::getFlightStatus | ( | ) | const |
Get flight status at any time during a flight mission.
Definition at line 521 of file DJI_API.cpp.
bool CoreAPI::getFollowData | ( | ) | const |
Definition at line 537 of file DJI_API.cpp.
bool DJI::onboardSDK::CoreAPI::getGimbalCtrlMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getGlobalNavTestMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getGoHomeMobileCMD | ( | ) | [inline] |
bool CoreAPI::getHotPointData | ( | ) | const |
HotPoint Mission Control.
Definition at line 535 of file DJI_API.cpp.
bool DJI::onboardSDK::CoreAPI::getLandingMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getLocalMissionPlanCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getLocalNavTestMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getObtainControlMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getReleaseControlMobileCMD | ( | ) | [inline] |
Version CoreAPI::getSDKVersion | ( | ) | const |
Get SDK version
Definition at line 875 of file DJI_API.cpp.
SimpleACK CoreAPI::getSimpleACK | ( | ) | const |
Definition at line 569 of file DJI_API.cpp.
bool DJI::onboardSDK::CoreAPI::getStartVideoMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getStopVideoMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getTakeOffMobileCMD | ( | ) | [inline] |
bool DJI::onboardSDK::CoreAPI::getTakePhotoMobileCMD | ( | ) | [inline] |
TimeStampData CoreAPI::getTime | ( | ) | const |
Get timestamp from flight controller.
Definition at line 519 of file DJI_API.cpp.
bool DJI::onboardSDK::CoreAPI::getVRCTestMobileCMD | ( | ) | [inline] |
bool CoreAPI::getWayPointData | ( | ) | const |
WayPoint Mission Control.
Definition at line 536 of file DJI_API.cpp.
bool DJI::onboardSDK::CoreAPI::getWayPointTestMobileCMD | ( | ) | [inline] |
void CoreAPI::init | ( | HardDriver * | Driver, |
CallBackHandler | userRecvCallback, | ||
bool | userCallbackThread, | ||
Version | SDKVersion | ||
) | [private] |
void CoreAPI::notifyCaller | ( | Header * | protocolHeader | ) |
Definition at line 178 of file DJI_Link.cpp.
void CoreAPI::notifyNonBlockingCaller | ( | Header * | protocolHeader | ) |
This version of non-blocking can be limited in performance since the read thread waits for the callback thread to return before the read thread continues.
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.
Definition at line 189 of file DJI_Link.cpp.
void CoreAPI::parseFromMobileCallback | ( | CoreAPI * | api, |
Header * | protocolHeader, | ||
UserData userData | __UNUSED = 0 |
||
) |
Mobile Data Transparent Transmission Input Servicing.
MOS Protocol parsing lirbary functions. Default MOS Protocol Parser. Calls other callback functions based on data
The next few are only polling based and do not use callbacks. See usage in Linux Sample.
Definition at line 686 of file DJI_API.cpp.
void CoreAPI::readPoll | ( | void | ) |
Definition at line 256 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::recvReqData | ( | Header * | protocolHeader | ) | [private] |
Definition at line 123 of file DJI_App.cpp.
void 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 |
||
) |
timeout |
Definition at line 90 of file DJI_API.cpp.
void 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 |
||
) |
void CoreAPI::send | ( | Command * | parameter | ) |
Definition at line 140 of file DJI_API.cpp.
void CoreAPI::sendData | ( | unsigned char * | buf | ) | [private] |
Definition at line 32 of file DJI_Link.cpp.
int CoreAPI::sendInterface | ( | Command * | parameter | ) | [private] |
Definition at line 373 of file DJI_Link.cpp.
void CoreAPI::sendPoll | ( | void | ) |
Definition at line 209 of file DJI_Link.cpp.
void CoreAPI::sendToMobile | ( | uint8_t * | data, |
uint8_t | len, | ||
CallBack | callback = 0 , |
||
UserData | userData = 0 |
||
) |
Definition at line 252 of file DJI_API.cpp.
void CoreAPI::sendToMobileCallback | ( | CoreAPI * | api, |
Header * | protocolHeader, | ||
UserData userData | __UNUSED = 0 |
||
) | [static] |
Definition at line 666 of file DJI_API.cpp.
void CoreAPI::setAccountData | ( | const ActivateData & | value | ) |
Activation Control.
Definition at line 531 of file DJI_API.cpp.
void DJI::onboardSDK::CoreAPI::setACKFrameStatus | ( | uint32_t | usageFlag | ) |
Let user know when ACK and Broadcast messages processed
Definition at line 302 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::setActivateMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setActivateMobileCMD | ( | bool | userInput | ) | [inline] |
void CoreAPI::setActivation | ( | bool | isActivated | ) |
Activation Control.
Is your aircraft already activated ?
Definition at line 294 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::setArmMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setArmMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setAttiCtrlMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setBroadcastCallback | ( | CallBackHandler | callback | ) | [inline] |
void CoreAPI::setBroadcastCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 229 of file DJI_App.cpp.
void DJI::onboardSDK::CoreAPI::setBroadcastFrameStatus | ( | bool | isFrame | ) |
Definition at line 54 of file DJI_App.cpp.
void CoreAPI::setBroadcastFreq | ( | uint8_t * | dataLenIs16, |
CallBack | callback = 0 , |
||
UserData | userData = 0 |
||
) |
Set broadcast frequency.
Definition at line 263 of file DJI_API.cpp.
unsigned short CoreAPI::setBroadcastFreq | ( | uint8_t * | dataLenIs16, |
int | timeout | ||
) |
Definition at line 289 of file DJI_API.cpp.
void CoreAPI::setBroadcastFreqDefaults | ( | ) |
Reset all broadcast frequencies to their default values
Definition at line 320 of file DJI_API.cpp.
unsigned short CoreAPI::setBroadcastFreqDefaults | ( | int | timeout | ) |
Set broadcast frequencies to their default values and block until ACK arrives from flight controller.
Blocking API Control
Definition at line 448 of file DJI_API.cpp.
void CoreAPI::setBroadcastFreqToZero | ( | ) |
Definition at line 390 of file DJI_API.cpp.
void CoreAPI::setControl | ( | bool | enable, |
CallBack | callback = 0 , |
||
UserData | userData = 0 |
||
) |
Definition at line 539 of file DJI_API.cpp.
unsigned short CoreAPI::setControl | ( | bool | enable, |
int | timeout | ||
) |
Blocking API Control.
Obtain control
Definition at line 546 of file DJI_API.cpp.
void CoreAPI::setControlCallback | ( | CoreAPI * | api, |
Header * | protocolHeader, | ||
UserData userData | __UNUSED = 0 |
||
) | [static] |
Definition at line 881 of file DJI_API.cpp.
void DJI::onboardSDK::CoreAPI::setDisArmMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setDisArmMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setDrawCirMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setDrawSqrMobileCMD | ( | bool | userInput | ) | [inline] |
void CoreAPI::setDriver | ( | HardDriver * | value | ) |
Initialize serial device
Definition at line 571 of file DJI_API.cpp.
void DJI::onboardSDK::CoreAPI::setFollowCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setFollowCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 141 of file DJI_Mission.cpp.
void CoreAPI::setFollowData | ( | bool | value | ) |
Follow Me Mission Control.
Definition at line 534 of file DJI_API.cpp.
void CoreAPI::setFrequencyCallback | ( | CoreAPI * | api, |
Header * | protocolHeader, | ||
UserData | userData = 0 |
||
) | [static] |
Definition at line 848 of file DJI_API.cpp.
void CoreAPI::setFromMobileCallback | ( | CallBackHandler | FromMobileEntrance | ) |
Definition at line 523 of file DJI_API.cpp.
void CoreAPI::setFromMobileCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 235 of file DJI_App.cpp.
void DJI::onboardSDK::CoreAPI::setGimbalCtrlMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setGlobalNavTestMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setGoHomeMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setGoHomeMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setHotPointCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setHotPointCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 129 of file DJI_Mission.cpp.
void CoreAPI::setHotPointData | ( | bool | value | ) |
HotPoint Mission Control.
Definition at line 532 of file DJI_API.cpp.
void CoreAPI::setKey | ( | const char * | key | ) |
Definition at line 288 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::setLandingMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setLandingMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setLocalMissionPlanCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setLocalNavTestMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setMisssionCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setMisssionCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 123 of file DJI_Mission.cpp.
void DJI::onboardSDK::CoreAPI::setObtainControlMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setObtainControlMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setReleaseControlMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setReleaseControlMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setStartVideoMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setStartVideoMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setStopVideoMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setStopVideoMobileCMD | ( | bool | userInput | ) | [inline] |
void CoreAPI::setSyncFreq | ( | uint32_t | freqInHz | ) |
Definition at line 312 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::setTakeOffMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setTakeOffMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setTakePhotoMobileCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setTakePhotoMobileCMD | ( | bool | userInput | ) | [inline] |
void CoreAPI::setup | ( | void | ) | [private] |
Definition at line 282 of file DJI_Link.cpp.
void DJI::onboardSDK::CoreAPI::setupMMU | ( | void | ) | [private] |
Definition at line 25 of file DJI_Memory.cpp.
void DJI::onboardSDK::CoreAPI::setupSession | ( | void | ) | [private] |
Definition at line 163 of file DJI_Memory.cpp.
void CoreAPI::setVersion | ( | const Version & | value | ) |
Set SDK version.
Definition at line 879 of file DJI_API.cpp.
void DJI::onboardSDK::CoreAPI::setVRCTestMobileCMD | ( | bool | userInput | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setWayPointCallback | ( | CallBackHandler | callback | ) | [inline] |
void DJI::onboardSDK::CoreAPI::setWayPointCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 135 of file DJI_Mission.cpp.
void CoreAPI::setWayPointData | ( | bool | value | ) |
WayPoint Mission Control.
Definition at line 533 of file DJI_API.cpp.
void DJI::onboardSDK::CoreAPI::setWayPointEventCallback | ( | CallBackHandler | callback | ) |
Definition at line 118 of file DJI_Mission.cpp.
void DJI::onboardSDK::CoreAPI::setWayPointEventCallback | ( | CallBack | handler, |
UserData | userData = 0 |
||
) |
Definition at line 147 of file DJI_Mission.cpp.
void DJI::onboardSDK::CoreAPI::setWayPointTestMobileCMD | ( | bool | userInput | ) | [inline] |
void CoreAPI::storeData | ( | SDKFilter * | p_filter, |
unsigned char | in_data | ||
) | [private] |
Definition at line 645 of file DJI_Codec.cpp.
void DJI::onboardSDK::CoreAPI::streamHandler | ( | SDKFilter * | p_filter, |
unsigned char | in_data | ||
) | [private] |
Definition at line 755 of file DJI_Codec.cpp.
void DJI::onboardSDK::CoreAPI::verifyData | ( | SDKFilter * | p_filter | ) | [private] |
Definition at line 701 of file DJI_Codec.cpp.
void DJI::onboardSDK::CoreAPI::verifyHead | ( | SDKFilter * | p_filter | ) | [private] |
Definition at line 715 of file DJI_Codec.cpp.
uint32_t DJI::onboardSDK::CoreAPI::ack_data |
uint32_t DJI::onboardSDK::CoreAPI::ackFrameStatus [private] |
bool DJI::onboardSDK::CoreAPI::activateMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::armMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::attiCtrlMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::broadcastFrameStatus [private] |
bool DJI::onboardSDK::CoreAPI::callbackThread [private] |
bool DJI::onboardSDK::CoreAPI::disArmMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::drawCirMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::drawSqrMobileCMD [private] |
unsigned char DJI::onboardSDK::CoreAPI::encodeACK[ACK_SIZE] [private] |
unsigned char DJI::onboardSDK::CoreAPI::encodeSendData[BUFFER_SIZE] [private] |
SDKFilter DJI::onboardSDK::CoreAPI::filter [private] |
bool DJI::onboardSDK::CoreAPI::followData [private] |
bool DJI::onboardSDK::CoreAPI::gimbalCtrlMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::globalNavTestMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::goHomeMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::hotPointData [private] |
bool DJI::onboardSDK::CoreAPI::landingMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::localMissionPlanCMD [private] |
bool DJI::onboardSDK::CoreAPI::localNavTestMobileCMD [private] |
unsigned char DJI::onboardSDK::CoreAPI::memory[MEMORY_SIZE] [private] |
MMU_Tab DJI::onboardSDK::CoreAPI::MMU[MMU_TABLE_NUM] [private] |
bool DJI::onboardSDK::CoreAPI::obtainControlMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::releaseControlMobileCMD [private] |
unsigned short DJI::onboardSDK::CoreAPI::seq_num [private] |
bool DJI::onboardSDK::CoreAPI::startVideoMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::stopVideoMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::takeOffMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::takePhotoMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::VRCTestMobileCMD [private] |
bool DJI::onboardSDK::CoreAPI::wayPointData [private] |
bool DJI::onboardSDK::CoreAPI::wayPointTestMobileCMD [private] |