Saturday, February 22, 2014

Multiple AR.Drones from a single computer using the ardrone_autonomy ROS package

I'm currently working with a small graduate student team on centrally controlling a group of Parrot AR.Drone quadcopters or "quads" using the Robot Operating System (ROS), a software middleware for connecting robotic system components. There is a ROS driver called ardrone_autonomy for the AR.Drone, which wraps the AR.Drone SDK and exposes its controls and feedback to ROS' publish-subscribe model. This works well for controlling a single quad from a single computer. However, we ran into issues when trying to control multiple quads from a single computer, seemingly because the underlying SDK was designed for single-computer to single-quad use.

A lot of other groups have posted interesting solutions for controlling multiple quads. The AR.Drones use 802.11 wireless networks for control, feedback, and video; some solutions we examined focus on reconfiguring all quads to use a common network and then use multiple computers to control them. Others go a step further and allow control of multiple quads from a single computer. However, no solution that we've encountered allows both control and feedback/video of multiple quads from a single computer (at least, not using stock AR.Drone firmware).

One of the students, Brenton Campbell, and I set out to fly, crash, and break multiple quads at once hack some code and develop a solution for full bi-directional communications. This post documents and provides all code necessary for multi-quad control, feedback (navdata), and video from a single computer. It uses a modified version of the ardrone_autonomy ROS package and its included version of the AR.Drone SDK (v2.0.1, internally termed ARDroneLib), combined with some network hackery. Further, our solution requires no manual or permanent changes to the quad; it is entirely coordinated from the computer and can "automatically" reconfigure and utilize out-of-the-box quads. It has only been tested on v1.0 quads, but as far as I've read, it should apply equally to v2.0 quads.

I should note that this solution draws on insights gleaned from the above-referenced posts, and also:

The solution described herein might void warranties, violate license agreements, and (though exceedingly unlikely) render your AR.Drone unusable. My description assumes a fair amount of familiarity with Linux, comfort using the command line, and a bit of C and Python programming skill. Use this information and code at your own risk!

The solution can be broken into three steps, each of which I discuss below:
  1. Reconfiguring network settings on individual AR.Drones
  2. Remapping UDP ports to unique ground-side port numbers
  3. Modifying the AR.Drone SDK and ardrone_autonomy package to customize UDP ports
Update 3/26/2014 - Following a discussion thread on the ardrone_autonomy GitHub project, another contributor, Kenneth Bogert, discovered an alternative to steps 2 and 3 above. It turns out that when the computer sends UDP probe datagrams to a quad's video and navdata ports, the quad captures the source ports and uses them as its destination ports. By modifying the SDK to use ephemeral client-side ports, both video and navdata work and no port remapping is necessary. Kenneth posted a pull request with his modifications here.

Update 11/20/2014 - An updated version of Kenneth's pull request was merged into ardrone_autonomy on the 9th.

Reconfiguring network settings

This is the most well-documented piece of the puzzle. AR.Drones are equipped with 802.11g wireless devices; by default, they are configured in "ad-hoc" mode with SSIDs of the form "ardrone_XXXXX", where XXXXX is derived from their wireless MAC addresses. Hence, each quad has in theory a unique SSID. To control a group of quads from a single computer, it's easiest to bring them all onto the same SSID and IP address scheme. It turns out that the 802.11g (and 802.11n) standard specifies higher maximum data rates in infrastructure mode than in ad-hoc mode anyway, so we really want to reconfigure the quads to associate with an access point (especially since multiple quads will be sharing a single wireless medium; see below for more discussion about this).

The most widely-published solution for this is to leverage the telnet server running on each quad to log in (by the way, the quads run Linux!), write a small script such as the following, then log in and execute the script each time the quad is turned on:

#!/bin/sh 
killall udhcpd 
ifconfig ath0 down 
iwconfig ath0 mode managed channel auto essid myssid ap any 
ifconfig ath0 inet 192.168.0.101 netmask 255.255.255.0 up

This approach works great, but requires a) having to pre-install a script on each quad, and b) having to manually run the script every time they are rebooted. (Note: I tried incorporating these steps directly into the boot sequence on one quad, but somehow messed it up and now its wireless interface doesn't get properly configured. I still need to build a USB cable to re-flash it; for now, it's a desk ornament.)

We can write a script to scan for AR.Drone SSIDs from a computer, configure the computer to talk to each one, log in and execute this script. Going one step further, we can take a cue from SkyJack and send the reconfiguration commands over telnet rather than create an onboard script file at all (though our task is ostensibly simpler since we aren't "stealing" control from another computer). Once the ground computer is configured with the correct SSID and a compatible IP address (e.g., 192.168.1.10), the following long single-line command using the "traditional" version of netcat as a telnet client will perform the full reconfiguration of the quad (if you're using Debian or Ubuntu and have the "OpenBSD" version of netcat installed, the command-line options are slightly different; you can execute sudo apt-get install netcat-traditional && update-alternatives --set nc /bin/nc.traditional to switch versions):

echo "killall udhcpd; ifconfig ath0 down; iwconfig ath0 mode managed channel auto essid myssid; ifconfig ath0 inet 192.168.0.101 netmask 255.255.255.0 up" | nc -w 5 -q 0 192.168.1.1 23

In the command above, replace "myssid" with the SSID of your access point and "192.168.0.101" with a unique IP address in your address scheme (each quad you reconfigure will require a different IP address).

The following Python script automates this whole process. It periodically scans for AR.Drone SSIDs using one of the computer's wireless devices, then looks each found SSID up in a dictionary that maps SSIDs to IPs; if listed, the script reconfigures the wireless device to talk to the quad then sends a tailored reconfiguration command over telnet.

Update 3/10/2014 - Changed the script to parse the "Address" value from the output of iwlist and use it in the iwconfig command. This should prevent some instances where telnet reconfiguration fails for no good reason.

Download: ardrone_scanner.py

There are three variables to adjust near the top of the script. You must select a wireless interface that you want to dedicate to scanning for and reconfiguring quads; it will be tied up by this script and be unusable for other tasks while the script is running. If you are using Ubuntu's network-manager, you will first want to disable the management of the interface you choose (the script incorporates a call to the rfkill command to try and "unblock" local interface reconfiguration):

iface = "wlan1"

Next, change the access point SSID you want each quad to associate with:

new_ssid = "myssid"

Finally, create a mapping between AR.Drone SSIDs and the IP addresses you want each one to receive; this ensures that each quad takes on the same IP address every time it boots. You can extend this list with additional quads as you wish (you can find out a quad's SSID by powering it up and searching for available wireless networks using any wireless device):

ssid_to_ip = { 'ardrone_145784' : '192.168.0.101', \
               'ardrone_189028' : '192.168.0.102', \
               'ardrone_216674' : '192.168.0.103' }

The script must be run as root: sudo python ardrone_scanner.py

This script will only reconfigure quads for which it has a mapping, so you can also have quads booted that are not reconfigured. To reset the quads to their default configuration, simply un-power and re-power them with the script stopped (use <control>+c to end it).

This script attempts to catch most errors, but you may run into some new ones that we didn't... please post in the comments if you do, so we can try and improve it!

Remapping UDP ports

At this point, hopefully you're able to power up multiple quads and see them being successfully reconfigured. You should be able to run ardrone_autonomy or other controller software on multiple computers (one for each quad) connected to your wireless network to control the group of quads. But perhaps you're interested in controlling multiple quads from a single computer. To do so, we have a bit more work to do.

Each quad communicates with the ground controller using several TCP and UDP ports; based on reading other peoples' documentation online and performing my own traffic analysis using Wireshark, the following is a summary of the major ports used by ardrone_autonomy ("Eph" stands for auto-assigned ephemeral ports):

Protocol  Computer  Quad  Description
UDP       5554      5554  Navdata, quad to computer
UDP       5555      5555  Video, quad to computer
UDP       5556      5556  AT (commands), computer to quad
TCP       Eph       5551  FTP, check/upgrade firmware?
TCP       Eph       21    FTP, check/upgrade firmware?
TCP       Eph       5559  Configuration commands

There are a couple other momentary connections and FTP data connections as well. Interestingly, since the quad doesn't know the IP address of the controlling computer in advance, the computer must initially send a couple UDP datagrams on ports 5554 and 5555 to request Navdata (status/feedback) and Video from the quad. Upon receiving these datagrams, the quad starts sending UDP datagrams back to the same ports at the computer.

This leads to the crux: The quad is hard-coded to always send UDP packets to specific ports on the computer (such as 5554 and 5555). (See my comment above about Kenneth's solution, or keep reading for an alternative.) However, only one process can tie up ("bind") a UDP port at a time on a computer. When we try to run multiple instances of ardrone_autonomy, all instances (after the first one) fail to bind those ports and terminate. To overcome this, we need to: a) remap the UDP ports en-route to the computer (this section of the post), and b) reconfigure each instance of ardrone_autonomy to bind custom (remapped) UDP ports (next section of the post).

We can use a form of Network Address Translation (NAT) to alter the destination port of a UDP datagram en-route from one network device to another. We will do this twice: once for datagrams from the computer to the quad, and again for datagrams en-route from the quad to the computer (the reason for doing this twice is in part because the AR.Drone SDK is written to use the same UDP port number on both the computer and the quad). The Linux firewall software iptables, which I've utilized in a previous post, can be used to create these remappings. To remap from a custom UDP port at the computer (e.g., 10156) to the AT/command port (5556) on a quad with IP 192.168.0.101, we can apply this rule at the computer:

sudo iptables -t nat -A OUTPUT -p udp -d 192.168.0.101 --dport 10156 -j DNAT --to :5556

Likewise, to remap the Navdata port (5554) from the quad to a custom port at the computer (e.g., 10154), we can apply at the computer:

sudo iptables -t nat -A PREROUTING -p udp -s 192.168.0.101 --dport 5554 -j DNAT --to :10154

What's happening here? In the first rule, the remapping is applied to packets that are "output" from the computer. If the packet is a UDP datagram and is destined for IP 192.168.0.101 at port 10156 (I'm assuming we've already customized the ports our software is using, as discussed below), iptables changes the UDP destination port to 5556 and sends the datagram on its way. The second rule undoes this remapping, changing the default port 5554 to our custom port of 10154, as the packet is received (pre-routing decision) at the computer.

Again, below is a script that helps to automate this. It is separate from the reconfiguration script above simply because we might want to have one computer perform scanning and reconfiguring, and have another computer act as the central controller.

Download: ardrone_udp_remap.py

Like the first script, there are a couple variables to adjust. First, we create a mapping of port names to default ports:

udp_ports = { 'navdata' : 5554, \
              'video' : 5555, \
              'at' : 5556 }

If you need to extend this to include other ports, here is the place to do so. Just be sure to use unique names for each port. Second, build a mapping of each reconfigured IP address to the custom port numbers you wish to use:

ip_to_ports = { '192.168.0.101' : { 'navdata' : 10154, 'video' : 10155, 'at' : 10156 }, \
                '192.168.0.102' : { 'navdata' : 10254, 'video' : 10255, 'at' : 10256 }, \
                '192.168.0.103' : { 'navdata' : 10354, 'video' : 10355, 'at' : 10356 } }

You will want to adjust this for your quads' IPs and custom ports. You can extend this list with additional quads as well. If you want some ports to not get remapped, simply omit those from the mapping entry for a particular IP; the script will skip over that port. Run this script as root: sudo python ardrone_udp_remap.py

To reset your computer's iptables configuration, either reboot or enter this command (assuming you don't have other iptables NAT rules loaded): sudo iptables -t nat -F

Customizing UDP ports in software

Now that we've remapped our UDP ports, we need to customize which ports are used by each instance of ardrone_autonomy. Unfortunately, the AR.Drone SDK doesn't allow ports to be customized at runtime. In the ardrone_autonomy package, in file ARDroneLib/Soft/Common/config.h, we see a series of #define's such as this one for Navdata:

#define NAVDATA_PORT 5554

So as not to disturb the rest of the software too much, we can turn these names into global variables, introduce setter functions, and expose them as command-line options. Here is a quick summary of how to do this, shown for only one port. You can copy this for all ports you wish to customize; below is a tarball that contains all changed files from a fairly recent Git checkout of ardrone_autonomy with SDK v2.0.1 (commit bba002865b077e52ef750f38c42a60327d1ea275, from November 15, 2013, to be specific). The tarball includes the described changes for all ports.

In ARDroneLib/Soft/Common/config.h, replace each #define with a declaration of an externally-defined variable (since valid ports range roughly from 0-65535, we can use unsigned short ints):

extern unsigned short NAVDATA_PORT;

Then in ARDroneLib/Soft/Lib/ardrone_tool/ardrone_tool.c, define each variable and give it a default value:

unsigned short NAVDATA_PORT = 5554;

Also in this file, create a setter function for each variable:

void set_NAVDATA_PORT(uint16_t p) { NAVDATA_PORT = p; }

and create a corresponding prototype in ardrone_tool.h in the same directory. Finally, expose each variable as a command-line option (e.g., -navdata-port) in src/ardrone_driver.cpp (add this in the options-processing loop in main(...) ):

...
if( !strcmp(*argv, "-ip") && ( argc > 1 ) )
{
drone_ip_address = *(argv+1);
printf("Using custom ip address %s\n",drone_ip_address);
argc--; argv++;
}
else if ( !strcmp(*argv, "-navdata-port") && ( argc > 1 ) )
{
set_NAVDATA_PORT((unsigned short)atoi(*(argv+1)));
argc--; argv++;
}
...

If running the ardrone_driver node using roslaunch, you can specify these options using the following syntax (I've included an example launch file in the tarball below for two quads, using namespaces):

<node name="ardrone_driver" pkg="ardrone_autonomy" type="ardrone_driver" output="screen" clear_params="true" args="-ip 192.168.0.101 -navdata-port 10154 -video-port 10155 -at-port 10156" />

Download: ardrone_autonomy_hack.tar.gz

The tarball includes all changed code files, an example launch file, and a quick and dirty installation script that overwrites the original files with the changed files and recompiles both the SDK and the ROS package. To install these changes, unpack the tarball in the same parent directory as ardrone_autonomy (that is, ardrone_autonomy and ardrone_autonomy_hack should be sibling directories). Run the install script from inside the 'hack' directory: source ./install.sh (Note: this will require rebuilding both the AR.Drone SDK and the ardrone_autonomy package, and assumes your system is configured with any necessary software such as gcc needed to do so.)

Next steps (and caveats)

Hopefully this post conveys some additional insights about the AR.Drone and provides a way for folks using ROS (and potentially other software) to control multiple quads from a single computer and to receive both video and feedback from each quad.

Another possible solution is to have a single process bind to the Video and Navdata ports and de-multiplex the datagrams from all quads according to their source IP address, then pass corresponding datagrams along to individual handling processes or threads. I suspect this would entail a larger restructuring of both ardrone_autonomy and the AR.Drone SDK.

A couple caveats: I would strongly recommend that the controlling computer be wired into the access point you are using. Otherwise, every wireless frame is transmitted once from computer to access point, and a second time from access point to quad (or vice versa for video and navdata).

As you scale up the number of attached quads, the traffic load on the network will likewise increase. This may lead to congestion issues and cause latency and packet loss, both of which are bad for control of flying objects! One idea we are still experimenting is to turn off or degrade the video on some quads. There are some options in the SDK exposed by ardrone_autonomy for doing this.

Again, all of the information and code I've shared here has been used successfully, though within narrowly-defined conditions; use at your own risk! And, if you have any feedback from using this work, please let me know in the comments.

7 comments:

  1. Um, the ardrone_autonomy_hack.tar.gz is no longer there. Can you please correct the link?

    ReplyDelete
  2. Hello! Interesting, all three file links seem to work fine from here. As they're hosted via Google Drive, I've tested downloading them while being either logged in or logged out of my account; perhaps you can check both of those cases and let me know if one (or both) aren't working for you? Cheers!

    ReplyDelete
  3. Thanks for the reply, I can too verify they work. My school's internet has been acting funny so that was probably the reason. Thanks again, going to try this out because my research requires the control of multiple UAVs. Much appreciation on the help you are giving to resolve the multiple UAV issues. Didn't realize it was UDP causing the issue.

    ReplyDelete
  4. No problem! And, as I note in one of the "updates" near the top of the post, another developer created a patch that can work in place of manual UDP port remapping and the ardrone_autonomy mods I discuss in my post. Depending on your needs, this might be easier to implement than my solution. You can read about that patch here: https://github.com/AutonomyLab/ardronelib/pull/2

    Happy flying!

    ReplyDelete
  5. Hi Mike. Can I know the steps to run multi-Ar-drones based on your package? Do we need to run ardrone_udp_remap.py once we run the dual_test.launch file? Thanks.

    ReplyDelete
    Replies
    1. Hi Phi, it's been a little while and my memory is fuzzy, but it should be fine to run the remap script first and then launch. I'd strongly recommend checking out the subsequent improvements to ardrone_autonomy; it's no longer necessary to do UDP remapping. Best of luck!

      Delete
  6. Hi Mike..! Plz tell me how i come to know the name of my "iface" ?
    and myssid.. what are these things can you plz explain it briefly ?
    Thanks.

    ReplyDelete