Guide for using DDS over PPP with a Raspberry Pi 4 companion computer

For those getting into ROS 2 and Raspberry Pi, here is a A-Z guide on how to setup a fresh Raspberry Pi 4 to run ROS 2 Humble on Ubuntu 22.04, and taking advantage of Ardupilot’s new features, such as DDS for low-latency topic publishing and PPP to simulate an network link that can support DDS, Mavlink and a webserver (and more) on the same connection.

At the time of writing this guide, Ardupilot 4.5.7 is the latest stable build. The steps in this guide require at the minimum AP 4.6. There is a 4.6.0-beta1 available at the time of writing this guide, but I will be showing how to build AP from the master branch, which will create the 4.7.0-dev firmware.

Support for ROS 2 Jazzy and Ubuntu 24.04 is being developed, so another guide could eventually written.

As DDS is still being developed, this guide might not be valid for future releases of Ardupilot.

1-Hardware Setup

My current setup doesn’t include a functional drone, it is simply a Raspberry Pi 4 paired with a Matek H743 Slim V3. Both are setup on a compact 3D printed support. CAD is available on Onshape. There’s also a Holybro M10 Micro GPS/Compass and a Pololu 5V, 5.5A Voltage Regulator to power the Pi when I will eventually transition to powering the hardware with a LiPo battery. For now, the flight controller is powered by the RPi’s USB port.

I recommend using a heatsink on the CPU and RAM, as well as a fan to help with cooling. It’s a must if you decide to overclock the CPU and/or run CPU intensive algorithms alongside DDS.

For wiring, I’m connecting the Pi’s UART0 to the flight controller’s SERIAL1 port. On the Matek H743 Slim, these are pads Rx7 and Tx7. I am also wiring for hardware flow control, which is required for fast baudrates.

Matek ~~~ RPi4
Rx7   ==> GPIO 14 (Pin 8)
Tx7   ==> GPIO 15 (Pin 10)
Rts7  ==> GPIO 16 (Pin 36)
Cts7  ==> GPIO 17 (Pin 11)
Gnd   ==> Gnd

2-Raspberry Pi 4 Setup

2.1-Ubuntu and Pi Setup

Flash SD card with Ubuntu 22.04 LTS (64 bit) using Raspberry Pi Imager. This guide should work for both Desktop or Server versions of Ubuntu, but if you’re going Server, it would be best to configure your networking before going too far in the setup process, to allow yourself to ssh into the RPi4 and copy/paste the commands from a PC with a web explorer. Full disclaimer, I wrote this guide using Ubuntu Desktop.
Boot up, set your language, computer and username, location and connect to wifi. Then, once booted, update the bootloader and all the packages.

sudo update
sudo rpi-eeprom-update -a
sudo reboot
sudo apt update
sudo apt upgrade -y
sudo reboot

Then edit the Raspberry Pi parameters with sudo nano /boot/firmware/config.txt. At the bottom of the file, add the lines:

enable_uart=1
init_uart_clock=200000000
dtoverlay=disable-bt
dtoverlay=uart0,ctsrts
gpio=16-17=a3

Explanation:
RPi 4 has 2 types of UART

  • PL011 (better)
  • Mini-UART (reduced features)

We disable Bluetooth (which was on a PL011) to move the primary UART from a Mini-UART to the PL011 (more info here). We also specify that UART0 will use hardware flow control (ctsrts) using GPIO 16 and 17. And we speed up the UART clock to 200 MHz to allow for a 12.5 MBaud connection. UART0 will be available on /dev/ttyAMA0 or /dev/serial0.

Then save /boot/firmware/config.txt with these changes.

To make sure the Primary UART (UART0) is unoccupied, make sure you disable the Bluetooth controller and the serial Linux console permanently.

sudo systemctl disable hciuart
sudo systemctl disable serial-getty@ttyAMA0.service

And then add yourself into the group dialout to be allowed to use the UART ports

sudo usermod -a -G dialout $USER
sudo reboot

Optional: CPU overclock
For those who need a little extra from the CPU. You can add these lines to /boot/firmware/config.txt. Choose either of the 2 sets of 3 parameters.

#over_voltage=6
#arm_freq=2000
#gpu_freq=700
over_voltage=8
arm_freq=2250
gpu_freq=750

This will not improve DDS or PPP. It’s only in case you plan on running CPU intensive algorithms alongside DDS.

2.2-Ardupilot

Install the Ardupilot development environment (more info here).

sudo apt install git -y
git clone --recurse-submodules https://github.com/ArduPilot/ardupilot.git
cd ardupilot
Tools/environment_install/install-prereqs-ubuntu.sh -y
. ~/.profile
sudo reboot

2.3-ROS 2

Install ROS 2 Humble (more info here).

Make sure your locales are set to UTF-8

locale  # check for UTF-8

sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8

locale  # verify settings

Setup the sources for apt

sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl -y
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null

Install ROS 2 Humble

sudo apt update && sudo apt upgrade -y
sudo apt install ros-humble-ros-base ros-dev-tools -y
sudo apt install ros-humble-geographic-msgs -y

Finally, permanently source the ROS location in your shell startup script.

echo "source /opt/ros/humble/setup.bash" >> ~/.bashrc
sudo reboot

2.4-Ardupilot ROS 2 Repos

Use these steps to download the ROS 2 repos for Ardupilot DDS and install the dependencies. Based off these guides (wiki, git readme).

mkdir -p ~/ros2_ws/src && cd ~/ros2_ws/src
wget https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/ros2.repos
vcs import --recursive < ros2.repos
cd ~/ros2_ws
sudo apt update
sudo rosdep init
rosdep update
rosdep install --rosdistro humble --from-paths src --ignore-src

2.5-Micro-XRCE-DDS-Gen

Install Micro-XRCE-DDS-Gen. This is needed when building the Ardupilot firmware with DDS enabled.

sudo apt install default-jre -y
cd ~/ros2_ws
git clone --recurse-submodules https://github.com/ardupilot/Micro-XRCE-DDS-Gen.git
cd Micro-XRCE-DDS-Gen/
./gradlew assemble
echo "export PATH=\$PATH:$PWD/scripts" >> ~/.bashrc
sudo reboot

2.6-Colcon Build

Now is time to build the ROS 2 packages using colcon. You have 2 options for building: either you build only for a companion computer that will not be used for SITL, or you build for a computer on which you might use SITL. Most likely, you will not be using your RPi4 for SITL.

Companion computer without SITL packages

cd ~/ros2_ws
colcon build --packages-select micro_ros_agent

Building for SITL and communication with hardware

cd ~/ros2_ws
colcon build --packages-up-to ardupilot_dds_tests

The latter option will take a lot more time to build on a RPi4.

2.7-PPPD

To enable the use of pppd (which is what is used on the Pi to enable the PPP connection with the flight controller), run this command

sudo apt install linux-modules-extra-raspi
sudo reboot

Most likely, the version by default on your Ubuntu 22.04 is version 2.4.9 (you can check with pppd --version. While you can still use version 2.4.9, it will not be able to achieve the fastest 12.5M baudrate. You will need version 2.5.1.

sudo apt update && sudo apt install build-essential -y
curl -L https://github.com/ppp-project/ppp/archive/refs/tags/ppp-2.5.1.tar.gz | tar -xz
cd ~/ppp-ppp-2.5.1
autoreconf -i 
./configure 
make 
sudo make install

Andrew Tridgell has a video showcasing the uses of PPP.

3-Flight Controller Setup

If using a brand new flight controller that doesn’t have Ardupilot pre-installed, you have to flash Ardupilot with bootloader. I recommend using STM32CubeProgrammer. This step doesn’t have to be performed on the RPi 4, I prefer using a Windows PC. Download the latest or stable firmware for your board (for example, for the Matek H743, from here). Make sure you download the _with_bl.hex file. Then follow this guide or this video tutorial.

4-Build Ardupilot Firmware

Once your flight controller is ready, plug it via USB to your RPi 4. Now back on your RPi 4, build the Ardupilot firmware with DDS and PPP enabled and upload it to your FC. When doing ./waf configure, specify the correct board.

cd ~/ardupilot
./waf configure --board MatekH743 --enable-dds --enable-PPP
./waf copter --upload

This will take some time.

5-Ardupilot Parameters

Now you must set the correct parameters in Ardupilot. You will have to reboot and/or refresh the parameters multiples times, as you will be enabling multiple “enable” parameters. You can use Mavproxy on your RPi4 to edit the parameters (mavproxy.py --console will detect the flight controller connected via USB), or connect your flight controller to a PC with Mission Planner.

5.1-Serial Port Parameters:

SERIAL1_PROTOCOL,48
SERIAL1_BAUD,12500000
BRD_SER1_RTSCTS,1

This enable PPP on SERIAL1, maxes out the baudrate (allowing for fast networking and fast log download using the webserver (faster than USB)), and also enables flow control.

5.2-PPP Parameters:

NET_ENABLE,1
NET_OPTIONS,0
NET_P1_IP0,192
NET_P1_IP1,168
NET_P1_IP2,13
NET_P1_IP3,16
NET_P1_PORT,15001
NET_P1_PROTOCOL,2
NET_P1_TYPE,1
NET_P2_TYPE,0
NET_P3_TYPE,0
NET_P4_TYPE,0

This enables Mavlink over PPP. NET_P1_TYPE,1 sets the port to use UDP and enables the IP address parameters. The address 192.168.13.16 is the destination address, which will need to be specified by pppd on the RPi4. You can choose a random value for NET_P1_IP3, as long as it is not the same as another device on your network.

5.3-DDS Parameters:

DDS_DOMAIN_ID,0
DDS_ENABLE,1
DDS_IP0,192
DDS_IP1,168
DDS_IP2,13
DDS_IP3,16
DDS_UDP_PORT,2019

This sets the DDS destination to the same address at the one specified by the NET_* parameters, but to port 2019 instead.

5.4-Webserver Parameters:

The webserver is done via a lua script. Therefore, first enable scripting:

SCR_ENABLE,1
SCR_VM_I_COUNT,1000000

And then download the file net_webserver.lua from Ardupilot’s Github. There is also a readme. Andrew Tridgell has a good video tutorial for the webserver.

Using Mission Planner’s MAVftp tool, upload the net_webserver.lua file to the flight controller’s APM/scripts/ folder. Then reboot and change the following parameters:

WEB_ENABLE,1
WEB_BIND_PORT,80

6-Run

You’re now ready to use DDS and PPP!
Power the RPi4 and the flight controller, open a terminal and run:

sudo pppd /dev/ttyAMA0 12500000 192.168.13.16:192.168.13.65 crtscts debug noauth nodetach local proxyarp ktune

This takes the incoming stream from /dev/ttyAMA0 (at a 12.5M Baudrate) destined for 192.168.13.16 (the local IP of pppd) and defines the remote (the flight controller) as 192.168.13.65. You can change 65 for anything you want.

Then, open another terminal and start the micro_ros_agent, listening on port 2019 (specified in the DDS_* parameters).

cd ~/ros2_ws
source install/setup.bash
ros2 run micro_ros_agent micro_ros_agent udp4 --port 2019

Nothing will happen at first. This is because DDS on the flight controller will shutdown if it doesn’t connect to the micro_ros_agent within 10 seconds of boot. You have to reboot the flight controller. Either power cycle the flight controller, or open another terminal to connect to the flight controller using Mavlink over the PPP connection:

mavproxy.py --console --master=udp:192.168.13.16:15001

Send the command reboot to reboot your flight controller.

You should see the micro_ros_agent acknowledge the reception of the DDS topics.

You can now view the available topics with

ros2 topic list -v
Published topics:
 * /ap/airspeed [geometry_msgs/msg/Vector3] 1 publisher
 * /ap/battery [sensor_msgs/msg/BatteryState] 1 publisher
 * /ap/clock [rosgraph_msgs/msg/Clock] 1 publisher
 * /ap/geopose/filtered [geographic_msgs/msg/GeoPoseStamped] 1 publisher
 * /ap/gps_global_origin/filtered [geographic_msgs/msg/GeoPointStamped] 1 publisher
 * /ap/imu/experimental/data [sensor_msgs/msg/Imu] 1 publisher
 * /ap/navsat [sensor_msgs/msg/NavSatFix] 1 publisher
 * /ap/pose/filtered [geometry_msgs/msg/PoseStamped] 1 publisher
 * /ap/tf_static [tf2_msgs/msg/TFMessage] 1 publisher
 * /ap/time [builtin_interfaces/msg/Time] 1 publisher
 * /ap/twist/filtered [geometry_msgs/msg/TwistStamped] 1 publisher
 * /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher
 * /rosout [rcl_interfaces/msg/Log] 1 publisher

Subscribed topics:
 * /ap/cmd_gps_pose [ardupilot_msgs/msg/GlobalPosition] 1 subscriber
 * /ap/cmd_vel [geometry_msgs/msg/TwistStamped] 1 subscriber
 * /ap/joy [sensor_msgs/msg/Joy] 1 subscriber
 * /ap/tf [tf2_msgs/msg/TFMessage] 1 subscriber

View the frequency of a topic with

ros2 topic hz /ap/time

View the contents of a topic with

ros2 topic echo /ap/imu/experimental/data

Finally, you can access the webserver by going on Firefox and entering 192.168.13.65 in the address bar. You can test log downloads and you should achieve speeds of 780-800 KB/s.

Obviously, you won’t be regularly accessing the webserver via the RPi4, but there are networking settings that need to be done to access the ROS 2 Topics and the webserver from a ground station computer. But that will be for another guide.

3 Likes

Hi, thanks for this guide. It covers just what I needed.
During step 2.6 - Colcon Build for SITL - I encountered errors from ardupilot_dds_tests and ardupilot_stil.


Did you encounter this, and do you know what the cause could be?
I followed your exact steps, so I am curious about this.
Thank you.

Yeah, i get those errors when doing colcon build --packages-up-to ardupilot_dds_tests just warnings and stderr. As far as I know, it’s “normal”. But the micro_ros_agent is still able to run. But I’m choosing to go with colcon build --packages-select micro_ros_agent since I won’t be using the RPi4 for SITL.

I think I also got those errors on my WSL where I do SITL, but the errors didn’t stop it from working.