A question that comes up from time to time is how to test DDS on hardware when connected to a laptop or desktop computer. The following notes describe the setup on a MacBook and MatekH743-WING using a CP2102 USB-to-UART bridge to provide a second USB connection to the FC. The procedure for other computers and FCs should be similar.
Hardware
The host and flight controller IP addresses and device mappings appearing in /dev/*
will be different for each individual setup. The ones listed below are used to illustrate how to set up the various networking and DDS parameters then use them in terminal commands.
Host
- MacBook Pro 2021
- Chip: Apple M1 Max
- RAM: 32 GB
- macOS: Sonoma 14.5
- IP: 192.168.1.181
FC
- MatekH743-WING v1
- IP: 192.168.1.60
The FC is connected to the computer by two cables:
- USB connected to the USB-C port on the FC. The device is
/dev/cu.usbmodem101
- CP2102 USB-to-UART bridge connected to RX7, TX7, GND. The device is
/dev/cu.usbserial-0001
.
Firmware
The ArduPilot firmware must be be built with the --enable-dds
and ---enable-ppp
flags. This combination is not currently supported on the custom build server, so will need to be built in a development environment.
Parameters
Overview of serial ports:
SERIAL0_PROTOCOL 2 # MAVLink2
SERIAL1_PROTOCOL 48.0 # PPP
SERIAL2_PROTOCOL 2 # MAVLink2
SERIAL3_PROTOCOL 32 # MSP
SERIAL4_PROTOCOL 5 # GPS
SERIAL5_PROTOCOL -1 # None
SERIAL6_PROTOCOL -1 # None
SERIAL7_PROTOCOL 23 # RCIN
SERIAL8_PROTOCOL 22 # SLCAN
Console (USB)
SERIAL0_BAUD 115 # 115200
SERIAL0_PROTOCOL 2 # MAVLink2
Serial1 = Telem1 (UART7)
SERIAL1_BAUD 921000.0
SERIAL1_OPTIONS 0 #
SERIAL1_PROTOCOL 48.0 # PPP
Networking
NET_ENABLED 1
NET_OPTIONS 0 #
NET_P1_IP0 192
NET_P1_IP1 168
NET_P1_IP2 1
NET_P1_IP3 60
NET_P1_PORT 0
NET_P1_PROTOCOL 0
NET_P1_TYPE 1 # UDP client
NET_P2_TYPE 0 # Disabled
NET_P3_TYPE 0 # Disabled
NET_P4_TYPE 0 # Disabled
DDS
DDS_ENABLE 1 # Enabled
DDS_IP0 192
DDS_IP1 168
DDS_IP2 1
DDS_IP3 181
DDS_PORT 2019
Terminals
MAVProxy
mavproxy.py --master /dev/cu.usbmodem101 --console
micro-ROS agent
ros2 run micro_ros_agent micro_ros_agent udp4 --port 2019 --verbose 6 --refs ./dds_xrce_profile.xml
Note: if running master
the refs
argument should not be used.
Run the PPP daemon
sudo pppd /dev/cu.usbserial-0001 921600 192.168.1.181:192.168.1.60 debug noauth nodetach local proxyarp ktune
ROS 2 console
ros2 node list
/ardupilot_dds
ros2 node info /ardupilot_dds
/ardupilot_dds
Subscribers:
/ap/cmd_gps_pose: ardupilot_msgs/msg/GlobalPosition
/ap/cmd_vel: geometry_msgs/msg/TwistStamped
/ap/joy: sensor_msgs/msg/Joy
/ap/tf: tf2_msgs/msg/TFMessage
Publishers:
/ap/battery/battery0: sensor_msgs/msg/BatteryState
/ap/clock: rosgraph_msgs/msg/Clock
/ap/geopose/filtered: geographic_msgs/msg/GeoPoseStamped
/ap/navsat/navsat0: sensor_msgs/msg/NavSatFix
/ap/pose/filtered: geometry_msgs/msg/PoseStamped
/ap/tf_static: tf2_msgs/msg/TFMessage
/ap/time: builtin_interfaces/msg/Time
/ap/twist/filtered: geometry_msgs/msg/TwistStamped
Service Servers:
/ap/arm_motors: ardupilot_msgs/srv/ArmMotors
/ap/mode_switch: ardupilot_msgs/srv/ModeSwitch
Service Clients:
Action Servers:
Action Clients:
Notes
On macOS the version of ROS 2 used is Rolling. This is primarily because on macOS ROS 2 must be built from source, and the package manager brew
operates a rolling release update / upgrade paradigm. At the beginning of 2024 brew
switched to Python 3.12 as default which meant that building ROS 2 Humble from source became quite complicated. The procedure in a ROS 2 Humble environment should be the same.
MacOS has a version of pppd
installed in /usr/sbin/pppd
. This works well at the suggested baudrate of 921000
when flow control is not available.
Before configuring the second serial connection for PPP, a useful check to verify the serial connection on the CP2102 USB-to-UART is working correctly is to initially configure the serial port for MAVLink2 at a baudrate 57600
.
Serial1 = Telem1 (UART7)
SERIAL1_BAUD 57 # 57600
SERIAL1_OPTIONS 0 #
SERIAL1_PROTOCOL 2 # MAVLink2
and check data is received with
python -m serial.tools.miniterm
or attach another MAVProxy session
mavproxy.py --master /dev/cu.usbserial-0001