MAVSDK-Python Timeout error only when running on real quadcopter

I’m trying to arm my drone without GPS data and I believe it’s possible through setting the parameter COM_ARM_WO_GPS to 1. I have tried this on SITL using make px4_sitl gz_x500 and setting SIM_GPS_USED to 0 (Hence no GPS data) and have no problem.

However, when i try this using my drone i get this error

  • Arming
    Traceback (most recent call last):
    File “//v2.py", line 164, in
    asyncio.run(run())
    File “/usr/lib/python3.12/asyncio/runners.py”, line 194, in run
    return runner.run(main)
    ^^^^^^^^^^^^^^^^
    File “/usr/lib/python3.12/asyncio/runners.py”, line 118, in run
    return self._loop.run_until_complete(task)
    ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
    File “/usr/lib/python3.12/asyncio/base_events.py”, line 687, in run_until_complete
    return future.result()
    ^^^^^^^^^^^^^^^
    File "/
    /v2.py”, line 126, in run
    await drone.action.arm()
    File “/**/action.py”, line 336, in arm
    raise ActionError(result, “arm()”)
    mavsdk.action.ActionError: TIMEOUT: ‘Timeout’; origin: arm(); params: ()

I’m using this code for testing

#!/usr/bin/env python3
import asyncio
import sys
import termios
import tty

from mavsdk import System
from mavsdk.offboard import OffboardError, VelocityBodyYawspeed, AttitudeRate

# --- Configuration (unchanged) ---
STEP_V     = 0.5
STEP_VZ    = 0.2
STEP_YAW   = 10.0
MAX_V      = 5.0
MAX_VZ     = 2.0
MAX_YAW    = 90.0

KEY_BINDINGS = {
    "w": ("vx",  STEP_V),
    "s": ("vx", -STEP_V),
    "a": ("vy", -STEP_V),
    "d": ("vy",  STEP_V),
    "r": ("vz", -STEP_VZ),
    "f": ("vz",  STEP_VZ),
    "q": ("yawspeed", -STEP_YAW),
    "e": ("yawspeed",  STEP_YAW),
    " ": "stop",
    "x": "exit",
}

def get_key():
    fd = sys.stdin.fileno()
    old = termios.tcgetattr(fd)
    try:
        tty.setraw(fd)
        ch = sys.stdin.read(1)
    finally:
        termios.tcsetattr(fd, termios.TCSADRAIN, old)
    return ch

async def teleop_loop(drone: System):
    vx = vy = vz = yawspeed = 0.0
    print("Use W/A/S/D to move, R/F up/down, Q/E yaw, Space to stop, X to exit")
    while True:
        key = await asyncio.get_event_loop().run_in_executor(None, get_key)
        action = KEY_BINDINGS.get(key.lower())
        if not action:
            continue

        if action == "stop":
            vx = vy = vz = yawspeed = 0.0
        elif action == "exit":
            print("-- Exiting teleop loop")
            break
        else:
            field, delta = action
            if field == "vx":
                vx = max(-MAX_V, min(MAX_V, vx + delta))
            elif field == "vy":
                vy = max(-MAX_V, min(MAX_V, vy + delta))
            elif field == "vz":
                vz = max(-MAX_VZ, min(MAX_VZ, vz + delta))
            elif field == "yawspeed":
                yawspeed = max(-MAX_YAW, min(MAX_YAW, yawspeed + delta))

        print(f"Vel→ vx={vx:.2f}, vy={vy:.2f}, vz={vz:.2f}, yaw_spd={yawspeed:.1f}°/s", end="\r")
        await drone.offboard.set_velocity_body(VelocityBodyYawspeed(vx, vy, vz, yawspeed))
        await asyncio.sleep(0.05)

async def wait_for_position_ok(drone: System):
    """Returns once we see a good global position & home."""
    async for health in drone.telemetry.health():
        if health.is_global_position_ok and health.is_home_position_ok:
            return

async def run():
    drone = System()
    # try connecting...
    for port in ["/dev/ttyAMA0", "/dev/ttyAMA1", "/dev/ttyAMA2"]:
        try:
            print(f"Trying to connect to {port}...")
            await drone.connect(system_address=f"serial://{port}:57600")
            print(f"✔ Connected to {port}")
            break
        except Exception as e:
            print(f"✘ {port}: {e}")
    else:
        print("✘ Could not connect to any port. Exiting.")
        return

    print("Waiting for drone to connect…")
    async for state in drone.core.connection_state():
        if state.is_connected:
            print("✔ Drone connected")
            break

    # 1) Attempt to get position fix, but only wait 10 s
    got_pos = True
    try:
        print("Waiting up to 10 s for position fix…")
        await asyncio.wait_for(wait_for_position_ok(drone), timeout=10.0)
        print("✔ Position OK")
    except asyncio.TimeoutError:
        print("⚠ No position fix in 10 s → test mode")
        got_pos = False

    # 2) Branch on whether we got a fix
    if got_pos:
        # prompt user if they want full offboard
        resp = await asyncio.get_event_loop().run_in_executor(
            None,
            input,
            "Global position OK. Proceed with offboard control? (y/N): "
        )
        if resp.strip().lower() != 'y':
            print("User chose NOT to proceed → arming only, then exit.")
            await drone.action.arm()
            return

    for i in range(100):
        await drone.offboard.set_attitude_rate(AttitudeRate(0, 0, 0, 0))
    await drone.offboard.set_attitude_rate(AttitudeRate(0, 0, 0, 0))
    await drone.offboard.set_attitude_rate(AttitudeRate(0, 0, 0, 0))
    
    # 3) Arm the drone (both branches)
    print("-- Arming")
    await drone.action.arm()

    # 4) If we did get position *and* user wants offboard, kick in offboard + teleop
    if got_pos:
        print("-- Sending zero setpoint")
        await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0, 0, 0, 0))

        print("-- Starting offboard")
        try:
            await drone.offboard.start()
        except OffboardError as e:
            print(f"✘ Offboard start failed: {e._result.result}")
            await drone.action.disarm()
            return

        try:
            await teleop_loop(drone)
        finally:
            print("\n-- Stopping offboard")
            try:
                await drone.offboard.stop()
            except OffboardError as e:
                print(f"✘ Offboard stop failed: {e._result.result}")

            print("-- Landing…")
            await drone.action.land()
            async for in_air in drone.telemetry.in_air():
                if not in_air:
                    print("✔ Landed")
                    break

            print("-- Disarming")
            await drone.action.disarm()
    else:
        # no position fix ⇒ we’re in test‐only mode; leave it armed for manual testing
        print("Test mode: drone armed but offboard NOT started. Exiting.")

if __name__ == "__main__":
    asyncio.run(run())

I have seen post that says they consistently getting timeout and that’s solved by solving the connectivity issue. But in my case the connection test (connection_state variable check) result is good so I doubt it’s a connectivity issue

What can i address so that I won’t get that error again?

You need to get output from the mavsdk_server.

You can either run the server separately like it is described here:

Or you can enable logging by adding this to the beginning of the file:

import logging
logging.basicConfig(level=logging.DEBUG) # Enable DEBUG logs

That might tell you more about what is going on.

Thanks for the pointer!
I have tried to see the logs and it’s consistently reporting REQUEST_MESSAGE query didn’t reply.
I have tried running the mavsdk_server through mavsdk_router (i also need it to report gcs) and the gcs says it’s not responding to specific request (i guess it’s the same as what the debug log says). I then think maybe it’s caused by faulty serial port, but even when switching the telemetry port with one that’s i plug elrs receiver it’s still not working

I’m still trying and found that i can use the micro usb of my fc (it’s cube orange plus, in case it’s important to know) for connecting the mavlink communication. And surprisingly GCS didn’t report any error in terms of the comms (using udp), but my python code still reporting the same issue

Do you have any suggestion what to check next? I’m now a bit lost since everything doesn’t make any sense…

Anyway, here’s the logs

DEBUG:mavsdk.system:[02:57:16|Info ] Waiting to discover system on udp://:14552... (connection_initiator.h:20)
DEBUG:mavsdk.system:[02:57:16|Warn ] Connection using udp:// is deprecated, please use udpin:// or udpout:// (cli_arg.cpp:28)
DEBUG:mavsdk.system:[02:57:16|Info ] New system on: 127.0.0.1:48026 (with system ID: 1) (udp_connection.cpp:206)
DEBUG:mavsdk.system:[02:57:16|Debug] New system ID: 1 Comp ID: 1 (mavsdk_impl.cpp:730)
DEBUG:mavsdk.system:[02:57:16|Debug] Component Autopilot (1) added. (system_impl.cpp:377)
DEBUG:mavsdk.system:[02:57:17|Warn ] Vehicle type changed (new type: 2, old type: 0) (system_impl.cpp:217)
DEBUG:mavsdk.system:[02:57:17|Debug] Discovered 1 component(s) (system_impl.cpp:497)
DEBUG:mavsdk.system:[02:57:17|Debug] Request message 148 using REQUEST_MESSAGE (mavlink_request_message.cpp:78)
DEBUG:mavsdk.system:[02:57:17|Info ] System discovered (connection_initiator.h:62)
DEBUG:mavsdk.system:[02:57:17|Info ] Server started (grpc_server.cpp:173)
DEBUG:mavsdk.system:[02:57:17|Info ] Server set to listen on 0.0.0.0:50051 (grpc_server.cpp:174)
DEBUG:mavsdk.system:[02:57:17|Debug] Request message 242 using REQUEST_MESSAGE (mavlink_request_message.cpp:78)
DEBUG:mavsdk.system:[02:57:17|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:17|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 1) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:17|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 2) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:17|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:17|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 3) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:17|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 4) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:19|Debug] Request message 242 using REQUEST_MESSAGE (mavlink_request_message.cpp:78)
DEBUG:mavsdk.system:[02:57:19|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:19|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 1) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:19|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 2) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:19|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:19|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 3) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:19|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 4) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:21|Debug] Request message 242 using REQUEST_MESSAGE (mavlink_request_message.cpp:78)
DEBUG:mavsdk.system:[02:57:21|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:21|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 1) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:21|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 2) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:21|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:21|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 3) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:21|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 4) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:23|Debug] Request message 242 using REQUEST_MESSAGE (mavlink_request_message.cpp:78)
DEBUG:mavsdk.system:[02:57:23|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:23|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 1) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:23|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 2) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:23|Info ] Try old command (mavlink_request_message.cpp:98)
DEBUG:mavsdk.system:[02:57:23|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 3) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:23|Warn ] Request message 242 again using REQUEST_MESSAGE (retries: 4) (mavlink_request_message.cpp:75)
DEBUG:mavsdk.system:[02:57:25|Debug] Request message 242 using REQUEST_MESSAGE (mavlink_request_message.cpp:78)

Sorry I just found out the request message is for retrieving home gps location. And I’m testing it indoors so it’s not going to work.
I want it to run without gps so i guess i will consider it solved. Many thanks btw !

If QGC also struggles to get a response, I would suspect something with the communication or the mavlink-router setup is wrong.