A complete software stack to operate a Pixhawk quadcopter Beyond Visual Line of Sight (BVLOS) over a 4G cellular link, using a Raspberry Pi 4 as the on-board companion computer and Tailscale VPN to securely reach the drone from Mission Planner running on your laptop.
[ Pixhawk ] --USB/UART--> [ Raspberry Pi 4 ] --4G dongle--> [ Internet ]
| |
+---- Tailscale VPN tunnel ----+
|
[ Laptop / Mission Planner / Joystick ]
GPS M10NRC IN (PPM/SBUS)POWERusb0 networking| Pixhawk TELEM2 | Raspberry Pi 4 (GPIO header) |
|---|---|
| TX (pin 2) | RX GPIO15 (pin 10) |
| RX (pin 3) | TX GPIO14 (pin 8) |
| GND (pin 6) | GND (pin 6) |
| 5V | do NOT connect (Pi powered separately by 5 V from SMPS) |
or
Connect Pi to Pichawk using USB.
Telemetry over GPIO UART =
/dev/serial0at 921600 baud (recommended for ArduPilotSERIAL2).
pipi / piFrom your laptop, secure copy the repository to the drone:
scp -r BVLOS pi@pi.local:/home/pi/
(If pi.local is not resolving, find the IP address assigned by your router and use scp -r BVLOS pi@<IP_ADDRESS>:/home/pi/)
Navigate to the directory and run the main installer script:
cd ~/BVLOS/drone
chmod +x *.sh
sudo ./00_install.sh
What this script does:
/dev/serial0 at 921600 baud) for connection to Pixhawk.mavproxy.service, video.service, and 4g-watchdog.service) so they start on system boot.Authenticate the Pi node on your Tailscale network:
sudo tailscale up --ssh --hostname=pi
Copy the provided auth URL and open it in your computer’s web browser to sign in. Note the Tailscale IP assigned to the Pi (e.g., 100.x.y.z).
The drone pipelines H.264 video directly to the IP address of your Ground Control Station (GCS). Find your laptop’s Tailscale IP address (Hover over Tailscale > your laptop name), then edit the drone’s video environment file:
nano ~/BVLOS/drone/video.env
Update GCS_IP=100.aa.bb.cc replacing it with your laptop’s Tailscale IP. Save and exit (Ctrl+O, Enter, Ctrl+X).
Reboot the Pi:
sudo reboot
SERIAL2_PROTOCOL: 2 (MAVLink2)SERIAL2_BAUD: 921 (921600 baud)BRD_SER2_RTSCTS: 0 (Disable flow control since we use 3-wire TX/RX/GND)SR2_EXTRA1: 4 (Attitude stream rate in Hz)SR2_EXTRA2: 4SR2_EXTRA3: 2SR2_POSITION: 3SR2_RAW_SENS: 2SR2_RC_CHAN: 2LOG_BACKEND_TYPE: 1 (Log strictly to the onboard SD card)Your USB 4G dongle acts as an RNDIS interface (usb0) providing internet to the Pi.
ip addr show usb0ping -c 3 8.8.8.8http://192.168.225.1 to configure it first.4g-watchdog.service (check below for the script) will monitor the internet connection during flight. If it drops for >60s, it automatically resets the USB connection to restore signal.On your Windows laptop:
ping pi in PowerShell.C:\\gstreamer\\1.0\\msvc_x86_64\\bin to your Windows Environment PATH variables.Navigate to the gcs folder locally:
cd BVLOS\\gcs
Open start_gcs.ps1 in a text editor (Notepad or VSCode).
If you changed the hostname on the Pi, update $PiTailscaleName = "pi".
Run the script:
.\\start_gcs.ps1
Mission Planner will launch and preload a TCP connection target. Ensure it says TCP, Port 5760, points to pi and click Connect.
The view_video.ps1 script will simultaneously launch in a secondary PowerShell window, listening on UDP port 5600 for the drone’s camera feed.
(Optional) Joystick Control: If you wish to fly with a USB gamepad (e.g. Xbox Controller or PC Joystick):
python gcs\\joystick_bridge.py --target <pi-tailscale-IP>:14551Hardware Power Up:
Boot & Link Negotiation (Wait 3 Minutes):
or
DO IT MANUALLY using ssh to pi:
Establish GCS Connection in a new terminal using SSH:
.\\start_gcs.ps1 on your laptop.Safety Checklist:
ping pi. Must be solidly < 250ms for safe joystick operations.4g-watchdog service is constantly running. If you lose connection for over 60 seconds, the watchdog will internally cycle the dongle, and the Pixhawk RC Failsafe will catch the drop and initiate RTL.BVLOS/
├── README.md ← this file
├── drone/ ← runs on the Raspberry Pi
│ ├── 00_install.sh
│ ├── 10_uart_setup.sh
│ ├── 20_tailscale.sh
│ ├── mavproxy.env
│ ├── start_mavproxy.sh
│ ├── video.env
│ ├── start_video.sh
│ ├── 4g_watchdog.sh
│ └── systemd/
│ ├── mavproxy.service
│ ├── video.service
│ └── 4g-watchdog.service
├── gcs/ ← runs on the laptop
│ ├── start_gcs.ps1
│ ├── view_video.ps1
│ └── joystick_bridge.py
└── docs/
└── wiring.md
SSH into the Pi:
ssh pi@pi.local or ssh pi@<tailscale_ip>
00_install.sh:
#!/usr/bin/env bash
# 00_install.sh — one-shot installer for the on-board Raspberry Pi
# Run as: sudo ./00_install.sh
set -euo pipefail
if [[ $EUID -ne 0 ]]; then
echo "Please run as root: sudo $0"
exit 1
fi
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
TARGET_USER="${SUDO_USER:-pi}"
TARGET_HOME="$(getent passwd "$TARGET_USER" | cut -d: -f6)"
echo "=== [1/6] apt update & base packages ==="
apt-get update
apt-get install -y --no-install-recommends \
python3 python3-pip python3-venv \
git curl wget jq \
screen tmux \
network-manager iputils-ping \
v4l-utils \
gstreamer1.0-tools gstreamer1.0-plugins-base \
gstreamer1.0-plugins-good gstreamer1.0-plugins-bad \
gstreamer1.0-plugins-ugly gstreamer1.0-libav
echo "=== [2/6] MAVProxy ==="
# pipx avoids the PEP 668 'externally-managed' error on Bookworm
apt-get install -y pipx
sudo -u "$TARGET_USER" pipx ensurepath || true
sudo -u "$TARGET_USER" pipx install --force MAVProxy || \
sudo -u "$TARGET_USER" pipx upgrade MAVProxy
# Symlink mavproxy into /usr/local/bin so systemd unit finds it
MAVPROXY_BIN="$TARGET_HOME/.local/bin/mavproxy.py"
if [[ -x "$MAVPROXY_BIN" ]]; then
ln -sf "$MAVPROXY_BIN" /usr/local/bin/mavproxy.py
fi
echo "=== [3/6] UART for Pixhawk ==="
bash "$SCRIPT_DIR/10_uart_setup.sh"
echo "=== [4/6] Tailscale ==="
bash "$SCRIPT_DIR/20_tailscale.sh"
echo "=== [5/6] Install systemd services ==="
install -m 0644 "$SCRIPT_DIR/systemd/mavproxy.service" /etc/systemd/system/mavproxy.service
install -m 0644 "$SCRIPT_DIR/systemd/video.service" /etc/systemd/system/video.service
install -m 0644 "$SCRIPT_DIR/systemd/4g-watchdog.service" /etc/systemd/system/4g-watchdog.service
chmod +x "$SCRIPT_DIR"/*.sh
# Substitute paths in unit files
sed -i "s|__USER__|$TARGET_USER|g; s|__DIR__|$SCRIPT_DIR|g" /etc/systemd/system/mavproxy.service
sed -i "s|__USER__|$TARGET_USER|g; s|__DIR__|$SCRIPT_DIR|g" /etc/systemd/system/video.service
sed -i "s|__USER__|$TARGET_USER|g; s|__DIR__|$SCRIPT_DIR|g" /etc/systemd/system/4g-watchdog.service
systemctl daemon-reload
systemctl enable mavproxy.service video.service 4g-watchdog.service
echo "=== [6/6] Done ==="
echo "Now run: sudo tailscale up --ssh --hostname=pi"
echo "Then reboot: sudo reboot"
echo "Services will start automatically on next boot."
4g_watchdog.sh:
#!/usr/bin/env bash
# 4g_watchdog.sh — restart the 4G usb0 interface when internet is lost
set -euo pipefail
IFACE="${IFACE:-usb0}"
PING_HOST="${PING_HOST:-8.8.8.8}"
FAIL_THRESHOLD="${FAIL_THRESHOLD:-6}" # 6 * 10 s = 60 s
SLEEP_SEC=10
fails=0
while true; do
if ping -I "$IFACE" -c 1 -W 3 "$PING_HOST" >/dev/null 2>&1; then
fails=0
else
fails=$((fails + 1))
echo "$(date -Is) ping fail #$fails on $IFACE"
if (( fails >= FAIL_THRESHOLD )); then
echo "$(date -Is) bouncing $IFACE"
ip link set "$IFACE" down || true
sleep 2
ip link set "$IFACE" up || true
# Try to get a fresh DHCP lease
dhclient -r "$IFACE" 2>/dev/null || true
dhclient "$IFACE" 2>/dev/null || true
fails=0
fi
fi
sleep "$SLEEP_SEC"
done
10_uart_setup.sh
#!/usr/bin/env bash
# 10_uart_setup.sh — free /dev/serial0 for Pixhawk telemetry on Raspberry Pi 4
set -euo pipefail
CONFIG=/boot/firmware/config.txt
[[ -f $CONFIG ]] || CONFIG=/boot/config.txt # fallback for older OS
CMDLINE=/boot/firmware/cmdline.txt
[[ -f $CMDLINE ]] || CMDLINE=/boot/cmdline.txt
echo "Using $CONFIG and $CMDLINE"
# 1) Disable serial console (login shell) on UART
systemctl disable --now serial-getty@ttyAMA0.service 2>/dev/null || true
systemctl disable --now serial-getty@ttyS0.service 2>/dev/null || true
sed -i 's/console=serial0,[0-9]\+ //g' "$CMDLINE"
# 2) Enable UART hardware and disable Bluetooth (so PL011 UART is on GPIO14/15)
add_line () {
local line="$1"
grep -qxF "$line" "$CONFIG" || echo "$line" >> "$CONFIG"
}
add_line "enable_uart=1"
add_line "dtoverlay=disable-bt"
systemctl disable --now hciuart 2>/dev/null || true
# 3) Permissions: add user to dialout
usermod -aG dialout "${SUDO_USER:-pi}"
echo "UART configured. /dev/serial0 will point to PL011 after reboot."
20_tailscale.sh
#!/usr/bin/env bash
# 20_tailscale.sh — install Tailscale on the Pi
set -euo pipefail
if command -v tailscale >/dev/null 2>&1; then
echo "Tailscale already installed: $(tailscale version | head -n1)"
exit 0
fi
curl -fsSL https://tailscale.com/install.sh | sh
systemctl enable --now tailscaled
cat <<EOF
Tailscale daemon is running. Authenticate once with:
sudo tailscale up --ssh --hostname=pi
EOF
mavproxy.env
# mavproxy.env — configuration for the MAVProxy bridge
# Source-able shell file (KEY=VALUE)
# Pixhawk telemetry UART on the Pi
SERIAL_PORT=/dev/serial0
SERIAL_BAUD=921600
# Local UDP outputs (over Tailscale, the laptop reaches these via the Pi's TS IP)
# - 5760 (TCP) is what Mission Planner connects to.
# - 14551 is for the joystick bridge / extra GCS clients.
TCP_PORT=5760
UDP_OUT_PORT=14551
# Bind addresses (0.0.0.0 so Tailscale interface is included)
BIND_ADDR=0.0.0.0
# MAVProxy log dir
LOG_DIR=/var/log/mavproxy
start_mavproxy.sh:
#!/usr/bin/env bash
# start_mavproxy.sh — bridge Pixhawk UART <-> network (run by systemd)
set -euo pipefail
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
# shellcheck disable=SC1091
source "$SCRIPT_DIR/mavproxy.env"
mkdir -p "$LOG_DIR"
exec mavproxy.py \
--master="${SERIAL_PORT},${SERIAL_BAUD}" \
--out="tcpin:${BIND_ADDR}:${TCP_PORT}" \
--out="udpin:${BIND_ADDR}:${UDP_OUT_PORT}" \
--daemon \
--logfile="${LOG_DIR}/mav.tlog" \
--state-basedir="${LOG_DIR}" \
--streamrate=10 \
--mav20
start_video.sh
#!/usr/bin/env bash
# start_video.sh — stream USB webcam over RTP/H.264 to the GCS
set -euo pipefail
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
# shellcheck disable=SC1091
source "$SCRIPT_DIR/video.env"
# Prevent multiple instances from racing for the same camera device.
LOCK_FILE="/tmp/start_video.lock"
exec 9>"$LOCK_FILE"
if ! flock -n 9; then
echo "Another start_video.sh instance is already running (lock: $LOCK_FILE)."
echo "If started by systemd, check: sudo systemctl status video"
exit 1
fi
# Wait for video device
for _ in {1..30}; do
[[ -e "$DEVICE" ]] && break
sleep 1
done
if [[ ! -e "$DEVICE" ]]; then
echo "Camera device not found: $DEVICE"
echo "Check USB camera connection and confirm device with: v4l2-ctl --list-devices"
exit 1
fi
if command -v fuser >/dev/null 2>&1 && fuser "$DEVICE" >/dev/null 2>&1; then
echo "Camera device is busy: $DEVICE"
echo "Process holding the device:"
fuser -v "$DEVICE" || true
echo "If this is your auto-start service, stop it before manual testing:"
echo " sudo systemctl stop video"
exit 1
fi
# Check if camera natively gives H.264 (most HP/Logitech UVC do at 720p)
FORMATS="$(v4l2-ctl -d "$DEVICE" --list-formats 2>/dev/null || true)"
if echo "$FORMATS" | grep -qi "H264"; then
echo "Using camera native H.264"
exec gst-launch-1.0 -v \
v4l2src device="$DEVICE" ! \
"video/x-h264,width=${WIDTH},height=${HEIGHT},framerate=${FPS}/1" ! \
h264parse config-interval=1 ! \
rtph264pay pt=96 config-interval=1 ! \
udpsink host="$GCS_IP" port="$GCS_PORT" sync=false
elif echo "$FORMATS" | grep -Eqi "MJPG|JPEG"; then
echo "Camera outputs MJPEG; decoding then encoding H.264"
exec gst-launch-1.0 -v \
v4l2src device="$DEVICE" ! \
"image/jpeg,width=${WIDTH},height=${HEIGHT},framerate=${FPS}/1" ! \
jpegdec ! \
videoconvert ! \
x264enc tune=zerolatency bitrate="$BITRATE" speed-preset=ultrafast key-int-max=25 ! \
rtph264pay pt=96 config-interval=1 ! \
udpsink host="$GCS_IP" port="$GCS_PORT" sync=false
else
echo "Camera does not output H.264/MJPEG with requested caps; using generic fallback"
exec gst-launch-1.0 -v \
v4l2src device="$DEVICE" ! \
videoconvert ! \
videoscale ! \
videorate ! \
"video/x-raw,width=${WIDTH},height=${HEIGHT},framerate=${FPS}/1" ! \
videoconvert ! \
x264enc tune=zerolatency bitrate="$BITRATE" speed-preset=ultrafast key-int-max=25 ! \
rtph264pay pt=96 config-interval=1 ! \
udpsink host="$GCS_IP" port="$GCS_PORT" sync=false
fi
video.env
# video.env — RTP video stream config
# Edit GCS_IP to your laptop's Tailscale IP (run `tailscale ip -4` on laptop)
GCS_IP=<GCS_IP>
GCS_PORT=5600
DEVICE=/dev/video0
WIDTH=1280
HEIGHT=720
FPS=25
BITRATE=1500 # kbit/s
joystick_bridge.py
"""
joystick_bridge.py — send RC_CHANNELS_OVERRIDE from a USB joystick to the drone.
This is an OPTIONAL alternative to the joystick support built into Mission
Planner. It connects directly to MAVProxy's UDP port (default 14551) over the
Tailscale tunnel and pushes 50 Hz RC overrides.
Channel mapping (typical mode-2 transmitter):
Ch1 Roll <- right stick X
Ch2 Pitch <- right stick Y (inverted)
Ch3 Throttle <- left stick Y (inverted, mapped 0..1 -> 1000..2000)
Ch4 Yaw <- left stick X
Ch5 Mode <- button A/B/X/Y switch (Stabilize/AltHold/Loiter/RTL)
Ch7 Arm/Disarm hold START button 1 s
Requires:
pip install pygame pymavlink
"""
from __future__ import annotations
import argparse
import time
import sys
try:
import pygame
except ImportError:
sys.exit("Please install dependencies: pip install pygame pymavlink")
from pymavlink import mavutil
# ---------- helpers ----------
def axis_to_pwm(value: float, reverse: bool = False) -> int:
"""Map a joystick axis (-1.0 .. 1.0) to RC PWM (1000..2000)."""
if reverse:
value = -value
value = max(-1.0, min(1.0, value))
return int(1500 + value * 500)
def throttle_to_pwm(value: float) -> int:
"""Left stick Y (-1=up, 1=down on most pads) -> 1000..2000."""
value = max(-1.0, min(1.0, -value)) # invert so up = high
return int(1000 + (value + 1.0) / 2.0 * 1000)
MODE_MAP = { # button index -> ArduCopter mode number
0: 0, # A -> STABILIZE
1: 2, # B -> ALT_HOLD
2: 5, # X -> LOITER
3: 6, # Y -> RTL
}
# ---------- main ----------
def main() -> int:
ap = argparse.ArgumentParser(description=__doc__)
ap.add_argument("--target", required=True,
help="MAVProxy endpoint, e.g. 100.64.0.5:14551")
ap.add_argument("--rate", type=float, default=50.0, help="Hz")
ap.add_argument("--source-system", type=int, default=255)
ap.add_argument("--source-component", type=int, default=190)
args = ap.parse_args()
pygame.init()
pygame.joystick.init()
if pygame.joystick.get_count() == 0:
print("No joystick detected.")
return 1
js = pygame.joystick.Joystick(0)
js.init()
print(f"Using joystick: {js.get_name()} axes={js.get_numaxes()} buttons={js.get_numbuttons()}")
print(f"Connecting to udpout:{args.target} ...")
mav = mavutil.mavlink_connection(
f"udpout:{args.target}",
source_system=args.source_system,
source_component=args.source_component,
)
# We do NOT wait_heartbeat() — joystick should work even before vehicle responds.
mode_pwm = 1000 # Ch5
arm_pwm = 1000 # Ch7
last_arm_press = 0.0
period = 1.0 / args.rate
print("Streaming RC overrides. Ctrl+C to quit.")
try:
while True:
pygame.event.pump()
# ---- mode buttons ----
for btn, mode in MODE_MAP.items():
if btn < js.get_numbuttons() and js.get_button(btn):
# Map mode number to a PWM bucket on Ch5
mode_pwm = 1000 + mode * 100
# ---- arm / disarm hold ----
start_btn = 7
if start_btn < js.get_numbuttons() and js.get_button(start_btn):
if last_arm_press == 0:
last_arm_press = time.time()
elif time.time() - last_arm_press > 1.0:
arm_pwm = 2000 if arm_pwm < 1500 else 1000
last_arm_press = 0
print("Toggle arm ->", arm_pwm)
else:
last_arm_press = 0
# ---- axes ----
roll = axis_to_pwm(js.get_axis(2)) # right X
pitch = axis_to_pwm(js.get_axis(3), reverse=True) # right Y
yaw = axis_to_pwm(js.get_axis(0)) # left X
throttle = throttle_to_pwm(js.get_axis(1)) # left Y
mav.mav.rc_channels_override_send(
mav.target_system or 1,
mav.target_component or 1,
roll, pitch, throttle, yaw,
mode_pwm, 1500, arm_pwm, 1500,
)
time.sleep(period)
except KeyboardInterrupt:
# Release overrides (0 = release on ArduPilot)
mav.mav.rc_channels_override_send(
mav.target_system or 1, mav.target_component or 1,
0, 0, 0, 0, 0, 0, 0, 0,
)
print("\nReleased RC overrides. Bye.")
return 0
if __name__ == "__main__":
raise SystemExit(main())
requirement.txt
pymavlink>=2.4.41
pygame>=2.5.2
start_gcs.ps1
# start_gcs.ps1 — launch Mission Planner with the drone's Tailscale endpoint
# Usage: pwsh ./start_gcs.ps1 (or right-click -> Run with PowerShell)
# ====== EDIT THIS ======
$PiTailscaleName = "beast-pi" # tailscale hostname of the Pi
$MavTcpPort = 5760
$VideoUdpPort = 5600
# =======================
# Resolve Tailscale IP of the Pi
$tsExe = "C:\Program Files\Tailscale\tailscale.exe"
if (-not (Test-Path $tsExe)) {
Write-Error "Tailscale is not installed. Download from https://tailscale.com/download/windows"
exit 1
}
Write-Host "Resolving $PiTailscaleName via Tailscale..."
$piIp = & $tsExe ip -4 $PiTailscaleName 2>$null | Select-Object -First 1
if (-not $piIp) {
Write-Error "Could not resolve $PiTailscaleName. Check that:`n 1) Tailscale is running on this PC ('& $tsExe status')`n 2) The Pi is online and signed in to the same tailnet"
exit 1
}
Write-Host "Pi IP = $piIp"
# Locate Mission Planner
$mpCandidates = @(
"C:\Program Files (x86)\Mission Planner\MissionPlanner.exe",
"C:\Program Files\Mission Planner\MissionPlanner.exe",
"$env:LOCALAPPDATA\Programs\Mission Planner\MissionPlanner.exe"
)
$mp = $mpCandidates | Where-Object { Test-Path $_ } | Select-Object -First 1
if (-not $mp) {
Write-Error "Mission Planner not found. Install from https://ardupilot.org/planner/"
exit 1
}
# Connection string for Mission Planner CLI: tcp:<host>:<port>
$conn = "tcp:${piIp}:${MavTcpPort}"
Write-Host "Launching Mission Planner -> $conn"
Start-Process -FilePath $mp -ArgumentList @("/connect", $conn)
# Open the video viewer in a new window
$viewer = Join-Path $PSScriptRoot "view_video.ps1"
if (Test-Path $viewer) {
Start-Process pwsh -ArgumentList @("-NoExit", "-File", $viewer, "-Port", $VideoUdpPort)
}
Write-Host ""
Write-Host "All windows launched. In Mission Planner, click CONNECT if it isn't already connected."
view_video.ps1
# view_video.ps1 — receive the drone's RTP/H.264 stream
#
# Prerequisite: install GStreamer for Windows (MSVC 64-bit, complete)
# https://gstreamer.freedesktop.org/download/ (choose "runtime" + "development")
# Add C:\gstreamer\1.0\msvc_x86_64\bin to PATH.
param(
[int]$Port = 5600
)
$gst = "gst-launch-1.0.exe"
$gstCmd = Get-Command $gst -ErrorAction SilentlyContinue
if ($gstCmd) {
$gstPath = $gstCmd.Source
} else {
$candidates = @(
"$env:ProgramFiles\gstreamer\1.0\msvc_x86_64\bin\gst-launch-1.0.exe",
"$env:ProgramFiles\gstreamer\1.0\mingw_x86_64\bin\gst-launch-1.0.exe",
"$env:ProgramFiles(x86)\gstreamer\1.0\msvc_x86_64\bin\gst-launch-1.0.exe",
"$env:ProgramFiles(x86)\gstreamer\1.0\mingw_x86_64\bin\gst-launch-1.0.exe",
"C:\gstreamer\1.0\msvc_x86_64\bin\gst-launch-1.0.exe",
"C:\gstreamer\1.0\mingw_x86_64\bin\gst-launch-1.0.exe"
)
$gstPath = $candidates | Where-Object { Test-Path $_ } | Select-Object -First 1
if ($gstPath) {
$gstDir = Split-Path $gstPath -Parent
$env:Path = "$gstDir;$env:Path"
} else {
Write-Error "gst-launch-1.0 not found. Install GStreamer (MSVC 64-bit Runtime + Development), then re-run this script."
exit 1
}
}
Write-Host "Listening for RTP/H.264 on UDP $Port ..."
& $gstPath -v `
udpsrc port=$Port caps="application/x-rtp,media=video,clock-rate=90000,encoding-name=H264,payload=96" `
! rtpjitterbuffer latency=50 `
! rtph264depay `
! h264parse `
! avdec_h264 `
! videoconvert `
! autovideosink sync=false
| Symptom | Fix |
|---|---|
| No telemetry in Mission Planner | sudo systemctl status mavproxy on Pi. Check /dev/serial0 exists; check Pixhawk SERIAL2 parameters. |
| MAVProxy: “no link” | Swap Pixhawk TX<->RX wires (very common!). |
| 4G keeps dropping | Check signal at antenna location; lower video bitrate; verify usb0 has a 192.168.x.x IP. |
| Cannot reach Pi from laptop | Run tailscale status on both. Test pinging the Tailscale IP directly rather than hostname. |
| Video lags > 1 s | Lower the BITRATE/FPS inside video.env. Ensure GCS view command is running with sync=false. |
| Joystick has no effect | In Mission Planner enable Joystick OR use joystick_bridge.py, not both. |