I was able to solve this by running codex on the source tree and using the intent:
I’m running PX4 on a PilotPi (POSIX target) and trying to inject GPS using only a companion computer. The companion sends valid MAVLink HIL_GPS (previously GPS_INPUT) messages at 1 Hz over UDP (udpout:127.0.0.1:14556). MAVLink is in Onboard mode, MAV_PROTO_VER=2, MAV_USEHILGPS=1, fix_type ≥ 3, non-zero lat/lon, satellites > 0, and mavlink status confirms the messages are received with no loss. However, listener sensor_gps never publishes, vehicle_gps_position stays zero, and EKF2 does not fuse GNSS. No physical GPS is connected — the goal is to use only the companion computer as the GPS source via MAVLink. Please review the PilotPi configuration (PX4-Autopilot/pilotpi_mc.config) and PX4 POSIX build path (PX4-Autopilot) to determine why received HIL_GPS / GPS_INPUT messages are not resulting in sensor_gps publication. Create a python script to inject and send the mavlink messages to the PX4 mavlink listener.
The key issue was that PX4 receives the MAVLink packets, but only accepts HIL_GPS for publication to sensor_gps when sender sysid matches the PX4 MAV_SYS_ID (unless full HIL mode is enabled). Once I matched source_system to param MAV_SYS_ID (I’m using 1) sensor_gps and vehicle_gps_position started publishing and EKF2 fused GNSS. Before fixing source_system, MAVLink status showed packets received, but sensor_gps never published.
What I set in PX4 config:
param set MAV_USEHILGPS 1
param set MAV_PROTO_VER 2
param set SYS_HAS_GPS 1
param set EKF2_GPS_CTRL 1
mavlink start -x -u 14556 -r 2000000 -m onboard
Note HIL_GPS works here, GPS_INPUT was not handled in build and no external GPS driver is started.
This script below should do it, run using:
# mock
python3 hil_gps_mavlink.py --mavlink udpout:127.0.0.1:14556 --source-system 1 --source-component 190 --mock --debug
# real
python3 hil_gps_mavlink.py --mavlink udpout:127.0.0.1:14556 --source-system 1 --source-component 190 --serial /dev/ttyUSB0 --baud 115200 --rate-hz 5 --debug
And verify onboard that the MAV_SYS_ID is what your sending in –source-system, the value “1”.
param show MAV_SYS_ID
# => x MAV_SYS_ID [474,1028] : 1
listener sensor_gps
listener vehicle_gps_position
hil_gps_mavlink.py:
#!/usr/bin/env python3
"""
hil_gps_mavlink.py
Send MAVLink HIL_GPS to PX4 from either:
1) NMEA GGA over serial, or
2) Internal mock trajectory.
No NTRIP/RTCM functionality is included.
"""
import os
import time
import argparse
import math
import serial
from pymavlink import mavutil
os.environ["MAVLINK20"] = "1"
def parse_latlon(field, hemi):
if not field:
return None
deg_len = 2 if hemi in ("N", "S") else 3
deg = float(field[:deg_len])
minutes = float(field[deg_len:])
value = deg + minutes / 60.0
if hemi in ("S", "W"):
value = -value
return value
def send_hil_gps(mav, lat, lon, alt, fix_type, sats, hdop, debug=False):
time_usec = int(time.time() * 1e6)
mav.mav.hil_gps_send(
time_usec, # time_usec
fix_type, # fix_type
int(lat * 1e7), # lat
int(lon * 1e7), # lon
int(alt * 1000), # alt (mm)
int(hdop * 100), # eph (cm)
int(hdop * 100), # epv (cm)
0, # vel (cm/s)
0, # vn
0, # ve
0, # vd
0, # cog
sats, # satellites_visible
0, # id
0 # yaw
)
if debug:
print(
f"[HIL_GPS] fix={fix_type} sats={sats} "
f"lat={lat:.7f} lon={lon:.7f} alt={alt:.2f}"
)
def main():
parser = argparse.ArgumentParser()
parser.add_argument("--mavlink", default="udpout:127.0.0.1:14556")
parser.add_argument("--source-system", type=int, default=1,
help="Must match PX4 MAV_SYS_ID for HIL_GPS acceptance outside HIL mode.")
parser.add_argument("--source-component", type=int, default=190)
parser.add_argument("--serial", default="/dev/ttyUSB0")
parser.add_argument("--baud", type=int, default=115200)
parser.add_argument("--rate-hz", type=float, default=1.0,
help="Max HIL_GPS send rate in NMEA mode.")
parser.add_argument("--mock", action="store_true")
parser.add_argument("--mock-lat", type=float, default=37.7825)
parser.add_argument("--mock-lon", type=float, default=-122.4662)
parser.add_argument("--mock-alt", type=float, default=60.0)
parser.add_argument("--mock-speed", type=float, default=0.5,
help="Meters/sec eastward drift in mock mode.")
parser.add_argument("--debug", action="store_true")
args = parser.parse_args()
print("[INFO] Connecting MAVLink:", args.mavlink)
mav = mavutil.mavlink_connection(
args.mavlink,
source_system=args.source_system,
source_component=args.source_component,
dialect="common",
autoreconnect=True,
force_connected=True,
)
mav.mavlink20 = True
print("[INFO] MAVLink ready")
if args.mock:
print("[INFO] MOCK mode enabled")
lat = args.mock_lat
lon = args.mock_lon
alt = args.mock_alt
meters_per_deg_lon = 111320 * math.cos(math.radians(lat))
period_s = max(0.05, 1.0 / max(0.1, args.rate_hz))
while True:
lon += args.mock_speed * period_s / meters_per_deg_lon
send_hil_gps(
mav,
lat,
lon,
alt,
fix_type=3,
sats=12,
hdop=0.8,
debug=args.debug,
)
time.sleep(period_s)
print("[INFO] NMEA serial mode:", args.serial)
ser = serial.Serial(args.serial, args.baud, timeout=1)
min_interval = 1.0 / max(0.1, args.rate_hz)
last_send = 0.0
while True:
try:
line = ser.readline().decode(errors="ignore").strip()
if not line.startswith("$") or "GGA" not in line:
continue
parts = line.split(",")
if len(parts) < 10:
continue
lat = parse_latlon(parts[2], parts[3])
lon = parse_latlon(parts[4], parts[5])
fix_quality = int(parts[6]) if parts[6] else 0
sats = int(parts[7]) if parts[7] else 0
hdop = float(parts[8]) if parts[8] else 1.5
alt = float(parts[9]) if parts[9] else 0.0
if lat is None or lon is None:
continue
if fix_quality == 0:
fix_type = 0
elif fix_quality == 1:
fix_type = 3
elif fix_quality == 2:
fix_type = 4
elif fix_quality == 4:
fix_type = 5
elif fix_quality == 5:
fix_type = 6
else:
fix_type = 3
now = time.time()
if now - last_send < min_interval:
continue
last_send = now
send_hil_gps(
mav,
lat,
lon,
alt,
fix_type,
sats,
hdop,
args.debug,
)
except Exception as exc:
print("[ERROR]", exc)
time.sleep(1)
if __name__ == "__main__":
main()