tentone / tello-ros2

ROS2 node for DJI Tello and Visual SLAM for mapping of indoor environments.
MIT License
136 stars 42 forks source link
dji-tello dji-tello-edu drone ros-foxy ros2 slam

DJI Tello ROS2

Topic Type Description Frequency
/image_raw sensor_msgs/Image Image of the Tello camera 30hz
/camera_info sensor_msgs/CameraInfo Camera information (size, calibration, etc) 2hz
/status tello_msg/TelloStatus Status of the drone (wifi strength, batery, temperature, etc) 2hz
/id tello_msg/TelloID Identification of the drone w/ serial number and firmware 2hz
/imu sensor_msgs/Imu Imu data capture from the drone 10hz
/battery sensor_msgs/BatteryState Battery status 2hz
/temperature sensor_msgs/Temperature Temperature of the drone 2hz
/odom nav_msgs/Odometry Odometry (only orientation and speed) 10hz
/tf geometry_msgs/TransformStamped Transform from base to drone tf, prefer a external publisher. 10hz
Topic Type Description
\emergency std_msgs/Empty When received the drone instantly shuts its motors off (even when flying), used for safety purposes
\takeoff std_msgs/Empty Drone takeoff message, make sure that the drone has space to takeoff safely before usage.
\land std_msgs/Empty Land the drone.
\control geometry_msgs/Twist Control the drone analogically. Linear values should range from -100 to 100, speed can be set in x, y, z for movement in 3D space. Angular rotation is performed in the z coordinate. Coordinates are relative to the drone position (x always relative to the direction of the drone)
\flip std_msgs/String Do a flip with the drone in a direction specified. Possible directions can be "r" for right, "l" for left, "f" for forward or "b" for backward.
\wifi_config tello_msg/TelloWifiConfig Configure the wifi credential that should be used by the drone. The drone will be restarted after the credentials are changed.
Name Type Description Default
connect_timeout float Time (seconds) until the node is killed if connection to the drone is not available. 10.0
tello_ip string IP of the tello drone. When using multiple drones multiple nodes with different IP can be launched. '192.168.10.1'
tf_base string Base tf to be used when publishing data 'map'
tf_drone string Name of the drone tf to use when publishing data 'drone'
tf_pub boolean If true a static TF from tf_base to tf_drone is published False
camera_info_file string Path to a YAML camera calibration file (obtained with the calibration tool) ''

Camera Calibration

ros2 run camera_calibration cameracalibrator --size 7x9 --square 0.16 image:=/image_raw camera:=/camera_info

Launch File

Node(
    package='tello',
    executable='tello',
    namespace='/',
    name='tello',
    parameters=[
        {'tello_ip': '192.168.10.1'}
    ],
    remappings=[
        ('/image_raw', 'camera')
    ],
    respawn=True
)

Overheating Problems

Install

Visual SLAM

ros2 run ros2_orbslam mono <VOCABULARY FILE> <CONFIG_FILE>

Setup ROS 2 Foxy

Workspace
Packages
# CPP Package
ros2 pkg create --build-type ament_cmake --node-name <node_name> <package_name>

# Python Package
ros2 pkg create --build-type ament_python --node-name <node_name> <package_name>
Tools
Bags
# Record a bag containing data from some topics into a file
ros2 bag record -o <bag_file_name> /turtle1/cmd_vel /turtle1/pose ...

# Check the content of a bag run the command
ros2 bag info <bag_file_name>

# Replay the content of some topics recorded into a bag file
 ros2 bag play <bag_file_name>
ros2 bag play -s rosbag_v2 <path_to_bagfile>
Camera calibration

Ubuntu Based Linux Distros

Windows Subsystem for Linux (WSL)

# Install WSL 2
Enable-WindowsOptionalFeature -Online -FeatureName Microsoft-Windows-Subsystem-Linux

# Enable WSL 2
dism.exe /online /enable-feature /featurename:VirtualMachinePlatform /all /norestart

# Check WSL version
wsl.exe --set-default-version 2
wsl -l -v
"C:\Program Files\VcXsrv\vcxsrv.exe" :0 -ac -terminate -lesspointer -multiwindow -clipboard -wgl -dpi auto
export DISPLAY="`grep nameserver /etc/resolv.conf | sed 's/nameserver //'`:0"
export LIBGL_ALWAYS_INDIRECT=0
sudo apt install ntpdate
sudo ntpdate time.windows.com