A tiny, ROS2‑friendly C++ library to talk to the DJI Tello over the official SDK 3.0 (UDP), with a minimal test app, telemetry parsing, logging, and optional OpenCV video viewer.
- Minimal C++17 library (
tello_lib) exposing a single class:tello::interface - Command/Telemetry sockets (UDP 8889/8890) + optional video (UDP 11111)
- Telemetry parser (SDK 3.0 format), thread‑safe queue, timestamping
- Logging to
Log/telemetry.txt(auto‑creates folder) - OpenCV video viewer that’s decoupled from Tello’s stream (
streamon/streamoff) - RC (joystick‑style) control and all key movement/rotation commands
- ROS2‑friendly design: non‑blocking telemetry
pop,get_last_frame()copy, public queue guarded by mutex - Clean CMake build with
build/andinstall/layouts
⚠️ Fly responsibly. Always test with props removed or in a safe space. Mind the battery and local regulations.
.
├─ CMakeLists.txt
├─ include/
│ ├─ telloComunication.hpp
│ └─ telloInterface.hpp
├─ src/
│ ├─ telloComunication.cpp
│ ├─ telloInterface.cpp
│ └─ fastTest.cpp # example app
├─ build/ # out-of-source build (generated)
├─ install/ # staged install: bin/, lib/, include/ (generated)
└─ Log/ # runtime logs (auto-created next to working dir)
- C++17 toolchain (gcc/clang/MSVC)
- OpenCV 4 built with FFmpeg (for
cv::VideoCaptureover UDP) - POSIX sockets /
pthread(on Linux; Windows not tested)
OpenCV on Linux can be found via pkg-config opencv4 or find_package(OpenCV REQUIRED).
# from repo root
mkdir -p build && cd build
cmake .. -DCMAKE_BUILD_TYPE=Release
make -j$(nproc)
# optional: stage install into ./install (bin/, lib/, include/)
make installThe
CMakeLists.txtis configured to install into./installby default (override with-DCMAKE_INSTALL_PREFIX=).
- Executable:
./install/bin/tello_test - Library:
./install/lib/libtello_lib.a - Headers:
./install/include/
You can link this library from other projects by adding -I<path>/install/include and -L<path>/install/lib -ltello_lib plus OpenCV and pthread.
Connect PC to Tello Wi‑Fi (
192.168.10.x). Then run the sample program.
#include "telloComunication.hpp"
#include "telloInterface.hpp"
#include <thread>
#include <iostream>
int main(){
tello::interface ifc;
if (ifc.begin(/*video_stream=*/false) != 0) return 1;
if (ifc.connect() != 0) return 1; // send "command"
// Arm SDK and takeoff
ifc.setAck(false);
ifc.takeoff();
ifc.waitAck();
std::this_thread::sleep_for(std::chrono::seconds(8));
// Move using distance commands (meters)
ifc.forward(0.8f); ifc.waitAck();
ifc.left(0.5f); ifc.waitAck();
ifc.turn_cw(90); ifc.waitAck();
// Land
ifc.setAck(false);
ifc.land();
ifc.waitAck();
std::this_thread::sleep_for(std::chrono::seconds(2));
ifc.close();
return 0;
}Compile/link flags if building manually:
g++ fastTest.cpp telloComunication.cpp telloInterface.cpp \
-I../include $(pkg-config --cflags --libs opencv4) -pthread \
-o tello_testint begin(bool video_stream=false): open UDP sockets (cmd/tlm)int connect(): sendcommand; start ACK and telemetry threadsvoid close(): stop threads, close sockets; (optionally stop video viewer)
-
int takeoff(),int land(),int stop() -
int forward(float m),back(float m),left(float m),right(float m),up(float m),down(float m)- meters clamped to
[0.2 .. 5.0]and sent as centimeters per SDK
- meters clamped to
-
int turn_cw(int deg),turn_ccw(int deg)withdeg ∈ [1..360] -
int move(int a, int b, int h_vel, int c)- direct RC control
[-100..100]for roll/pitch/throttle/yaw (rc a b c dsemantics)
- direct RC control
int cmd_raw(const std::string& cmd): send any SDK string (e.g.,"battery?")
-
Parser consumes strings like:
mid:-1;x:-100;y:-100;z:-100;mpry:0,0,0;pitch:0;roll:0;...;agz:-1002.00;and fills aTelemetrystruct (attitude, vels, temp, tof, height, batt, baro, acc, timestamp) -
bool parseTelemetry(const std::string&)— internal -
bool get_last_frame(cv::Mat& out)— deep copy of latest video frame -
Telemetry popTelemetry()— pops one packet from queue (returns default if empty) -
Public members for ROS2 bridge:
std::queue<Telemetry> queue_tlm_;std::mutex mtx_tlm_;
void waitAck(): busy‑wait onflagAckset byack_loop()when a response comes back (e.g.,ok\norerror message\n).
int video_on() / video_off()— only send SDKstreamon/streamoff(do not manage threads)void video_loop()— viewer loop: triesudp://0.0.0.0:11111via FFmpeg; showsTello Videowindow; updateslast_frame_under mutexint switchCamera()— toggledownvision 1/0(requires stream active)
void log()— appends telemetry toLog/telemetry.txtin the current working directory (folder auto‑created)
-
Threads:
receiver_loop(telemetry),ack_loop(ACK), optionalvideo_loop(viewer) -
Flags:
telemetry_run_flag,command_run_flag,view_run_(for viewer),flagAck -
Synchronization:
- Telemetry queue guarded by
mtx_tlm_ - Video
last_frame_guarded bymtx_frame_
- Telemetry queue guarded by
- Stop viewer with
stop_video_view()(or ESC/qin window) - Then call
close()to stop telemetry/ack threads and close sockets - If you also want to stop the drone’s stream: call
video_off()separately
- Parser ignores
mid/x/y/z/mpryand reads frompitchonward - Expected fields parsed: 16
- Negative values are supported (e.g., yaw
< 0, accelerations) - Timestamp:
std::chrono::steady_clock::now()
Troubleshooting:
- If you see
[parse] fields=<number>less than 16, print the raw line to check the format
- The viewer uses:
cv::VideoCapture("udp://0.0.0.0:11111", cv::CAP_FFMPEG) - Requires OpenCV built with FFmpeg; otherwise
cap.isOpened()will fail - If you get
bind failed: Address already in use, stop any other process grabbing11111(e.g., another viewer)
Use get_last_frame() to fetch a deep copy for ROS2 publishing.
// Slide left for ~1s using RC
for (int i=0; i<20; ++i) {
ifc.move(0, -30, 0, 0);
ifc.waitAck();
std::this_thread::sleep_for(std::chrono::milliseconds(50));
}SDK expects integers
[-100..100].
[ACK]: error Not joystick: you likely sent a distance command with a float string (e.g.,"up 0.5"). Use meters API; the lib converts to integer cm (e.g.,up(0.5f)→up 50).- No log file: parser must succeed; if not,
log()is never called. Print the raw telemetry line to verify.
-
Create a node that:
- Calls
popTelemetry()in a timer to publish asensor_msgs/ custom msg - Calls
get_last_frame()and convertscv::Mat→sensor_msgs::msg::Image
- Calls
-
Keep the library single‑responsibility: ROS2 logic stays out of
tello_lib
- Fly in a safe, open area. Keep hands/face clear.
- Respect local laws. Don’t fly near people or restricted zones.
- Watch battery (Tello can emergency land when low).
MIT
- ROS2 package wrapping this lib with publishers/services/actions
This project stands on the shoulders of: DJI Tello SDK 3.0, OpenCV + FFmpeg, and the broader open‑source community.