Skip to content

Commit

Permalink
OSDK 3.2.1 commit - versioning system overhauled. See Release Notes o…
Browse files Browse the repository at this point in the history
…n the website.
  • Loading branch information
Rohit Sant committed Feb 3, 2017
1 parent 44670dc commit 3109a6d
Show file tree
Hide file tree
Showing 29 changed files with 500 additions and 489 deletions.
1 change: 0 additions & 1 deletion dji_sdk/include/dji_sdk/DJI_LIB_ROS_Adapter.h
Expand Up @@ -141,7 +141,6 @@ class ROSAdapter {

void activate(ActivateData *data, CallBack callback) {

coreAPI->setVersion(data->version);
coreAPI->activate(data, callback);

}
Expand Down
4 changes: 1 addition & 3 deletions dji_sdk/launch/sdk_manifold.launch
@@ -1,13 +1,11 @@
<launch>
<node pkg="dji_sdk" type="dji_sdk_node" name="dji_sdk" output="screen">
<!-- node parameters -->
<!-- For Drone Version enter M100 or A3_31 or A3_32 depending on your Flight Controller/Aircraft -->
<param name="drone_version" type="string" value="M100"/>
<param name="serial_name" type="string" value="/dev/ttyUSB0"/>
<param name="baud_rate" type="int" value="230400"/>
<param name="app_id" type="int" value="1234EnterAppIDhere"/>
<param name="app_version" type="int" value="1"/>
<param name="app_bundle_id" type="string" value="Welcome to use dji-sdk"/>
<param name="app_bundle_id" type="string" value="Not required in this SDK version"/>
<param name="enc_key" type="string" value="1234Enterkeyhere"/>
<param name="groundstation_enable" type="int" value="1"/>
</node>
Expand Down
1 change: 0 additions & 1 deletion dji_sdk/launch/sdk_osx.launch
@@ -1,7 +1,6 @@
<launch>
<node pkg="dji_sdk" type="dji_sdk_node" name="dji_sdk" output="screen">
<!-- node parameters -->
<param name="drone_version" type="string" value="M100"/>
<param name="serial_name" type="string" value="/dev/cu.usbserial-A603T4HK"/>
<param name="baud_rate" type="int" value="230400"/>
<param name="app_id" type="int" value="1022384"/>
Expand Down
8 changes: 4 additions & 4 deletions dji_sdk/package.xml
@@ -1,14 +1,14 @@
<?xml version="1.0"?>
<package>
<name>dji_sdk</name>
<version>0.1.9</version>
<version>3.2.0</version>
<description>A ROS package using DJI Onboard SDK. </description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="norman.li@dji.com">Norman Li</maintainer>
<maintainer email="me@botao.hu">Botao Hu</maintainer>
<maintainer email="arjun.menon@dji.com">Arjun Menon</maintainer>


<!-- One license tag required, multiple allowed, one license per tag -->
Expand All @@ -20,13 +20,13 @@
<!-- Url tags are optional, but mutiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/dji_sdk</url> -->
<url type="website">http://developer.dji.com/onboard-sdk/documentation/github-platform-docs/ROS/README.html</url>


<!-- Author tags are optional, mutiple are allowed, one per tag -->
<!-- Authors do not have to be maintianers, but could be -->
<!-- Example: -->
<author email="me@botao.hu">Botao Hu</author>
<author email="arjun.menon@dji.com">Arjun Menon</author>


<!-- The *_depend tags are used to specify dependencies -->
Expand Down
40 changes: 13 additions & 27 deletions dji_sdk/src/modules/dji_sdk_node_main.cpp
Expand Up @@ -29,7 +29,7 @@ void DJISDKNode::broadcast_callback()
{
DJI::onboardSDK::BroadcastData bc_data = rosAdapter->coreAPI->getBroadcastData();

DJI::onboardSDK::Version version = rosAdapter->coreAPI->getSDKVersion();
DJI::onboardSDK::Version version = rosAdapter->coreAPI->getFwVersion();
unsigned short msg_flags = bc_data.dataFlag;

static int frame_id = 0;
Expand Down Expand Up @@ -143,10 +143,10 @@ void DJISDKNode::broadcast_callback()
}

/******************************************************************
****************************If using A3****************************
****************************If using A3/N3/M600********************
******************************************************************/

if(version == DJI::onboardSDK::versionA3_31 || version == DJI::onboardSDK::versionA3_32) {
if(version > MAKE_VERSION(3,1,10,0)) {

//update gimbal msg
if (msg_flags & A3_HAS_GIMBAL) {
Expand Down Expand Up @@ -321,7 +321,6 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private)
std::string serial_name;
int baud_rate;
int app_id;
int app_version;
std::string app_bundle_id; //reserved
std::string enc_key;
int uart_or_usb;
Expand All @@ -330,7 +329,6 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private)
nh_private.param("serial_name", serial_name, std::string("/dev/ttyTHS1"));
nh_private.param("baud_rate", baud_rate, 230400);
nh_private.param("app_id", app_id, 1022384);
nh_private.param("app_version", app_version, 1);
nh_private.param("enc_key", enc_key,
std::string("e7bad64696529559318bb35d0a8c6050d3b88e791e1808cfe8f7802150ee6f0d"));

Expand All @@ -339,32 +337,12 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private)

// activation
user_act_data.ID = app_id;

if((uart_or_usb)&&(drone_version.compare("M100")))
{
printf("M100 does not support USB API.\n");
return -1;
}

if(!drone_version.compare("M100"))
{
user_act_data.version = versionM100_31;
}
else if (!drone_version.compare("A3_31"))
{
user_act_data.version = versionA3_31;
}
else if (!drone_version.compare("A3_32"))
{
user_act_data.version = versionA3_32;
}
user_act_data.encKey = app_key;
strcpy(user_act_data.encKey, enc_key.c_str());

printf("=================================================\n");
printf("app id: %d\n", user_act_data.ID);
printf("app version: 0x0%X\n", user_act_data.version);
printf("app key: %s\n", user_act_data.encKey);
printf("app id : %d\n", user_act_data.ID);
printf("app key : %s\n", user_act_data.encKey);
printf("=================================================\n");

if(uart_or_usb) //use usb port for SDK
Expand All @@ -373,6 +351,14 @@ int DJISDKNode::init_parameters(ros::NodeHandle& nh_private)
}

rosAdapter->init(serial_name, baud_rate);
rosAdapter->coreAPI->getDroneVersion();
//usleep(1000000);
ros::Duration(1.0).sleep();
printf("=================================================\n");
printf("Hardware : %s\n", rosAdapter->coreAPI->getHwVersion());
printf("Firmware : 0x0%X\n", rosAdapter->coreAPI->getFwVersion());
printf("=================================================\n");

rosAdapter->activate(&user_act_data, NULL);
rosAdapter->setBroadcastCallback(&DJISDKNode::broadcast_callback, this);
rosAdapter->setFromMobileCallback(&DJISDKNode::transparent_transmission_callback,this);
Expand Down
2 changes: 1 addition & 1 deletion dji_sdk/src/modules/dji_sdk_node_services.cpp
Expand Up @@ -218,7 +218,7 @@ bool DJISDKNode::velocity_control_callback(dji_sdk::VelocityControl::Request& re
bool DJISDKNode::version_check_callback(dji_sdk::VersionCheck::Request& request, dji_sdk::VersionCheck::Response& response)
{
int sdkVer;
sdkVer = rosAdapter->coreAPI->getSDKVersion();
sdkVer = rosAdapter->coreAPI->getFwVersion();
std::cout << std::hex << sdkVer << '\n';
response.result = true;
return true;
Expand Down
4 changes: 2 additions & 2 deletions dji_sdk_doc/doxygen/html/DJI__API_8h_source.html

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion dji_sdk_doc/doxygen/html/DJI__App_8h_source.html

Large diffs are not rendered by default.

Expand Up @@ -115,7 +115,7 @@
<tr class="even"><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#a83775b0cee8ef84d454ce6025edc1b62">getFlightStatus</a>() const </td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0"><td class="entry"><b>getFollowData</b>() const (defined in <a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a>)</td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#a021fc52fda6637f3624ae14e1a96dc28">getHotPointData</a>() const </td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f">getSDKVersion</a>() const </td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f">getFwVersion</a>() const </td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0" class="even"><td class="entry"><b>getSessionStatus</b>() (defined in <a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a>)</td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#af90c4551b82a3926d9ed5316b4084bb3">getTime</a>() const </td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
<tr class="even"><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#ab5aa9af0ebe66a85ef24630284a1699d">getWayPointData</a>() const </td><td class="entry"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html">DJI::onboardSDK::CoreAPI</a></td><td class="entry"></td></tr>
Expand Down
Expand Up @@ -158,7 +158,7 @@
<tr class="separator:a0b42c3b5010dea459c294a357d5f759c"><td class="memSeparator" colspan="2">&#160;</td></tr>
<tr class="memitem:ab06228e965457f85ac8eebc7669a09ef"><td class="memItemLeft" align="right" valign="top"><a class="el" href="classDJI_1_1onboardSDK_1_1HardDriver.html">HardDriver</a> *&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#ab06228e965457f85ac8eebc7669a09ef">getDriver</a> () const </td></tr>
<tr class="separator:ab06228e965457f85ac8eebc7669a09ef"><td class="memSeparator" colspan="2">&#160;</td></tr>
<tr class="memitem:aba01d2d5cc5fa9b13198312d1cc8fd5f"><td class="memItemLeft" align="right" valign="top"><a class="el" href="DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495">Version</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f">getSDKVersion</a> () const </td></tr>
<tr class="memitem:aba01d2d5cc5fa9b13198312d1cc8fd5f"><td class="memItemLeft" align="right" valign="top"><a class="el" href="DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495">Version</a>&#160;</td><td class="memItemRight" valign="bottom"><a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f">getFwVersion</a> () const </td></tr>
<tr class="separator:aba01d2d5cc5fa9b13198312d1cc8fd5f"><td class="memSeparator" colspan="2">&#160;</td></tr>
<tr class="memitem:a7be1fa967af760409494aadb779ad413"><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a7be1fa967af760409494aadb779ad413"></a>
void&#160;</td><td class="memItemRight" valign="bottom"><b>setBroadcastCallback</b> (<a class="el" href="structDJI_1_1onboardSDK_1_1CallBackHandler.html">CallBackHandler</a> callback)</td></tr>
Expand Down Expand Up @@ -571,7 +571,7 @@
<div class="memproto">
<table class="memname">
<tr>
<td class="memname"><a class="el" href="DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495">Version</a> CoreAPI::getSDKVersion </td>
<td class="memname"><a class="el" href="DJI__Version_8h.html#a1621781715a8b4947de1fdbf3dd80495">Version</a> CoreAPI::getFwVersion </td>
<td>(</td>
<td class="paramname"></td><td>)</td>
<td> const</td>
Expand Down
2 changes: 1 addition & 1 deletion dji_sdk_doc/doxygen/html/functions.html
Expand Up @@ -222,7 +222,7 @@ <h3><a class="anchor" id="index_g"></a>- g -</h3><ul>
<li>getRCData()
: <a class="el" href="classDJI_1_1onboardSDK_1_1VirtualRC.html#ab2ff6d77cdc0da443c5ae27736c06501">DJI::onboardSDK::VirtualRC</a>
</li>
<li>getSDKVersion()
<li>getFwVersion()
: <a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f">DJI::onboardSDK::CoreAPI</a>
</li>
<li>getTime()
Expand Down
2 changes: 1 addition & 1 deletion dji_sdk_doc/doxygen/html/functions_func.html
Expand Up @@ -196,7 +196,7 @@ <h3><a class="anchor" id="index_g"></a>- g -</h3><ul>
<li>getRCData()
: <a class="el" href="classDJI_1_1onboardSDK_1_1VirtualRC.html#ab2ff6d77cdc0da443c5ae27736c06501">DJI::onboardSDK::VirtualRC</a>
</li>
<li>getSDKVersion()
<li>getFwVersion()
: <a class="el" href="classDJI_1_1onboardSDK_1_1CoreAPI.html#aba01d2d5cc5fa9b13198312d1cc8fd5f">DJI::onboardSDK::CoreAPI</a>
</li>
<li>getTime()
Expand Down
2 changes: 1 addition & 1 deletion dji_sdk_doc/doxygen/html/structVersionData-members.html
Expand Up @@ -93,7 +93,7 @@
<tr bgcolor="#f0f0f0" class="even"><td class="entry"><b>version</b> (defined in <a class="el" href="structVersionData.html">VersionData</a>)</td><td class="entry"><a class="el" href="structVersionData.html">VersionData</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0"><td class="entry"><b>version_ack</b> (defined in <a class="el" href="structVersionData.html">VersionData</a>)</td><td class="entry"><a class="el" href="structVersionData.html">VersionData</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0" class="even"><td class="entry"><b>version_crc</b> (defined in <a class="el" href="structVersionData.html">VersionData</a>)</td><td class="entry"><a class="el" href="structVersionData.html">VersionData</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0"><td class="entry"><b>version_ID</b> (defined in <a class="el" href="structVersionData.html">VersionData</a>)</td><td class="entry"><a class="el" href="structVersionData.html">VersionData</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0"><td class="entry"><b>hw_serial_num</b> (defined in <a class="el" href="structVersionData.html">VersionData</a>)</td><td class="entry"><a class="el" href="structVersionData.html">VersionData</a></td><td class="entry"></td></tr>
<tr bgcolor="#f0f0f0" class="even"><td class="entry"><b>version_name</b> (defined in <a class="el" href="structVersionData.html">VersionData</a>)</td><td class="entry"><a class="el" href="structVersionData.html">VersionData</a></td><td class="entry"></td></tr>
</table></div><!-- contents -->
<!-- start footer part -->
Expand Down
2 changes: 1 addition & 1 deletion dji_sdk_doc/doxygen/html/structVersionData.html
Expand Up @@ -100,7 +100,7 @@
unsigned int&#160;</td><td class="memItemRight" valign="bottom"><b>version_crc</b></td></tr>
<tr class="separator:ade3eba54d9e8b303e27eba71475e9907"><td class="memSeparator" colspan="2">&#160;</td></tr>
<tr class="memitem:a587b6b572f66745c53276b1fad61c3fd"><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a587b6b572f66745c53276b1fad61c3fd"></a>
char&#160;</td><td class="memItemRight" valign="bottom"><b>version_ID</b> [11]</td></tr>
char&#160;</td><td class="memItemRight" valign="bottom"><b>hw_serial_num</b> [11]</td></tr>
<tr class="separator:a587b6b572f66745c53276b1fad61c3fd"><td class="memSeparator" colspan="2">&#160;</td></tr>
<tr class="memitem:a47f69033ccee97765b271be73766a69b"><td class="memItemLeft" align="right" valign="top"><a class="anchor" id="a47f69033ccee97765b271be73766a69b"></a>
char&#160;</td><td class="memItemRight" valign="bottom"><b>version_name</b> [32]</td></tr>
Expand Down

0 comments on commit 3109a6d

Please sign in to comment.