flock2
can fly a swarm of DJI Tello drones.
flock2
is built on top of ROS2,
fiducial_vlam,
and tello_ros.
Set up a Ubuntu 20.04 box or VM.
Use your favorite Python package manager to set up Python 3.6+ and the following packages:
- numpy 1.15.2
- transformations 2018.9.5
Install ROS2 Foxy with the ros-foxy-desktop
option.
If you install binaries, be sure to also install the development tools and ROS tools from the source installation instructions.
Install these additional packages:
sudo apt install ros-foxy-cv-bridge ros-foxy-camera-calibration-parsers ros-foxy-gazebo-ros
Download, compile and install the following packages:
mkdir -p ~/flock2_ws/src
cd ~/flock2_ws/src
git clone https://github.com/clydemcqueen/flock2.git
git clone https://github.com/clydemcqueen/tello_ros.git
git clone https://github.com/ptrmu/fiducial_vlam.git
git clone https://github.com/ptrmu/ros2_shared.git
cd ..
source /opt/ros/foxy/setup.bash
# If you didn't install Gazebo, avoid building tello_gazebo:
colcon build --event-handlers console_direct+ --packages-skip tello_gazebo
launch_one.py
will allow you to fly a drone using a wired XBox One gamepad.
Turn on the drone, connect to TELLO-XXXXX
via wifi, and launch ROS2:
cd ~/flock2_ws
source install/setup.bash
ros2 launch flock2 launch_one.py
Gamepad controls:
- menu button to take off
- view button to land
- B to start mission
- A to stop mission
launch_two.py
provides an example for flying multiple drones.
Key elements of multi-drone missions:
- All drones must be networked together. One way to do this is to connect to each drone's wifi using a Raspberry Pi 3 or similar device, and forward all UDP packets from the Pi to the host computer. See udp_forward for an example using 2 Tello drones.
- Global nodes such as
flock_base
should have exactly 1 instance running. Per-drone nodes such asdrone_base
should have 1 instance running per drone. - Each drone has it's own ROS topic namespace. The default namespace for 1 drone is
solo
. - Each drone must have it's own URDF file with the appropriate coordinate frames.
- The joystick controls one drone at a time. Hit the right bumper to select a different drone.
- All drones participate in the mission.
ROS world coordinate frames are ENU (East, North, Up).
There are 3 significant coordinate frames in flock2
:
- The world frame is
map
- Each drone has a base coordinate frame. The default for 1 drone is
base_link
- Each drone has a camera coordinate frame. The default for 1 drone is
camera_frame
An arena is a right rectangular prism defined by 2 points: (x1=0, y1=0, z1=0) and (x2, y2, z2). z1 defines the ground, so z2 must be positive. The ground must be flat. Drones will never fly outside of the arena.
There must be at least one 6x6 ArUco marker, with id 1, associated with the arena. Marker 1's pose is known in advance, the other ArUco marker poses are estimated during flight. The drones will use ArUco marker poses to estimate their current pose.
A mission is defined as autonomous flight by all drones. A mission is initiated when the user hits the start mission button on the gamepad. A mission will end on it's own, or when the user hits the stop mission button.
All drones must be able to localize on the ground to start a mission. In practice this means that all drones must be able to see marker 1 while sitting on the ground, or at least one drone has to be flown around manually to build a good map before the mission starts.
The overall mission dataflow looks like this:
flock_base
publishes a message on the/start_mission
topicplanner_node
generates an overall pattern of flight for all drones, and publishes a sequence waypoints for each drone on/[prefix]/plan
drone_base
subscribes to~plan
and~base_odom
, runs a PID controller, and sends commands totello_ros
If odometry stops arriving drone_base
will execute a series of recovery tasks, which might include landing.
If flight indicates that a drone has a low battery drone_base
will land the drone.
Install Gazebo 9 and build tello_gazebo, if you haven't already.
cd ~/flock2_ws
source install/setup.bash
export GAZEBO_MODEL_PATH=${PWD}/install/tello_gazebo/share/tello_gazebo/models
source /usr/share/gazebo/setup.sh
ros2 launch flock2 gazebo_launch.py
Hit the "B" button on the XBox controller to start the mission. You should see 4 drones take off, rotate through 4 positions, then land.
Orchestrates the flight of one or more Tello drones.
~joy
sensor_msgs/Joy
/start_mission
std_msgs/Empty/stop_mission
std_msgs/Empty~[prefix]/joy
sensor_msgs/Joy
drones
is an array of strings, where each string is a topic prefix
Controls a single Tello drone. Akin to move_base
in the ROS navigation stack.
/start_mission
std_msgs/Empty/stop_mission
std_msgs/Empty~joy
sensor_msgs/Joy~tello_response
tello_msgs/TelloResponse~flight_data
tello_msgs/FlightData~base_odom
nav_msgs/Odometry
~cmd_vel
geometry_msgs/Twist
~tello_command
tello_msgs/TelloCommand
Compute and publish a set of waypoints for each drone in a flock.
/start_mission
std_msgs/Empty/stop_mission
std_msgs/Empty~[prefix]/base_odom
nav_msgs/Odometry
~[prefix]/plan
nav_msgs/Path
drones
is an array of strings, where the number of strings is the number of drones and each string is the topic prefix for a drone. For example,['d1', 'd2']
refers to 2 drones, and the flight data topic for the first drone is/d1/flight_data
. The default is['solo']
.arena_x
defines the X extent of the arena, in meters. The default is 2.arena_y
defines the Y extent of the arena, in meters. The default is 2.arena_z
defines the Z extent of the arena, in meters. Must be greater than 1.5. The default is 2.
flock2
was developed along with several other projects while ROS2 was rapidly changing.
All of the related projects adopted similar conventions around branch names:
- the
master
branch works with the latest ROS2 release (Foxy as of this writing) - there may be branches for older ROS2 versions, such as
crystal
,dashing
oreloquent
The following projects and branches were tested together:
- ROS2 Foxy with fiducial_vlam: