Only released in EOL distros:
Package Summary
A ROS package using DJI Onboard SDK.
- Maintainer status: maintained
- Maintainer: Norman Li <norman.li AT dji DOT com>, Botao Hu <me AT botao DOT hu>
- Author: Botao Hu <me AT botao DOT hu>
- License: MIT
- Source: git https://github.com/dji-sdk/Onboard-SDK-ROS.git (branch: 3.1)
Contents
Overview
This package provides a ROS interface for the DJI onboard SDK and enables the users to take full control of supported platforms (DJI M100, M600, M210, or drones equipped with A3/N3 flight controllers) using ROS messages and services.
This package depends on DJI SDK core library, which can be found here.
The latest releases 3.4 and 3.5 introduce support for Matrice 210 and 210 RTK. Developers will now have access to previously unavailable data such as stereo camera feeds (front-facing and downward-facing), FPV camera stream, and main gimbaled camera stream through USB. M210 Users will need to upgrade to the latest firmware (1.1.0410) to work with Onboard SDK and to download the latest DJI Assistant 2 (1.1.8) for simulation.
ATTENTION:
Since version 3.3, the dji_sdk ROS package starts to follow the REP103 convention on coordinate frame and units for the telemetry data. In the header of most of the telemetry data such as imu and attitude, the frame_id is either "body_FLU" or ground_ENU, to make it explicit. The flight control signals subscribed by the dji_sdk node are also supposed to be FLU for body frame or ENU for ground frame. The gimbal related data is currently NOT fully following the convention yet.
Nodes
dji_sdk
The main wrapper node for DJI Onboard SDKSubscribed Topics
1. Flight Control Topics
The user send flight control setpoints to the drone by publishing one of the following topics, which are subscribed by the dji_sdk node. All the fight control topics has message type sensor_msg/Joy. Among the flight control topics, the dji_sdk/flight_control_setpoint_generic is the most general one and requires the user to provide the control flag which dictates how the inputs are interpreted by the flight controller, while the rest are wrappers for the convenience of users and don't need the flag. All supported flags are listed in dji_sdk.h .- General setpoint where axes[0] to axes[3] stores set-point data for the 2 horizontal channels, the vertical channel, and the yaw channel, respectively. The meaning of the set-point data will be interpreted based on the control flag which is stored in axes[4].
- Command the X, Y position offset, Z position (height) and yaw angle in ENU ground frame.
- Command the X, Y, Z velocity in ENU ground frame and yaw rate.
- Command the roll pitch angle, height, and yaw rate.
2. Gimbal Control
The subscribers that takes the input for Gimbal arm controls.- Gimbal control command: Controls the Gimbal roll pitch and yaw angles (unit: 0.1 deg). mode: 0 - incremental control, the angle reference is the current Gimbal location. 1 - absolute control, the angle reference is related to configuration in DJI Go App.
- Gimbal speed command: Controls the Gimbal rate of change for roll pitch and yaw angles (unit: 0.1 deg/sec).
Published Topics
/dji_sdk/acceleration_ground_fused (geometry_msgs/Vector3Stamped)- Fused acceleration with respect to East-North-Up (ENU) ground frame, published at 100 Hz. This topic is unavailable on M100. Use imu topic for raw acceleration.
- Fused angular rate (p,q,r) around Forward-Left-Up (FLU) body frame, published at 100 Hz. This topic is unavailable on M100. Use imu topic for raw rate.
- Vehicle attitude represented as quaternion for the rotation from FLU body frame to ENU ground frame, published at 100 Hz.
- Report the current battery voltage at 10 Hz
- Display mode is the detailed status of the drone. All supported status are listed in dji_sdk.h. Published at 50 Hz. This topic is unavailable on M100.
- Simple status of the vehicle published at 50 Hz, detailed status are listed in dji_sdk.h. Note that status for M100 and A3/N3 are different.
- Data received from mobile device to the vehicle.
- Current gimbal joint angles, published at 50 Hz. If no gimbal present, default publishes all zeros.
- GPS signal health is between 0 and 5, 5 is the best condition. Use gps_position for control only if gps_health >= 3. Published at 50 Hz.
- Fused global position of the vehicle in latitude, longitude and altitude(m). Position in WGS 84 reference ellipsoid, published at 50 Hz. If no gps present, default publishes longitude and latitude equal zeros.
- IMU data including raw gyro reading in FLU body frame, raw accelerometer reading in FLU body frame, and attitude estimation, published at 100 Hz for M100, and 400 Hz for other platforms. Note that raw accelerometer reading will give a Z direction 9.8 m/s2 when the drone is put on a level ground statically.
- Reading of the 6 channels of the remote controller, published at 50 Hz.
sensor_msgs/Joy description (LB2, M100) description (SBUS) Range (LB2) Range (SBUS) Range (M100) axes[0] Roll Channel Channel A -1 to +1 -1 to +1 -1 to +1 axes[1] Pitch Channel Channel E -1 to +1 -1 to +1 -1 to +1 axes[2] Yaw Channel Channel R -1 to +1 -1 to +1 -1 to +1 axes[3] Throttle Channel Channel T -1 to +1 -1 to +1 -1 to +1 axes[4] Mode switch Channel U -10000, 0, 10000 -10000, 0, 10000 -8000, 0, 8000 axes[5] Landing gear (H) switch Channel Gear -5000, -10000 -10000, 10000 -4545, -10000 Known bug For SBUS controllers, the gear output depend on the channel mapping. Please refer to DJI Assistant 2 Remote controller settings.
- Velocity in ENU ground frame, published at 50 Hz. The velocity is valid only when gps_health >= 3.
- Height above takeoff location. It is only valid after drone is armed, when the flight controller has a reference altitude set.
- The time at which a hardware sync pulse is generated by the flight controller. This topic is unavailable on M100.
- Local position in Cartesian ENU frame, of which the origin is set by the user by calling the /dji_sdk/set_local_pos_ref service. Note that the local position is calculated from GPS position, so good GPS health is needed for the local position to be useful.
- RTK position published at 10hz Only available when RTK present
- Velocty measure by RTK published at 10hzOnly available when RTK present
- The azimuth measured by RTK published at 10hzOnly available when RTK present
- The type of RTK positioning, indicating different solutions for calculating the position published at 10hz. Only available when RTK present
- The type of RTK orientation, indicating different solutions for calculating the orientation published at 10hz. Only available when RTK present
- stereo image from the front-left camera of M210 in 240x320 resolution
- stereo image from the front-right camera of M210 in 240x320 resolution
- stereo image from the down-front camera of M210 in 240x320 resolution
- stereo image from the down-back camera of M210 in 240x320 resolution
- stereo disparity map from the front-facing camera of M210 in 240x320 resolution
- stereo image from the front-left camera of M210 in 640x480 resolution
- stereo image from the front-right camera of M210 in 640x480 resolution
- RGB image from the FPV camera of M210 in 608x448 resolution
- RGB image from the main camera of M210. Resolution can be set in DJI Go App
Services
/dji_sdk/activation (dji_sdk/Activation)- The service to activate the drone with app ID and key pair. The activation arguments should be specified in launch files.
- Usage:
Response bool result true--succeed false--invalid action
- Take photo or video via service, return true if successful.
- Usage:
Request Uint8 Camera_action 0--Shoot Photo 1--Start video taking 2--Stop video taking Response bool result true--succeed false--invalid action
- Enable or disable vehicle's arm motors.
- Usage:
Request uint8 arm 1--enable vehicle arm motor else: disable arm motor Response bool result true--succeed false--invalid action
- Execute takeoff, landing or go home.
- Usage:
Request uint8 task 4--takeoff 6--landing 1--gohome Response bool result true--succeed false--failed
- Config Multi-function IO. This service is unavailable on M100
- Usage:
Request uint8 mode 0--PWM_OUT 1--PWM_IN 2--GPIO_OUT 3--GPIO_IN 4--ADC uint8 channel 0-7 uint32 init_on_time_us uint16 pwm_freq
- Set MFIO value. This service is unavailable on M100
- Usage:
Request uint8 channel 0-7 uint32 init_on_time_us
- Service that start/stop/pause/resume the hotpoint mission.
- Usage:
Request uint8 action 0--start 1--stop 2--pause 3--resume Response bool result true--succeed false--failed
- Return the hotpoint tasks info. Use rosmsg show dji_sdk/MissionHotpointTask for more detail
- Usage:
Response MissionHotpointTask hotpoint_task
- Resets the Yaw position of the vehicle
- Usage:
Response bool result true--succeed false--failed
- Update the radius of the hot point mission
- Usage:
Request float32 radius Response bool result true--succeed false--failed
- Update the rate of change for Yaw and the direction of the change.
- Usage:
Request float32 yaw_rate uint8 direction Response bool result true--succeed false--failed
- Upload a set of hotpoint tasks to the vehicle. Use rosmsg show dji_sdk/MissionHotpointTask for more detail
- Usage:
Request MissionHotpointTask hotpoint_task Response bool result true--succeed false--failed
- Start/stop/pause/resume waypoint action.
- Usage:
Request uint8 action 0--start 1--stop 2--pause 3--resume Response bool result true--succeed false--failed
- Get the current waypoint tasks. Use rosmsg show dji_sdk/MissionWaypointTask for more detail
- Usage:
Response MissionWaypointTask waypoint_task
- Return the waypoint velocity
- Usage:
Response float32 speed
- Set the waypoint velocity.
- Usage:
Request float32 speed Response bool result true--succeed false--failed
- Upload a new waypoint task, return true if succeed. Use rosmsg show dji_sdk/MissionWaypointTask for more detail
- Usage:
Request MissionWaypointTask waypoint_task Response bool result true--succeed false--failed
- request/release the control authority
- Usage:
Request uint8 control_enable 1--request control 0--release control Response bool result true--succeed false--failed
- Send data to the mobile side. The length of the data is upper-limited to 100.
- Usage:
Request uint8[] data length(data) <= 100 Response bool result true--succeed false--failed
- Set Hard Sync. This service is unavailable on M100
- Usage:
Request uint32 frequency frequency in Hz uint16 tag the tag is to distinguish between different call Response bool result true--succeed false--failed
- Query drone firmware version. Available version list can be found in dji_sdk.h
- Set the origin of the local position to be the current GPS coordinate. Fail if GPS health is low (<=3).
- subscribe to stereo images from the front-facing and down-facing cameras of M210 in 240x320 resolution. If unsubscribe_240p is 1, service will unsubscribe no matter what. This service is only available on M210.
- Usage:
Request uint8 front_right_240p 1--subscribe 0--no behavior uint8 front_left_240p 1--subscribe 0--no behavior uint8 down_front_240p 1--subscribe 0--no behavior uint8 down_back_240p 1--subscribe 0--no behavior uint8 unsubscribe_240p 1--unsubscribe 0--no behavior Response bool result true--succeed false--failed
- subscribe to stereo disparity map from the front-facing camera of M210 in 240x320 resolution. If unsubscribe_240p is 1, service will unsubscribe no matter what. This service is only available on M210.
- Usage:
Request uint8 front_depth_240p 1--subscribe 0--no behavior uint8 unsubscribe_240p 1--unsubscribe 0--no behavior Response bool result true--succeed false--failed
- subscribe to stereo images from the front-facing camera of M210 in 640x480 resolution. If unsubscribe_vga is 1, service will unsubscribe no matter what. This service is only available on M210.
- Usage:
Request uint8 vga_freq 0--20Hz 1--10Hz uint8 front_vga 1--subscribe 0--no behavior uint8 unsubscribe_vga 1--unsubscribe 0--no behavior Response bool result true--succeed false--failed
- subscribe to FPV and/or main camera images. This service is only available on M210.
- Usage:
Request uint8 cameraType 0--FPV camera 1--main camera uint8 start 1--start 0--stop Response bool result true--succeed false--failed
Parameters
~/dji_sdk/app_id (int)- You must register as a developer with DJI and create an onboard SDK application ID and Key pair. Please go to https://developer.dji.com/register/ to complete registration.
- Baud rate should be set to match that is displayed in DJI Assistant 2 SDK settings. For M100, 230400 should be set on both DJI Assistant 2, and in launch file. For A3/N3, 921600 should be used.
- You must register as a developer with DJI and create an onboard SDK application ID and Key pair. Please go to https://developer.dji.com/register/ to complete registration.
- The serial port name that the USB is connected with. Candidates can be /dev/ttyUSBx, /dev/ttyTHSx, etc.
- Choose to use subscription (supported only on A3/N3) or broadcast method (supported by both M100 and A3/N3) for accessing telemetry data.
Details on flight control setpoint
All the above flight control topics take setpoint values of the X, Y, Z, and Yaw channels in axes[0]-axes[3]. In addition, the /dji_sdk/flight_control_setpoint_generic topic requires a control flag as axes[4] of the input. The control flag is an UInt8 variable that dictates how the inputs are interpreted by the flight controller. It is the bitwise OR of 5 separate flags defined as enums in dji_sdk.h, including Horizontal, Vertical, Yaw, Coordinate Frame, and the Breaking Mode.
Horizontal |
description |
reference |
limit |
0x00 |
Command roll and pitch angle |
Ground/Body |
0.611 rad (35 degree) |
0x40 |
Command horizontal velocities |
Ground/Body |
30 m/s |
0x80 |
Command position offsets |
Ground/Body |
N/A |
0xC0 |
Command angular rates |
Ground/Body |
5⁄6π rad/s |
Vertical |
description |
reference |
limit |
0x00 |
Command the vertical speed |
Ground |
-5 to 5 m/s |
0x10 |
Command altitude |
Ground |
0 to 120 m |
0x20 |
Command thrust |
Body |
0% to 100% |
Yaw |
description |
reference |
limit |
0x00 |
Command yaw angle |
Ground |
-π to π |
0x08 |
Command yaw rate |
Ground |
5⁄6π rad/s |
Coordinate |
description |
0x00 |
Horizontal command is ground_ENU frame |
0x02 |
Horizontal command is body_FLU frame |
Active Break |
description |
0x00 |
No active break |
0x01 |
Actively break to hold position after stop sending setpoint |