Giter Club home page Giter Club logo

tello-ros2's Introduction

DJI Tello ROS2

  • DJI Tello driver for ROS 2 based on DJITelloPy that uses the official SDK for the drone.
  • Can be used to control multiple drones both using the swarm functionality (only for Tello EDU) or using multiple WLAN with regular Tello drones.
  • This project was developed as a way of learning ROS 2 and evaluate the viability of moving other in progress projects from ROS 1 to ROS 2.
  • Ii is recommended to update the Tello firmware to the latest version available
  • Project workspace is divided into sub-workspaces that contain different logic.
    • tello package is the main package, includes access to the drone information, camera image and control.
    • tello_msg package defines custom messages to access specific Tello data.
      • Defines the TelloStatus, TelloID and TelloWifiConfig messages
    • tello_control package is a sample control package that displays the drone image and provides keyboard control.
      • T used for takeoff, L to land the drone, F to flip forward, E for emergency stop, WASD and arrows to control the drone movement.

  • Bellow is the list of topics published and consumed by the tello package
  • The list of published topics alongside their description and frequency. These topics are only published when some node subscribed to them, otherwise they are not processed.
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
  • The list of topics subscribed by the node, these topics can be renamed in the launch file.
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.
  • The list of parameters used to configure the node. These should be defined on a launch file.
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

  • To allow the drone to be used for 3D vision tasks, as for example monocular SLAM the camera should be first calibrated.
  • A sample calibration file is provided with parameters captures from the drone used for testing but it is recommended to perform individual calibrations for each drone used.
  • Calibration can be achieved using the camera_calibration package. Calibration pattern can be generated using the calib.io pattern generator tool.
ros2 run camera_calibration cameracalibrator --size 7x9 --square 0.16 image:=/image_raw camera:=/camera_info
  • Take as many frame as possible and measure your check board grid size to ensure good accuracy in the process. When the process ends a calibrationdata.tar.gz will be created in the /tmp path.

Launch File

  • Launch files in ROS2 are now defined using python code. To launch the main node of the project add the following code to your launch.py file.
Node(
    package='tello',
    executable='tello',
    namespace='/',
    name='tello',
    parameters=[
        {'tello_ip': '192.168.10.1'}
    ],
    remappings=[
        ('/image_raw', 'camera')
    ],
    respawn=True
)

Overheating Problems

  • The motor drivers in the DJI Tello overheat after a while when the drone is not flying. To cool down the drivers i have removed the plastic section on top of the heat spreader (as seen in the picture).
  • If you are comfortable with leaving the PCB exposed removing the plastic cover should result in even better thermals.
  • If possible place the drone on top of an old computer fan or use a laptop cooler to prevent the drone from shutting down due to overheating.

Install

  • To install the driver download the code from git, install dependencies using the script/install.sh script.
  • After all dependencies are installed build the code and and install using colcon as usual or use the script/build.sh and script/run.sh to test the code.

Visual SLAM

  • The drone is equipped with a IMU and a camera that can be used for visual SLAM in order to obtain the location of the drone and a map of the environment.
  • ORB SLAM 2 is a monocular visual based algorithm for SLAM that can be easily integrated with the Tello drone using this package.
  • The wrapper provided alongside with this repository is based on the alsora/ros2-ORB-SLAM2 project using the alsora/ORB_SLAM2 modified version of ORB Slam that does not depend on pangolin.
  • To run the monocular SLAM node after installing all dependencies and building the package run.
ros2 run ros2_orbslam mono <VOCABULARY FILE> <CONFIG_FILE>
  • The vocabulary file can be obtained from the ORB_SLAM2 repository ( ORB_SLAM2/Vocabulary/ORBvoc.txt).
  • Sample configuration files can be found inside the package at orbslam2/src/monocular/config.yaml for monocular SLAM.

Setup ROS 2 Foxy

  • Run the install script to setup the ROS 2 (Foxy Fitzroy) environment.
  • Check the ROS2 Tutorials page to learn how to setup workspace and create packages.
Workspace
  • To install dependencies of the packages available in a workspace directory src run rosdep install -i --from-path src --rosdistro foxy -y

  • To build workspace you can use the command colcon build, some useful arguments for colcon build:

    • --packages-up-to builds the package you want, plus all its dependencies, but not the whole workspace (saves time)
    • --symlink-install saves you from having to rebuild every time you tweak python scripts
    • --event-handlers console_direct+ shows console output while building (can otherwise be found in the log directory)
Packages
  • To create a new ROS2 package (C++ or Python) for development move to the src package and run
# 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
  • rqt_topic Used to monitor topics and their values in a list
  • rqt_graph Draw the graph of connection between the currently active nodes and explore communication between them
  • rviz Visualize topics in 3D space.
Bags
  • Bags can be used to record data from topics that can be later replayed for off-line testing. Bags can be manipulated using the ros2 bag command. To
# 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>
  • To play ROS 1 bags in ROS 2 you will need to first install ROS 1, and the ROS bag adapter plugin. The the bags can be run using the command.
ros2 bag play -s rosbag_v2 <path_to_bagfile>
Camera calibration

Ubuntu Based Linux Distros

  • When installing on ubuntu based distros it might be required to change the distro codename so that the lsb_release -cs command returns the correct ubuntu base distribution.
  • To change the output of the lsb_release command edit the /etc/os-release file. For ubuntu 20.04 the codename should be focal.
  • Edit the file to contain the value UBUNTU_CODENAME=focal.

Windows Subsystem for Linux (WSL)

  • Install WSL2 from the windows store or using the commands bellow, install Ubuntu 20.04 as the SO over the WSL overlay.
# 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
  • Install a VcXsrv Windows X Server to be used as a X11 display server required to run GUI applications.
    • "Native opengl" unchecked
    • "Disable access control" checked
  • Create a shortcut for VcXSrv with the following parameters
"C:\Program Files\VcXsrv\vcxsrv.exe" :0 -ac -terminate -lesspointer -multiwindow -clipboard -wgl -dpi auto
  • To enable the access to the installed server add the display address to the .bashrc file
export DISPLAY="`grep nameserver /etc/resolv.conf | sed 's/nameserver //'`:0"
export LIBGL_ALWAYS_INDIRECT=0
  • If you are using Visual Studio Code as and IDE you can configure for remote WSL development, allowing to debug code and interact with the WSL terminal.

  • If you require CUDA acceleration you can also install NVidia CUDA drivers for WSL2

  • If you get Clock skew detected. Your build may be incomplete. while compiling the code run the following commands or install the wsl-clock tool to automatically fix the clock drift problems.

sudo apt install ntpdate
sudo ntpdate time.windows.com

tello-ros2's People

Contributors

tentone avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar

tello-ros2's Issues

Images sent are encoded to bgr8 but are actually rgb8

The image messages sent claim the images are bgr8 but in my testing it seems they are actually rgb8. The line where the message is sent is here. To test this you could add

cv2.imshow(frame)
cv2.waitKey(1)

before sending the message and you will see that the blue and red channels appear flipped in the display. cv2 expects a BGR image so this means the images sent over UDP are actually RGB. To fix this either add

frame = cv2.cvtColor(frame, cv2.COLOR_RGB2BGR)

before converting the image to an image message or change the encoding on this line to "rgb8".

ModuleNotFoundError: No module named 'ament_package'

Hello,
I'm trying to install this repo but when I run the build.sh script, I keep getting this error:

ERROR: the following packages/stacks could not have their rosdep keys resolved
to system dependencies:
tello: Cannot locate rosdep definition for [rosidl_default_runtime]
tello_control: Cannot locate rosdep definition for [ament_lint_common]
tello_msg: Cannot locate rosdep definition for [ament_lint_common]
Starting >>> tello_msg
Starting >>> tello_control
--- stderr: tello_msg                                                                  
Traceback (most recent call last):
  File "/opt/ros/foxy/share/ament_cmake_core/cmake//package_templates/templates_2_cmake.py", line 20, in <module>
    from ament_package.templates import get_environment_hook_template_path
ModuleNotFoundError: No module named 'ament_package'
CMake Error at /opt/ros/foxy/share/ament_cmake_core/cmake/ament_cmake_package_templates-extras.cmake:41 (message):
  execute_process(/usr/bin/python3
  /opt/ros/foxy/share/ament_cmake_core/cmake//package_templates/templates_2_cmake.py
  /home/huangpan1/tello_1410/tello-ros2/workspace/build/tello_msg/ament_cmake_package_templates/templates.cmake)
  returned error code 1
Call Stack (most recent call first):
  /opt/ros/foxy/share/ament_cmake_core/cmake/ament_cmake_coreConfig.cmake:41 (include)
  /opt/ros/foxy/share/ament_cmake/cmake/ament_cmake_export_dependencies-extras.cmake:15 (find_package)
  /opt/ros/foxy/share/ament_cmake/cmake/ament_cmakeConfig.cmake:41 (include)
  CMakeLists.txt:18 (find_package)


---
Failed   <<< tello_msg [0.82s, exited with code 1]
Aborted  <<< tello_control [0.81s]

Summary: 0 packages finished [0.96s]
  1 package failed: tello_msg
  1 package aborted: tello_control
  2 packages had stderr output: tello_control tello_msg
  1 package not processed

I found similar questions somewhere else, all of them suggest to source the setup file to set the environment, which I did already(source /opt/ros/foxy/setup.bash), but I can't get rid of the error.

Also what is weird is, if I open python (/usr/bin/python3) and I execute the instruction, it works perfectly fine:

from ament_package.templates import get_environment_hook_template_path

The instruction runs without error.

Any hint on how I can solve the issue? I'm really stuck and no clue on how to solve it. Thanks!

Runtime error with cv_bridge_boost

Hello,

I am trying to use your ROS2 Tello node on Foxy, Ubuntu 20.04 but I always get an error about cv_bridge_boost. The Tello node crashes at startup.

Please find the trace:

[INFO] [launch]: All log files can be found below /home/camille/.ros/log/2022-04-12-16-00-37-900309-PC-Drone-Swarming-39164
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [tello-1]: process started with pid [39166]
[INFO] [tello_control-2]: process started with pid [39168]
[INFO] [static_transform_publisher-3]: process started with pid [39170]
[static_transform_publisher-3] [INFO] [1649772037.967412362] [tf]: Spinning until killed publishing transform from 'map' to 'drone'
[tello-1] RuntimeError: FATAL: module compiled as little endian, but detected different endianness at runtime
[tello-1] Traceback (most recent call last):
[tello-1]   File "/home/camille/Documents/ros2_swarm/tello-ros2/workspace/install/tello/lib/tello/tello", line 11, in <module>
[tello-1]     load_entry_point('tello', 'console_scripts', 'tello')()
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 490, in load_entry_point
[tello-1]     return get_distribution(dist).load_entry_point(group, name)
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 2854, in load_entry_point
[tello-1]     return ep.load()
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 2445, in load
[tello-1]     return self.resolve()
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 2451, in resolve
[tello-1]     module = __import__(self.module_name, fromlist=['__name__'], level=0)
[tello-1]   File "/home/camille/Documents/ros2_swarm/tello-ros2/workspace/build/tello/tello/node.py", line 23, in <module>
[tello-1]     from cv_bridge import CvBridge
[tello-1]   File "/usr/lib/python3/dist-packages/cv_bridge/__init__.py", line 6, in <module>
[tello-1]     from cv_bridge.boost.cv_bridge_boost import cvtColorForDisplay, getCvType
[tello-1] SystemError: initialization of cv_bridge_boost raised unreported exception
[ERROR] [tello-1]: process has died [pid 39166, exit code 1, cmd '/home/camille/Documents/ros2_swarm/tello-ros2/workspace/install/tello/lib/tello/tello --ros-args -r __node:=tello -r __ns:=/ --params-file /tmp/launch_params_s36z8217 --params-file /tmp/launch_params_6yadarlc --params-file /tmp/launch_params_bdzwut2j --params-file /tmp/launch_params_y_elw_8y -r /image_raw:=/camera'].
[INFO] [tello-1]: process started with pid [39207]
[tello-1] RuntimeError: FATAL: module compiled as little endian, but detected different endianness at runtime
[tello-1] Traceback (most recent call last):
[tello-1]   File "/home/camille/Documents/ros2_swarm/tello-ros2/workspace/install/tello/lib/tello/tello", line 11, in <module>
[tello-1]     load_entry_point('tello', 'console_scripts', 'tello')()
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 490, in load_entry_point
[tello-1]     return get_distribution(dist).load_entry_point(group, name)
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 2854, in load_entry_point
[tello-1]     return ep.load()
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 2445, in load
[tello-1]     return self.resolve()
[tello-1]   File "/usr/lib/python3/dist-packages/pkg_resources/__init__.py", line 2451, in resolve
[tello-1]     module = __import__(self.module_name, fromlist=['__name__'], level=0)
[tello-1]   File "/home/camille/Documents/ros2_swarm/tello-ros2/workspace/build/tello/tello/node.py", line 23, in <module>
[tello-1]     from cv_bridge import CvBridge
[tello-1]   File "/usr/lib/python3/dist-packages/cv_bridge/__init__.py", line 6, in <module>
[tello-1]     from cv_bridge.boost.cv_bridge_boost import cvtColorForDisplay, getCvType
[tello-1] SystemError: initialization of cv_bridge_boost raised unreported exception
[ERROR] [tello-1]: process has died [pid 39207, exit code 1, cmd '/home/camille/Documents/ros2_swarm/tello-ros2/workspace/install/tello/lib/tello/tello --ros-args -r __node:=tello -r __ns:=/ --params-file /tmp/launch_params_s36z8217 --params-file /tmp/launch_params_6yadarlc --params-file /tmp/launch_params_bdzwut2j --params-file /tmp/launch_params_y_elw_8y -r /image_raw:=/camera'].

I don't understand this line as I used packages from the Ubuntu OS :
RuntimeError: FATAL: module compiled as little endian, but detected different endianness at runtime

Do you have an idea how to solve it?

Thanks a lot.

ros2 topic echo /camera_info fails

hi! thanks a lot of tello-ros2!

im trying to get camera_info in second terminal with: ros2 topic echo /camera_info` but receive nothing.
in main terminal i see:

Traceback (most recent call last):
[tello-1]   File "/usr/lib/python3.8/threading.py", line 932, in _bootstrap_inner
[tello-1]     self.run()
[tello-1]   File "/usr/lib/python3.8/threading.py", line 870, in run
[tello-1]     self._target(*self._args, **self._kwargs)
[tello-1]   File "/home/ubuntu/ros2_ws/install/tello/lib/python3.8/site-packages/tello/node.py", line 238, in status_loop
[tello-1]     msg.height = self.camera_info.image_height
[tello-1] AttributeError: 'dict' object has no attribute 'image_height'

i made may own calibration and put it there:

# Declare parameters
        self.node.declare_parameter('connect_timeout', 10.0)
        self.node.declare_parameter('tello_ip', '192.168.10.1')
        self.node.declare_parameter('tf_base', 'map')
        self.node.declare_parameter('tf_drone', 'drone')
        self.node.declare_parameter('tf_pub', False)
        self.node.declare_parameter('camera_info_file', '/home/ubuntu/ros2_ws/src/tello/tello/ost.yaml')

may be API has changed ?
and do you know how to decrease camera shape as 960x720 hangs on my raspberry pi ?

Cannot build SLAM node

I have followed the steps religiously, and can build the tello nodes, and can build ORB_SLAM.

When I attempt to build the SLAM node however I get the following errors:

`/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp: In member function ‘void MonocularSlamNode::UpdateSLAMState()’:

/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:183:45: error: ‘class ORB_SLAM2::System’ has no member named ‘GetCurrentFrame’
183 | ORB_SLAM2::Frame currentFrame = m_SLAM->GetCurrentFrame();
| ^~~~~~~~~~~~~~~
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:194:29: error: ‘class ORB_SLAM2::System’ has no member named ‘GetInitialKeys’
194 | mvIniKeys = m_SLAM->GetInitialKeys();
| ^~~~~~~~~~~~~~
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:195:32: error: ‘class ORB_SLAM2::System’ has no member named ‘GetInitialMatches’
195 | mvIniMatches = m_SLAM->GetInitialMatches();
| ^~~~~~~~~~~~~~~~~
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp: In member function ‘void MonocularSlamNode::UpdateMapState()’:
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:230:17: error: ‘class ORB_SLAM2::System’ has no member named ‘IsMapOptimized’
230 | if (m_SLAM->IsMapOptimized())
| ^~~~~~~~~~~~~~
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:234:31: error: ‘class ORB_SLAM2::System’ has no member named ‘GetAllKeyFrames’
234 | mvKeyFrames = m_SLAM->GetAllKeyFrames();
| ^~~~~~~~~~~~~~~
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:235:31: error: ‘class ORB_SLAM2::System’ has no member named ‘GetAllMapPoints’; did you mean ‘GetTrackedMapPoints’?
235 | mvMapPoints = m_SLAM->GetAllMapPoints();
| ^~~~~~~~~~~~~~~
| GetTrackedMapPoints
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:236:34: error: ‘class ORB_SLAM2::System’ has no member named ‘GetReferenceMapPoints’
236 | mvRefMapPoints = m_SLAM->GetReferenceMapPoints();
| ^~~~~~~~~~~~~~~~~~~~~
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp: In member function ‘void MonocularSlamNode::PublishFrame()’:
/home/ps/ros2_ws/src/slam/src/orbslam2/src/monocular/monocular-slam-node.cpp:255:63: error: no matching function for call to ‘rclcpp::Publisher<sensor_msgs::msg::Image_<std::allocator > >::publish(sensor_msgs::msg::Image_<std::allocator >::SharedPtr)’
255 | m_annotated_image_publisher->publish(rosImage.toImageMsg());
`

Any suggestions would be appreciated.

error: ‘MapPub’ was not declared in this scope

When I try to run the orbslam.sh, happens this error:

/home/user/Documents/Paul/tello-ros2/libs/Pangolin/build/ORB_SLAM2/src/System.cc:259:9: error: ‘MapPub’ was not declared in this scope
259 | MapPub->SetCurrentCameraPose(Tcw);
| ^~~~~~
make[2]: *** [CMakeFiles/ORB_SLAM2.dir/build.make:76: CMakeFiles/ORB_SLAM2.dir/src/System.cc.o] Error 1
make[2]: *** Waiting for unfinished jobs....
make[1]: *** [CMakeFiles/Makefile2:173: CMakeFiles/ORB_SLAM2.dir/all] Error 2
make: *** [Makefile:146: all] Error 2

If I comment the lines where the MapPub is used, works fine, but the compilation stops on
[ 72%] Linking CXX shared library ../lib/libORB_SLAM2.so

It nevers finish. What I need to do?

decoding error

I got error like blow, please help me.
the wifi connection is ok and I can control tello with offical app.

ROS2 version : Foxy Fitzroy

chaos@chaos-ubuntu:~/drone_ws$ ros2 run tello tello
[INFO] [1627166321.719289990] [tello]: Tello: Connecting to drone
[INFO] tello.py - 106 - Tello instance was initialized. Host: '192.168.10.1'. Port: '8889'.
[INFO] tello.py - 421 - Send command: 'command'
[INFO] tello.py - 445 - Response command: 'ok'
[INFO] [1627166321.876126831] [tello]: Tello: Connected to drone
[INFO] tello.py - 421 - Send command: 'streamon'
[INFO] tello.py - 445 - Response streamon: 'ok'
[INFO] [1627166322.085020725] [tello]: Tello: Driver node ready
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] non-existing PPS 0 referenced
[h264 @ 0x7fb75c013d80] decode_slice_header error
[h264 @ 0x7fb75c013d80] no frame!
[h264 @ 0x7fb75c06e280] error while decoding MB 12 39, bytestream -8
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 37, bytestream 4086
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 42, bytestream 2032
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 33, bytestream 4329
[h264 @ 0x7fb75c076600] left block unavailable for requested intra4x4 mode -1
[h264 @ 0x7fb75c076600] error while decoding MB 0 41, bytestream 1757
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 37, bytestream 3033
[h264 @ 0x7fb75c06e280] error while decoding MB 58 35, bytestream -10
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 26, bytestream 4906
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 34, bytestream 5268
[h264 @ 0x7fb75c06e280] error while decoding MB 10 34, bytestream -10
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 42, bytestream 1449
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 31, bytestream 4850
[h264 @ 0x7fb75c06e280] error while decoding MB 45 35, bytestream -6
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 38, bytestream 2674
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 41, bytestream 1390
[h264 @ 0x7fb75c06e280] error while decoding MB 15 35, bytestream -6
[h264 @ 0x7fb75c076600] left block unavailable for requested intra4x4 mode -1
[h264 @ 0x7fb75c076600] error while decoding MB 0 36, bytestream 2928
[h264 @ 0x7fb75c06e280] error while decoding MB 1 40, bytestream -10
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 43, bytestream 1078
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 39, bytestream 2424
[h264 @ 0x7fb75c06e280] error while decoding MB 17 35, bytestream -6
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 41, bytestream 1614
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 40, bytestream 1637
[h264 @ 0x7fb75c06e280] error while decoding MB 5 31, bytestream -8
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 40, bytestream 2956
[h264 @ 0x7fb75c06e280] error while decoding MB 11 33, bytestream -6
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 42, bytestream 38
[h264 @ 0x7fb75c06e280] error while decoding MB 44 43, bytestream -10
[h264 @ 0x7fb75c06e280] error while decoding MB 39 43, bytestream -8
[h264 @ 0x7fb75c076600] left block unavailable for requested intra4x4 mode -1
[h264 @ 0x7fb75c076600] error while decoding MB 0 34, bytestream 4200
[h264 @ 0x7fb75c06e280] error while decoding MB 31 32, bytestream -12
[h264 @ 0x7fb75c06e280] error while decoding MB 29 32, bytestream -10
[h264 @ 0x7fb75c076600] left block unavailable for requested intra mode
[h264 @ 0x7fb75c076600] error while decoding MB 0 37, bytestream 3102
[h264 @ 0x7fb75c076600] left block unavailable for requested intra4x4 mode -1
[h264 @ 0x7fb75c076600] error while decoding MB 0 35, bytestream 4137
[h264 @ 0x7fb75c06e280] error while decoding MB 3 40, bytestream -14
[h264 @ 0x7fb75c06e280] left block unavailable for requested intra mode
[h264 @ 0x7fb75c06e280] error while decoding MB 0 37, bytestream 3371
^CTraceback (most recent call last):
  File "/home/chaos/drone_ws/install/tello/lib/tello/tello", line 11, in <module>
    load_entry_point('tello==0.1.0', 'console_scripts', 'tello')()
  File "/home/chaos/drone_ws/install/tello/lib/python3.8/site-packages/tello/node.py", line 349, in main
    rclpy.spin(node)
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/__init__.py", line 191, in spin
    executor.spin_once()
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 703, in spin_once
    handler, entity, node = self.wait_for_ready_callbacks(timeout_sec=timeout_sec)
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 689, in wait_for_ready_callbacks
    return next(self._cb_iter)
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 586, in _wait_for_ready_callbacks
    _rclpy.rclpy_wait(wait_set, timeout_nsec)
KeyboardInterrupt
^CException ignored in: <module 'threading' from '/usr/lib/python3.8/threading.py'>
Traceback (most recent call last):
  File "/usr/lib/python3.8/threading.py", line 1388, in _shutdown
    lock.acquire()
KeyboardInterrupt:
Exception ignored in: <function Executor.__del__ at 0x7fb79028ff70>
Traceback (most recent call last):
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/executors.py", line 240, in __del__
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/signals.py", line 39, in destroy
AttributeError: 'NoneType' object has no attribute 'rclpy_unregister_sigint_guard_condition'
Exception ignored in: <function SignalHandlerGuardCondition.__del__ at 0x7fb7903a53a0>
Traceback (most recent call last):
  File "/opt/ros/foxy/lib/python3.8/site-packages/rclpy/signals.py", line 30, in __del__
TypeError: catching classes that do not inherit from BaseException is not allowed

Multi Drones

Hello,

In the readme you mention the possibility to use several drones with the driver. Have you already experimented it?
If yes, what is the approach?
For information I work with tello edu.

Thanks to you,
have a nice day.

No timestamps for /camera topic

Hi!

The problem is: there are no timestamps for /camera topic unfortunately...

See the screenshot below from

ros2 topic echo /camera

Screenshot from 2023-06-14 17-50-39

So, I can't use this topic to write a rosbag and use it further.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.