LD-PAY-004  ·  v1.0.0  ·  published  ·  2026-03-30  ·  CC BY-SA 4.0
docs  /  payloads  /  "libdrone — LCM-1 Payload: Compute Module (Pi Zero 2W)"

About

Complete specification for the LCM-1 — libdrone Compute Module, revision 1. The LCM-1 is an optional payload that fits into the Pi bay above the Backplane on any libdrone platform. It houses a Raspberry Pi Zero 2W connected directly to the flight controller via a dedicated companion UART, powered from a dedicated battery rail buck converter independent of the FC BEC.

The LCM-1 is not a sensor. It is not a camera. It is the intelligence layer that aggregates flight data, sensor readings, and FC telemetry — and decides what is worth transmitting to the ground operator and when.

This document is written for someone who wants to understand, build, and operate the LCM-1. You do not need to read any other libdrone documentation first — everything required is here.


[1] WHAT THE LCM-1 DOES

Commercial drone platforms give operators a live video feed and basic telemetry. Position. Battery. Flight mode. The operator sees the drone. They do not see what the drone is sensing.

The LCM-1 changes this. It sits on the drone and watches everything:

  • Flight state from the FC via companion UART: GPS position, altitude, attitude, battery voltage, flight mode, RC switch states
  • Sensor readings from the payload above it via WiFi: PM2.5, CO2, radiation, temperature — whatever sensor is fitted
  • History of all of the above: what it was five seconds ago, thirty seconds ago, five minutes ago

From this complete picture, it applies logic. Not just forwarding data — making decisions about what matters:

PM2.5 just spiked from 12 to 67 µg/m³ while at 45m AGL heading NE.
This is significant. Transmit a single alert with position, value, and context.
PM2.5 has been stable at 14 µg/m³ for the last 30 seconds.
Nothing to report. Stay quiet.

The filtered output travels through the existing ELRS radio link to the TX16S transmitter. The TX16S WiFi backpack serves it to the operator's tablet. QGroundControl displays live position on OpenStreetMap with sensor events pinned at the GPS coordinates where they occurred.

No additional radio. No cellular. No cloud. No subscription. The existing control link carries the intelligence layer's output alongside RC commands and standard telemetry. It costs nothing extra in bandwidth for quiet missions. It delivers exactly the right information when conditions change.


[2] WHY THIS MATTERS

What closed platforms offer

DJI Enterprise, Pilotix, and VC-backed commercial platforms offer: - Proprietary payload interfaces (NDA-gated, expensive to enter) - Telemetry forwarded verbatim at fixed rates - Cloud-dependent data pipelines - No access to raw FC state from third-party compute

The operator gets a stream of numbers. What those numbers mean in context — is this reading significant given current altitude, wind direction, and recent history? — is left to the human.

What the LCM-1 adds

The LCM-1 is the first component in the libdrone stack that has opinions. It reads the same data the FC has and the same data the sensor has, and it applies domain logic to decide what to surface and when.

This is not something that can be added to a closed platform without access to the FC's internal state. It requires the companion UART — the direct FC-to-compute link that libdrone's open architecture makes available by design.

The LCM-1 is possible because libdrone is open. It is useful because sensor data without context is noise.


[3] PHYSICAL INTERFACE

3.1 Pi Bay

The Pi bay is a 6mm PETG tray printed as part of the standard backplane assembly on every libdrone build. It sits above the Backplane, raising the payload mast boss pad surface by 6mm. Every libdrone is Pi-ready.

Parameter Value
Internal width 72mm
Internal length 38mm
Internal height 6mm
Wall thickness 2mm
Pi standoff spacing X 58mm
Pi standoff spacing Y 23mm
Standoff thread M2.5
Harness entry slot 8mm JST-SH

When LCM-1 is not fitted: printed cover plate. Zero functional penalty. When LCM-1 is fitted: Pi Zero 2W on M2.5 × 5mm standoffs, companion harness plugged, buck converter powered.

3.2 Companion Harness

Pre-wired during drone build. 4-wire JST-SH loom from FC UART6 through the Platform signal channel to the Pi bay base connector.

Pin Signal Direction Notes
1 5V_COMP Buck → Pi From dedicated XL4016 buck, NOT FC BEC
2 GND Common ground, star topology
3 FC_TX FC → Pi UART6 TX — MAVLink2 or MSP at 921600 baud
4 FC_RX Pi → FC UART6 RX — return path

Critical: FC UART6 is permanently reserved as COMPANION on all libdrone platforms. Never reassign it. The companion harness is pre-wired on every build.

3.3 Power

The Pi Zero 2W is powered from a dedicated XL4016 buck converter tapped from the main battery rail — the same tap logic as the VTX XL4015. Input: 6S battery (21–25V). Output: 5.1V regulated. Minimum 1A.

This is independent of the FC BEC. The FC BEC is rated 2A continuous and is already serving the receiver, GPS, fan, and payload. The Pi's 200mA typical draw (400mA peak at boot) does not affect the BEC budget.

3.4 GX12 Connection

The LCM-1 does not use the GX12 connectors for its own operation. It connects to the drone via the companion harness only.

The GX12 connectors A and B remain the payload interface — they connect to whatever sensor or camera payload sits above the LCM-1 in the mast stack. The Pi reads sensor data from that payload via WiFi, not via the GX12.

[ Sensor payload — SEN66, Geiger, thermal, etc. ]
         ↕ WiFi (payload ESP32-S3 → Pi hotspot)
   [ LCM-1 / Pi Zero 2W in Pi bay ]
         ↕ Companion UART (UART6, 921600 baud)
   [ Flight Controller (FC) ]
         ↕ GX12-A and GX12-B
   [ GX12 connectors → sensor payload above ]

The GX12 is never in the Pi's signal path. The Pi is a parallel intelligence layer, not a bridge.


[4] WHAT THE PI SEES

Via the companion UART at 921600 baud, the Pi receives the FC's full internal state as a continuous stream:

Betaflight (Pro, Core): MSP protocol. Pi polls for attitude, GPS, battery, RC channel states, flight mode. Poll rate: 2–5Hz per message type.

ArduPilot (Ghost, Bandit): MAVLink2 protocol. FC streams automatically. Pi subscribes to message types and rates it needs.

Data Source Update rate
GPS position (lat/lon/alt) FC UART6 5Hz
Attitude (roll/pitch/yaw) FC UART6 10Hz
Battery voltage + current FC UART6 2Hz
Flight mode + armed state FC UART6 2Hz
RC channel states (AUX switches) FC UART6 5Hz
Barometric altitude FC UART6 5Hz
Compass heading FC UART6 5Hz

Via WiFi (payload ESP32-S3 connects to Pi hotspot):

Data Source Update rate
All sensor channels Payload ESP32-S3 1–2Hz
Payload status Payload ESP32-S3 1Hz

[5] THRESHOLD LOGIC — THE INTELLIGENCE LAYER

The LCM-1's primary function is deciding what to transmit. Raw data stays on the SD card. Meaningful events go to the ground operator.

5.1 Default threshold table

THRESHOLDS = {
    'PM25':      5.0,    # µg/m³  — transmit if changes by more than this
    'PM10':     10.0,    # µg/m³
    'CO2':      25.0,    # ppm
    'VOC':      10.0,    # index
    'NOX':      10.0,    # index
    'TEMP':      2.0,    # °C
    'RAD':       0.05,   # µSv/h  — tighter: any meaningful change
}

HEARTBEAT_INTERVAL = 30   # seconds — always send something
ALTITUDE_MIN_M     = 20   # metres — ignore readings below this (ground contamination)

5.2 Transmission logic

def should_transmit(key, new_value, altitude_m):
    # Never transmit below minimum altitude
    if altitude_m < ALTITUDE_MIN_M:
        return False

    now = time.time()
    prev = last_sent.get(key, {'value': None, 'time': 0})

    # Always transmit if no previous value
    if prev['value'] is None:
        return True

    delta = abs(new_value - prev['value'])
    age   = now - prev['time']

    # Transmit on threshold crossing OR heartbeat interval
    return delta > THRESHOLDS.get(key, float('inf')) \
        or age   > HEARTBEAT_INTERVAL

5.3 Contextual alert construction

When a threshold is crossed, the Pi builds a single alert string combining all relevant context:

"PM2.5 spike +460% | 67 µg/m³ | 50.1234,14.5678 | 45m AGL | heading NE"

This string is transmitted as a MAVLink STATUSTEXT message. QGroundControl displays it as a map notification pinned to the GPS coordinates.

The operator sees one meaningful event rather than watching a number climb across 30 consecutive 2Hz updates.

5.4 Cross-sensor logic

The Pi can apply rules that span flight state and sensor data — something no ESP32-S3 payload can do because it lacks FC telemetry:

# Only flag radiation when not in descent — prop wash contaminates during descent
if not is_descending() and radiation > THRESHOLDS['RAD']:
    transmit_alert('RAD', radiation)

# Only log PM data above minimum altitude — ground readings not relevant to aerial survey
if altitude_m > ALTITUDE_MIN_M:
    log_and_maybe_transmit('PM25', pm25)

# Infer approximate wind direction from heading vs track over ground
wind_direction = infer_wind(heading, ground_track, ground_speed)

5.5 Bandwidth budget

ELRS at 100Hz with 1:2 telemetry ratio provides ~3,200 bytes/second uplink. FC telemetry consumes ~650 bytes/second at standard rates. Available for LCM-1 payload data: ~2,550 bytes/second.

Mode LCM-1 bandwidth use % of available
Quiet airspace (no thresholds) ~15 bytes/sec (heartbeat) <1%
Active survey (some crossings) ~100 bytes/sec 4%
Alert burst (multiple changes) ~300 bytes/sec 12%
Average over typical mission ~30 bytes/sec 1.2%

The existing radio link has ample headroom. No link saturation at any realistic sensor update rate.


[6] GROUND STATION OUTPUT

6.1 QGroundControl via ELRS WiFi Backpack

The TX16S WiFi backpack (RadioMaster ELRS Backpack, ~€15) clips onto the TX16S internal ELRS module bay. It creates a local WiFi hotspot. QGroundControl connects via UDP port 14550.

The operator's tablet receives: - Live aircraft position on OpenStreetMap - Altitude, speed, heading, battery - All LCM-1 STATUSTEXT alerts pinned to GPS coordinates - NAMED_VALUE_FLOAT sensor readings in the telemetry panel

No internet required. No cloud. No subscription. The TX16S in the pilot's hands is the ground station hub.

6.2 REST API (local WiFi)

The LCM-1 runs a lightweight Flask REST API on its WiFi hotspot (SSID: libdrone-[serial], IP: 192.168.4.1):

Endpoint Method Returns
/telemetry GET Full JSON: GPS, attitude, battery, all sensor channels
/alerts GET Last 20 threshold crossing events with timestamps
/status GET Pi uptime, FC link status, payload link status
/sensors GET Latest sensor readings with units
/config GET/POST Read or update threshold values

Any device on the WiFi hotspot — tablet, laptop, phone — can query these endpoints directly without QGroundControl.

6.3 Fused log file

The LCM-1 writes a single fused log to its SD card (or the payload ESP32-S3 SD card via WiFi sync):

timestamp,lat,lon,alt_m,heading,battery_v,PM25,CO2,VOC,NOX,TEMP,RH,alert
2026-03-30T09:14:23Z,50.123456,14.456789,45.2,237,23.8,14.2,412,98,12,18.4,67.1,
2026-03-30T09:14:24Z,50.123401,14.456812,45.5,238,23.8,14.1,411,98,12,18.4,67.2,
2026-03-30T09:14:55Z,50.122890,14.457102,44.8,241,23.6,67.3,418,103,13,18.6,66.8,ALERT:PM25_SPIKE

Flight state and sensor readings in one file, one timestamp, already aligned. No post-processing to correlate two separate log files. The alert column marks threshold events for easy filtering.


[7] BUILD GUIDE

7.1 Hardware

Component Part Source Est. cost
Compute Raspberry Pi Zero 2W (with pre-soldered headers) rpilocator.com / official reseller ~€15
Buck converter XL4016 mini 5V 3A AliExpress ~€2
Companion cable JST-SH 4-pin 150mm ×2 AliExpress ~€1
Standoffs M2.5 × 5mm brass ×4 + M2.5 nuts AliExpress / hardware stock ~€1
Ground backpack ELRS WiFi Backpack (TX16S internal module) RadioMaster / AliExpress ~€15
Total ~€34

7.2 OS Setup

Image: Raspberry Pi OS Lite 64-bit (headless — no desktop)

Critical — disable Bluetooth / enable UART:

In /boot/config.txt:

enable_uart=1
dtoverlay=disable-bt

In /boot/cmdline.txt — remove console=serial0,115200 if present.

The Pi Zero 2W maps its primary hardware UART (used by GPIO pins 8/10) to Bluetooth by default. Without this step, the companion UART will not work. This is the single most common failure mode. Do it first.

Configure in Raspberry Pi Imager before flashing: - Hostname: libdrone-[serial] - SSH: enabled - Username: pi — document password in build log - WiFi: set to bench network for initial setup only

7.3 Python dependencies

sudo apt update && sudo apt install -y python3-pip
pip3 install pymavlink flask pyserial

7.4 WiFi hotspot

Install hostapd and dnsmasq:

sudo apt install -y hostapd dnsmasq
sudo systemctl unmask hostapd

/etc/hostapd/hostapd.conf:

interface=wlan0
ssid=libdrone-[serial]
wpa_passphrase=libdrone2046
hw_mode=g
channel=6
wpa=2
wpa_key_mgmt=WPA-PSK
wpa_pairwise=CCMP

/etc/dnsmasq.conf — add:

interface=wlan0
dhcp-range=192.168.4.2,192.168.4.20,255.255.255.0,24h

/etc/dhcpcd.conf — add:

interface wlan0
static ip_address=192.168.4.1/24
nohook wpa_supplicant

7.5 Broker script and autostart

Place the libdrone broker at /home/pi/libdrone_broker.py. Full reference implementation: build/LD_-_Software_v246.md §Pi Zero 2W Setup.

Systemd service /etc/systemd/system/libdrone.service:

[Unit]
Description=libdrone LCM-1 broker
After=network.target

[Service]
ExecStart=/usr/bin/python3 /home/pi/libdrone_broker.py
Restart=always
RestartSec=5
User=pi

[Install]
WantedBy=multi-user.target

Enable:

sudo systemctl enable libdrone
sudo systemctl start libdrone

7.6 Physical installation

  1. Solder XL4016 buck — input from battery rail tap, output 5.1V verified on bench supply before connecting to Pi
  2. Mount Pi Zero 2W on M2.5 × 5mm standoffs in Pi bay (58×23mm spacing)
  3. Plug JST-SH companion cable:
  4. Pi GPIO pin 4 (5V) → harness PIN 1
  5. Pi GPIO pin 6 (GND) → harness PIN 2
  6. Pi GPIO pin 8 (UART TX) → harness PIN 3 (FC UART6 RX)
  7. Pi GPIO pin 10 (UART RX) → harness PIN 4 (FC UART6 TX)
  8. Verify no shorts before battery connection
  9. Install ELRS WiFi Backpack on TX16S internal module

[8] COMMISSIONING AND TEST

Follow WBS Phase 9 (steps 9.1–9.12) for the full commissioning sequence.

Quick verification checklist

[ ] Bluetooth disabled  /dev/ttyAMA0 exists and responds
[ ] Pi boots in <25 seconds from battery power
[ ] WiFi hotspot libdrone-[serial] visible on phone
[ ] REST API: curl 192.168.4.1/status returns {"fc_link": true, ...}
[ ] FC telemetry: curl 192.168.4.1/telemetry shows live GPS lat/lon
[ ] Threshold filtering confirmed: no transmission on stable readings
[ ] Alert generated on simulated spike (modify threshold config temporarily)
[ ] ELRS WiFi Backpack firmware matches TX16S ELRS firmware version
[ ] QGroundControl connects to backpack UDP 14550  live map position
[ ] 10-minute flight: no Pi reboot, lockup, or brown-out
[ ] AUW measured and documented  EASA category confirmed unchanged

[9] WEIGHT AND CG

Component Weight
Raspberry Pi Zero 2W 11g
XL4016 buck converter 5g
JST-SH cable + wiring 2g
M2.5 standoffs ×4 + nuts 1g
LCM-1 total ~19g

Pi bay tray (always present, empty or fitted): ~4g

CG impact: Pi bay sits at Y = −66mm (electronics zone) — near CG. Impact on CG is minimal. Verify with payload fitted. Betaflight trim adjustment may be needed — document in flight log.

EASA category: with SEN66 payload + LCM-1, AUW ~879g — Open A2 ✓ (21g headroom). Measure actual AUW after build. Document in Hardware doc.


[10] WHAT THE LCM-1 IS NOT

Not a bridge between GX12 and payload. The GX12 connectors remain the direct payload interface. The Pi is a parallel observer, not a passthrough. Remove the LCM-1 and every payload continues to work identically.

Not a flight controller companion in the ArduPilot sense. The LCM-1 does not send navigation commands to the FC. It reads telemetry and sends status messages. It does not fly the drone.

Not always necessary. A simple sensor logging mission needs only the ESP32-S3 on the PSB-1. The LCM-1 earns its 19g when the mission requires contextual intelligence, live map overlay, or cross-sensor logic. Fit it when the mission justifies it.

Not a cloud dependency. Every function described in this document works in a field with no internet connectivity. The REST API, the WiFi hotspot, the QGroundControl connection via ELRS backpack — all local, all offline-capable.


[11] FUTURE DEVELOPMENT

Capability Notes
MAVLink command forwarding Pi sends waypoint commands to ArduPilot FC on Ghost/Bandit
OpenDroneMap pre-processing Pi buffers thermal images, begins processing before landing
RTL-SDR spectrum logging Pi runs spectrum analysis alongside sensor payload
Multi-payload fusion Two payloads simultaneously — Pi correlates their readings
LD-PAY-005 SW API Reference Formal API documentation for libdrone.py and LCM-1 REST

The LCM-1 is revision 1. As the platform matures and ArduPilot variants (Ghost, Bandit) mature alongside it, the companion computer role will deepen. The hardware and harness are designed to support that growth without modification to the drone body.


Revision History

Version Date Author Summary
1.0.0 2026-03-30 JS Initial release. Full LCM-1 specification: physical interface, Pi bay, companion harness, threshold logic, ground station output, build guide, commissioning, weight/CG.