From 528ec1e61f19b9d73d23364762d7f8c371f5f34e Mon Sep 17 00:00:00 2001 From: default Date: Wed, 7 Jan 2026 20:21:56 +0000 Subject: [PATCH] fix: Update MAVLink connection string from UDP to TCP for SITL. --- config.py | 4 ++-- src/mavlink_bridge.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/config.py b/config.py index 582b205..535b2dd 100644 --- a/config.py +++ b/config.py @@ -156,8 +156,8 @@ MAVLINK = { "target_system": 1, "target_component": 1, - # Connection - "connection_string": "udpin:127.0.0.1:14550", + # Connection - SITL listens on TCP 5760 (shown as SERIAL0) + "connection_string": "tcp:127.0.0.1:5760", # Timeouts (seconds) "heartbeat_timeout": 5.0, diff --git a/src/mavlink_bridge.py b/src/mavlink_bridge.py index c894b13..da70724 100644 --- a/src/mavlink_bridge.py +++ b/src/mavlink_bridge.py @@ -64,7 +64,7 @@ class MAVLinkCommander: Provides methods for arming, disarming, mode changes, and flight commands. """ - def __init__(self, connection_string: str = "udpin:127.0.0.1:14550"): + def __init__(self, connection_string: str = "tcp:127.0.0.1:5760"): """ Initialize MAVLink commander.