Skip to content

Commit

Permalink
Updated ROS with latest Core API. Change to DJI_Hardriver to implemen…
Browse files Browse the repository at this point in the history
…t default Getdevicestatus
  • Loading branch information
amenonDJI committed Sep 28, 2016
1 parent b40b12f commit 8b6744a
Show file tree
Hide file tree
Showing 14 changed files with 297 additions and 39 deletions.
1 change: 1 addition & 0 deletions .catkin_workspace
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
# This file currently only serves to mark the location of a catkin workspace for tool integration
1 change: 1 addition & 0 deletions CMakeLists.txt
47 changes: 38 additions & 9 deletions dji_sdk_lib/include/dji_sdk_lib/DJI_API.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -228,6 +228,7 @@ class CoreAPI

//! Notify caller ACK frame arrived
void notifyCaller(Header *protocolHeader);
void notifyNonBlockingCaller(Header *protocolHeader);

//@{
/**
Expand Down Expand Up @@ -401,6 +402,8 @@ class CoreAPI
/**Get broadcasted data values from flight controller.*/
BroadcastData getBroadcastData() const;

bool nonBlockingCBThreadEnable = false;

/**
* Get timestamp from flight controller.
*
Expand Down Expand Up @@ -433,6 +436,7 @@ class CoreAPI
*/
HardDriver *getDriver() const;

SimpleACK getSimpleACK() const;
/**
* Get SDK version
*/
Expand Down Expand Up @@ -545,7 +549,8 @@ class CoreAPI
void setVersion(const Version &value);

/**
* 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
*/
bool getObtainControlMobileCMD() {return obtainControlMobileCMD;}
bool getReleaseControlMobileCMD() {return releaseControlMobileCMD;}
Expand All @@ -558,7 +563,15 @@ class CoreAPI
bool getTakePhotoMobileCMD() {return takePhotoMobileCMD;}
bool getStartVideoMobileCMD() {return startVideoMobileCMD;}
bool getStopVideoMobileCMD() {return stopVideoMobileCMD;}
bool getFollowMeMobileCMD() {return followMeMobileCMD;}

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;}

void setObtainControlMobileCMD(bool userInput) {obtainControlMobileCMD = userInput;}
void setReleaseControlMobileCMD(bool userInput) {releaseControlMobileCMD= userInput;}
Expand All @@ -571,7 +584,15 @@ 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;}

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;}


private:
Expand All @@ -581,9 +602,7 @@ 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;
Expand All @@ -605,6 +624,8 @@ class CoreAPI
CallBackHandler startVideoMobileCallback;
CallBackHandler stopVideoMobileCallback;

//! Mobile Data Transparent Transmission - flags

bool obtainControlMobileCMD;
bool releaseControlMobileCMD;
bool activateMobileCMD;
Expand All @@ -616,8 +637,16 @@ 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;

VersionData versionData;
ActivateData accountData;

Expand Down
1 change: 1 addition & 0 deletions dji_sdk_lib/include/dji_sdk_lib/DJI_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion dji_sdk_lib/include/dji_sdk_lib/DJI_Follow.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
10 changes: 10 additions & 0 deletions dji_sdk_lib/include/dji_sdk_lib/DJI_HardDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -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() {;}

public:
virtual void lockMemory() = 0;
Expand All @@ -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);
};
Expand Down
3 changes: 3 additions & 0 deletions dji_sdk_lib/include/dji_sdk_lib/DJI_Link.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,4 +24,7 @@

#include "DJI_Type.h"



#endif // DJI_LINK_H

47 changes: 47 additions & 0 deletions dji_sdk_lib/include/dji_sdk_lib/DJI_Logging.h
Original file line number Diff line number Diff line change
@@ -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
9 changes: 8 additions & 1 deletion dji_sdk_lib/include/dji_sdk_lib/DJI_Type.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -310,7 +317,7 @@ typedef struct WayPointData
*/

typedef uint8_t MissionACK;
typedef uint32_t SimpleACK;
typedef uint16_t SimpleACK;

typedef struct HotPointStartACK
{
Expand Down
1 change: 0 additions & 1 deletion dji_sdk_lib/include/dji_sdk_lib/DJI_Version.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
61 changes: 45 additions & 16 deletions dji_sdk_lib/src/DJI_API.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,6 +214,10 @@ 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)
Expand Down Expand Up @@ -304,7 +308,6 @@ unsigned short CoreAPI::setBroadcastFreq(uint8_t *dataLenIs16, int timeout)
serialDevice->lockACK();
serialDevice->wait(timeout);
serialDevice->freeACK();

return missionACKUnion.simpleACK;
}

Expand Down Expand Up @@ -362,18 +365,18 @@ void CoreAPI::setBroadcastFreqToZero()
* 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;
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;

setBroadcastFreq(freq);
}
Expand Down Expand Up @@ -456,6 +459,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)
Expand Down Expand Up @@ -559,6 +564,8 @@ void CoreAPI::sendToMobileCallback(CoreAPI *api, Header *protocolHeader, UserDat
protocolHeader->sessionID, protocolHeader->sequenceNumber);
}
}

//! Mobile Data Transparent Transmission Input Servicing
void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, UserData userData __UNUSED)
{
uint16_t mobile_data_id;
Expand Down Expand Up @@ -689,11 +696,33 @@ void CoreAPI::parseFromMobileCallback(CoreAPI *api, Header *protocolHeader, User
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:
followMeMobileCMD = true;
VRCTestMobileCMD = true;
break;
}
}

}
}

void CoreAPI::setFrequencyCallback(CoreAPI *api __UNUSED, Header *protocolHeader,
Expand Down
4 changes: 2 additions & 2 deletions dji_sdk_lib/src/DJI_App.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Loading

0 comments on commit 8b6744a

Please sign in to comment.