Skip to content

Commit

Permalink
OSDKROS 3.3 - Changes to ReadMe file with updated support information
Browse files Browse the repository at this point in the history
  • Loading branch information
amenonDJI committed Jun 24, 2017
1 parent c9bf681 commit ffc2f08
Show file tree
Hide file tree
Showing 5 changed files with 35 additions and 9 deletions.
29 changes: 28 additions & 1 deletion ReadMe.md
Expand Up @@ -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)



Expand Down
7 changes: 1 addition & 6 deletions dji_sdk/src/modules/dji_sdk_node.cpp
Expand Up @@ -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);
Expand Down
1 change: 0 additions & 1 deletion dji_sdk/src/modules/dji_sdk_node_mission_services.cpp
Expand Up @@ -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;
}

Expand Down
6 changes: 5 additions & 1 deletion dji_sdk/src/modules/dji_sdk_node_publisher.cpp
Expand Up @@ -253,6 +253,8 @@ DJISDKNode::publish50HzData(Vehicle* vehicle, RecvContainer recvFrame,
Telemetry::TypeMap<Telemetry::TOPIC_VELOCITY>::type v_FC =
vehicle->subscribe->getValue<Telemetry::TOPIC_VELOCITY>();
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
Expand Down Expand Up @@ -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<Telemetry::TOPIC_STATUS_DISPLAYMODE>::type dm =
vehicle->subscribe->getValue<Telemetry::TOPIC_STATUS_DISPLAYMODE>();

Expand Down Expand Up @@ -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;
Expand Down
1 change: 1 addition & 0 deletions dji_sdk_demo/src/demo_mobile_comm.cpp
Expand Up @@ -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)) {
Expand Down

0 comments on commit ffc2f08

Please sign in to comment.