Only released in EOL distros:  

Package Summary

A ROS package using DJI Onboard SDK.

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 SDK

Subscribed 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 .
/dji_sdk/flight_control_setpoint_generic (sensor_msgs/Joy)
  • 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].
/dji_sdk/flight_control_setpoint_ENUposition_yaw (sensor_msgs/Joy)
  • Command the X, Y position offset, Z position (height) and yaw angle in ENU ground frame.
/dji_sdk/flight_control_setpoint_ENUvelocity_yawrate (sensor_msgs/Joy)
  • Command the X, Y, Z velocity in ENU ground frame and yaw rate.
/dji_sdk/flight_control_setpoint_rollpitch_yawrate_zposition (sensor_msgs/Joy)
  • Command the roll pitch angle, height, and yaw rate.
2. Gimbal Control
The subscribers that takes the input for Gimbal arm controls.
/dji_sdk/gimbal_angle_cmd (dji_sdk/Gimbal)
  • 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.
/dji_sdk/gimbal_speed_cmd (geometry_msgs/Vector3Stamped)
  • 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.
/dji_sdk/angular_velocity_fused (geometry_msgs/Vector3Stamped)
  • 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.
/dji_sdk/attitude (geometry_msgs/QuaternionStamped)
  • Vehicle attitude represented as quaternion for the rotation from FLU body frame to ENU ground frame, published at 100 Hz.
/dji_sdk/battery_state (sensor_msgs/BatteryState)
  • Report the current battery voltage at 10 Hz
/dji_sdk/display_mode (std_msgs/UInt8)
  • 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.
/dji_sdk/flight_status (std_msgs/UInt8)
  • 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.
/dji_sdk/from_mobile_data (std_msgs/UInt8[])
  • Data received from mobile device to the vehicle.
/dji_sdk/gimbal_angle (geometry_msgs/Vector3Stamped)
  • Current gimbal joint angles, published at 50 Hz. If no gimbal present, default publishes all zeros.
/dji_sdk/gps_health (std_msgs/UInt8)
  • 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.
/dji_sdk/gps_position (sensor_msgs/NavSatFix)
  • 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.
/dji_sdk/imu (sensor_msgs/Imu)
  • 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.
/dji_sdk/rc (sensor_msgs/Joy)
  • 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.
/dji_sdk/velocity (geometry_msgs/Vector3Stamped)
  • Velocity in ENU ground frame, published at 50 Hz. The velocity is valid only when gps_health >= 3.
/dji_sdk/height_above_takeoff (std_msgs/Float32)
  • Height above takeoff location. It is only valid after drone is armed, when the flight controller has a reference altitude set.
/dji_sdk/trigger_time (sensor_msgs/TimeReference)
  • The time at which a hardware sync pulse is generated by the flight controller. This topic is unavailable on M100.
/dji_sdk/local_position (geometry_msgs/PointStamped)
  • 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.
/dji_sdk/rtk_position (sensor_msgs/NavSatFix)
  • RTK position published at 10hz Only available when RTK present
/dji_sdk/rtk_velocity (geometry_msgs/Vector3)
  • Velocty measure by RTK published at 10hzOnly available when RTK present
/dji_sdk/rtk_yaw (std_msgs/Int16)
  • The azimuth measured by RTK published at 10hzOnly available when RTK present
/dji_sdk/rtk_info_position (std_msgs/UInt8)
  • The type of RTK positioning, indicating different solutions for calculating the position published at 10hz. Only available when RTK present
/dji_sdk/rtk_info_yaw (std_msgs/UInt8)
  • The type of RTK orientation, indicating different solutions for calculating the orientation published at 10hz. Only available when RTK present
/dji_sdk/stereo_240p_front_left_images (sensor_msgs/Image)
  • stereo image from the front-left camera of M210 in 240x320 resolution
/dji_sdk/stereo_240p_front_right_images (sensor_msgs/Image)
  • stereo image from the front-right camera of M210 in 240x320 resolution
/dji_sdk/stereo_240p_down_front_images (sensor_msgs/Image)
  • stereo image from the down-front camera of M210 in 240x320 resolution
/dji_sdk/stereo_240p_down_back_images (sensor_msgs/Image)
  • stereo image from the down-back camera of M210 in 240x320 resolution
/dji_sdk/stereo_240p_front_depth_images (sensor_msgs/Image)
  • stereo disparity map from the front-facing camera of M210 in 240x320 resolution
/dji_sdk/stereo_vga_front_left_images (sensor_msgs/Image)
  • stereo image from the front-left camera of M210 in 640x480 resolution
/dji_sdk/stereo_vga_front_right_images (sensor_msgs/Image)
  • stereo image from the front-right camera of M210 in 640x480 resolution
/dji_sdk/fpv_camera_images (sensor_msgs/Image)
  • RGB image from the FPV camera of M210 in 608x448 resolution
/dji_sdk/main_camera_images (sensor_msgs/Image)
  • 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
/dji_sdk/camera_action (dji_sdk/CameraAction)
  • 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
/dji_sdk/drone_arm_control (dji_sdk/DroneArmControl)
  • 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
/dji_sdk/drone_task_control (dji_sdk/DroneTaskControl)
  • Execute takeoff, landing or go home.
  • Usage:
    • Request
      uint8 task 4--takeoff 6--landing 1--gohome
      Response
      bool result true--succeed false--failed
/dji_sdk/mfio_config (dji_sdk/MFIOConfig)
  • 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
/dji_sdk/mfio_set_value (dji_sdk/MFIOSetValue)
  • Set MFIO value. This service is unavailable on M100
  • Usage:
    • Request
      uint8 channel 0-7
      uint32 init_on_time_us
/dji_sdk/mission_hotpoint_action (dji_sdk/MissionHpAction)
  • 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
/dji_sdk/mission_hotpoint_getInfo (dji_sdk/MissionHpGetInfo)
  • Return the hotpoint tasks info. Use rosmsg show dji_sdk/MissionHotpointTask for more detail
/dji_sdk/mission_hotpoint_resetYaw (dji_sdk/MissionHpResetYaw)
  • Resets the Yaw position of the vehicle
  • Usage:
    • Response
      bool result true--succeed false--failed
/dji_sdk/mission_hotpoint_updateRadius (dji_sdk/MissionHpUpdateRadius)
  • Update the radius of the hot point mission
  • Usage:
    • Request
      float32 radius
      Response
      bool result true--succeed false--failed
/dji_sdk/mission_hotpoint_updateYawRate (dji_sdk/MissionHpUpdateYawRate)
  • 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
/dji_sdk/mission_hotpoint_upload (dji_sdk/MissionHpUpload)
  • Upload a set of hotpoint tasks to the vehicle. Use rosmsg show dji_sdk/MissionHotpointTask for more detail
  • Usage:
/dji_sdk/mission_waypoint_action (dji_sdk/MissionWpAction)
  • 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
/dji_sdk/mission_waypoint_getInfo (dji_sdk/MissionWpGetInfo)
  • Get the current waypoint tasks. Use rosmsg show dji_sdk/MissionWaypointTask for more detail
/dji_sdk/mission_waypoint_getSpeed (dji_sdk/MissionWpGetSpeed)
  • Return the waypoint velocity
  • Usage:
    • Response
      float32 speed
/dji_sdk/mission_waypoint_setSpeed (dji_sdk/MissionWpSetSpeed)
  • Set the waypoint velocity.
  • Usage:
    • Request
      float32 speed
      Response
      bool result true--succeed false--failed
/dji_sdk/mission_waypoint_upload (dji_sdk/MissionWpUpload)
  • Upload a new waypoint task, return true if succeed. Use rosmsg show dji_sdk/MissionWaypointTask for more detail
  • Usage:
/dji_sdk/sdk_control_authority (dji_sdk/SDKControlAuthority)
  • request/release the control authority
  • Usage:
    • Request
      uint8 control_enable 1--request control 0--release control
      Response
      bool result true--succeed false--failed
/dji_sdk/send_data_to_mobile (dji_sdk/SendMobileData)
  • 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
/dji_sdk/set_hardsyc (dji_sdk/SetHardSync)
  • 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
/dji_sdk/query_drone_version (dji_sdk/QueryDroneVersion)
  • Query drone firmware version. Available version list can be found in dji_sdk.h
/dji_sdk/set_local_pos_ref (dji_sdk/SetLocalPosRef)
  • Set the origin of the local position to be the current GPS coordinate. Fail if GPS health is low (<=3).
/dji_sdk/stereo_240p_subscription (dji_sdk/Stereo240pSubscription)
  • 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
/dji_sdk/stereo_depth_subscription (dji_sdk/StereoDepthSubscription)
  • 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
/dji_sdk/stereo_vga_subscription (dji_sdk/StereoVGASubscription)
  • 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
/dji_sdk/setup_camera_stream (dji_sdk/SetupCameraStream)
  • 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) ~/dji_sdk/baud_rate (int, default: 921600)
  • 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.
~/dji_sdk/enc_key (string, default: Enter your enc key here) ~/dji_sdk/serial_name (string, default: /dev/ttyUSB0)
  • The serial port name that the USB is connected with. Candidates can be /dev/ttyUSBx, /dev/ttyTHSx, etc.
~/dji_sdk/use_broadcast (, default: false)
  • 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

Wiki: dji_sdk (last edited 2017-12-20 22:42:05 by Zhiyuan Li)