From ffc2f08a7f5da0f7d590fcba281d80706dd975cd Mon Sep 17 00:00:00 2001 From: ArjunMenon Date: Fri, 23 Jun 2017 18:36:37 -0700 Subject: [PATCH] OSDKROS 3.3 - Changes to ReadMe file with updated support information --- ReadMe.md | 29 ++++++++++++++++++- dji_sdk/src/modules/dji_sdk_node.cpp | 7 +---- .../modules/dji_sdk_node_mission_services.cpp | 1 - .../src/modules/dji_sdk_node_publisher.cpp | 6 +++- dji_sdk_demo/src/demo_mobile_comm.cpp | 1 + 5 files changed, 35 insertions(+), 9 deletions(-) diff --git a/ReadMe.md b/ReadMe.md index 3224da3a..a301795d 100644 --- a/ReadMe.md +++ b/ReadMe.md @@ -10,7 +10,34 @@ This repository contains the Onboard SDK ROS wrapper and demos. The ROS package The ROS package is a full rewrite of DJI Onboard SDK ROS, with changes in APIs, reference frames, communication mechanisms etc. We encourage you to take a look at the documentation for full details. -ROS Wiki can be found [here](http://wiki.ros.org/dji_sdk). +ROS Wiki can be found [here](http://wiki.ros.org/dji_sdk). Please be sure to read the [release notes](https://developer.dji.com/onboard-sdk/documentation/appendix/releaseNotes.html). + +## Firmware Compatibility + +| Aircraft/FC | Firmware Package Version | Flight Controller Version | OSDK Version Support | +|--------------- |--------------------------|----------------------------|---------------------- | +| **A3/A3 Pro** | **1.7.1.5** | **3.2.36.8** | **OSDK 3.3 (Current)** | +| | 1.7.0.5 | 3.2.15.50 | OSDK 3.2 | +| | 1.7.0.0 | 3.2.15.37 | OSDK 3.2 | +| | | | | +| **N3** | **1.7.1.5** | **3.2.36.8** | **OSDK 3.3 (Current)** | +| | 1.7.0.0 | 3.2.15.37 | OSDK 3.2 | +| | | | | +| **M600/M600 Pro** | Coming soon! | Coming soon! | **OSDK 3.3 (Current)** | +| | 1.0.1.20 | 3.2.15.62 | OSDK 3.2 | +| | 1.0.0.80 | 3.2.15.00 | OSDK 3.2 | +| | | | | +| **M100** | 1.3.1.0 | 3.1.10.0 | OSDK 3.2 | + + +## Support + +You can get support from DJI and the community with the following methods: + +- Github Issues or [gitter.im](https://gitter.im/dji-sdk/Onboard-SDK) +- Send email to dev@dji.com describing your problem and a clear description of your setup +- Post questions on [**Stackoverflow**](http://stackoverflow.com) using [**dji-sdk**](http://stackoverflow.com/questions/tagged/dji-sdk) tag +- [**DJI Forum**](http://forum.dev.dji.com/en) diff --git a/dji_sdk/src/modules/dji_sdk_node.cpp b/dji_sdk/src/modules/dji_sdk_node.cpp index 280b04d3..667a97d1 100644 --- a/dji_sdk/src/modules/dji_sdk_node.cpp +++ b/dji_sdk/src/modules/dji_sdk_node.cpp @@ -420,12 +420,7 @@ bool DJISDKNode::validateSerialDevice(LinuxSerialDevice* serialDevice) //! Check the serial channel for data uint8_t buf[BUFFER_SIZE]; if (!serialDevice->setSerialPureTimedRead()) { - ROS_ERROR("Failed to set up port for timed read.\n" - "This usually means the serial port is not correctly set up; \n" - "however on a small number of machines this error can come up\n" - "even when the port is correctly set up. If you are absolutely certain\n" - "your connections are okay, try commenting out L77-L89 in file dji_sdk_node.cpp\n" - "and build again.\n"); + ROS_ERROR("Failed to set up port for timed read.\n"); return (false); }; usleep(100000); diff --git a/dji_sdk/src/modules/dji_sdk_node_mission_services.cpp b/dji_sdk/src/modules/dji_sdk_node_mission_services.cpp index 6e9cd05c..972cbbdc 100644 --- a/dji_sdk/src/modules/dji_sdk_node_mission_services.cpp +++ b/dji_sdk/src/modules/dji_sdk_node_mission_services.cpp @@ -19,7 +19,6 @@ DJISDKNode::missionStatusCallback(dji_sdk::MissionStatus::Request& request, response.waypoint_mission_count = vehicle->missionManager->wayptCounter; response.hotpoint_mission_count = vehicle->missionManager->hotptCounter; - return true; } diff --git a/dji_sdk/src/modules/dji_sdk_node_publisher.cpp b/dji_sdk/src/modules/dji_sdk_node_publisher.cpp index 4996a9dc..e6faf291 100644 --- a/dji_sdk/src/modules/dji_sdk_node_publisher.cpp +++ b/dji_sdk/src/modules/dji_sdk_node_publisher.cpp @@ -253,6 +253,8 @@ DJISDKNode::publish50HzData(Vehicle* vehicle, RecvContainer recvFrame, Telemetry::TypeMap::type v_FC = vehicle->subscribe->getValue(); geometry_msgs::Vector3Stamped v; + // v_FC has 2 fields, data and info. The latter contains the health + /*! * note: We are now following REP 103 to use ENU for @@ -282,8 +284,8 @@ DJISDKNode::publish50HzData(Vehicle* vehicle, RecvContainer recvFrame, gimbal_angle_vec3.vector.z = gimbal_angle.z; p->gimbal_angle_publisher.publish(gimbal_angle_vec3); - // See dji_sdk.h for details about display_mode + Telemetry::TypeMap::type dm = vehicle->subscribe->getValue(); @@ -315,6 +317,8 @@ DJISDKNode::publish50HzData(Vehicle* vehicle, RecvContainer recvFrame, * V V * -10000 -10000 * + * In this code, before publish, RC is transformed to M100 style to be compatible with controller + *****************************/ // sensor_msgs::Joy rc_joy; diff --git a/dji_sdk_demo/src/demo_mobile_comm.cpp b/dji_sdk_demo/src/demo_mobile_comm.cpp index f25ea653..2a9c9f7e 100644 --- a/dji_sdk_demo/src/demo_mobile_comm.cpp +++ b/dji_sdk_demo/src/demo_mobile_comm.cpp @@ -94,6 +94,7 @@ int main(int argc, char *argv[]) { Display_Main_Menu(); while (!userExitCommand && ros::ok()) { + ros::spinOnce(); std::cout << "Enter Input Val: "; while (!(std::cin >> temp32)) {