From 492c64b5a324394e5a9b14d97f4d87579b1b21b1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 29 Jun 2025 13:01:04 +1200 Subject: [PATCH 1/3] README: update connection string --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 57d766c0..46e5c452 100644 --- a/README.md +++ b/README.md @@ -39,7 +39,7 @@ from mavsdk import System ... drone = System() -await drone.connect(system_address="udp://:14540") +await drone.connect(system_address="udpin://0.0.0.0:14540") ``` Note: `System()` takes two named parameters: `mavsdk_server_address` and `port`. When left empty, they default to `None` and `50051`, respectively, and `mavsdk_server -p 50051` is run by `await drone.connect()`. If `mavsdk_server_address` is set (e.g. to "localhost"), then `await drone.connect()` will not start the embedded `mavsdk_server` and will try to connect to a server running at this address. This is useful for platforms where `mavsdk_server` does not come embedded, for debugging purposes, and for running `mavsdk_server` in a place different than where the MAVSDK-Python script is run. From c37dff77469091a74b8c9b179cd0212d6cad947d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 29 Jun 2025 13:12:51 +1200 Subject: [PATCH 2/3] examples: use new connection syntax --- examples/all_params.py | 2 +- examples/calibration.py | 2 +- examples/camera.py | 2 +- examples/camera_params.py | 2 +- examples/do_orbit.py | 2 +- examples/failure_injection.py | 2 +- examples/firmware_version.py | 2 +- examples/follow_me_example.py | 2 +- examples/geofence.py | 2 +- examples/gimbal.py | 2 +- examples/goto.py | 2 +- examples/gripper.py | 2 +- examples/highres_imu.py | 2 +- examples/logfile_download.py | 2 +- examples/manual_control.py | 2 +- examples/mission.py | 2 +- examples/mission_import.py | 2 +- examples/mission_raw.py | 2 +- examples/offboard_attitude.py | 2 +- examples/offboard_from_csv/offboard_from_csv.py | 2 +- examples/offboard_position_ned.py | 2 +- examples/offboard_position_velocity_ned.py | 2 +- examples/offboard_velocity_body.py | 2 +- examples/offboard_velocity_ned.py | 2 +- examples/px4_ev_automation.py | 2 +- examples/px4_ev_automation_keyboard.py | 2 +- examples/send_status_message.py | 2 +- examples/shell.py | 2 +- examples/takeoff_and_land.py | 2 +- examples/telemetry.py | 2 +- examples/telemetry_flight_mode.py | 2 +- examples/telemetry_is_armed_is_in_air.py | 2 +- examples/telemetry_status_text.py | 2 +- examples/telemetry_takeoff_and_land.py | 2 +- examples/tune.py | 2 +- examples/upload_params.py | 2 +- examples/winch.py | 2 +- 37 files changed, 37 insertions(+), 37 deletions(-) diff --git a/examples/all_params.py b/examples/all_params.py index 353ae082..9fd2b5fc 100755 --- a/examples/all_params.py +++ b/examples/all_params.py @@ -7,7 +7,7 @@ async def run(): # Connect to the drone drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") # Get the list of parameters all_params = await drone.param.get_all_params() diff --git a/examples/calibration.py b/examples/calibration.py index eb8bb417..e43e9f8f 100755 --- a/examples/calibration.py +++ b/examples/calibration.py @@ -7,7 +7,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("-- Starting gyroscope calibration") async for progress_data in drone.calibration.calibrate_gyro(): diff --git a/examples/camera.py b/examples/camera.py index c027f36d..b8cb4b2d 100755 --- a/examples/camera.py +++ b/examples/camera.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/camera_params.py b/examples/camera_params.py index 5b3fc0e1..c4e35bef 100755 --- a/examples/camera_params.py +++ b/examples/camera_params.py @@ -22,7 +22,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") asyncio.ensure_future(observe_current_settings(drone)) asyncio.ensure_future(observe_camera_mode(drone)) diff --git a/examples/do_orbit.py b/examples/do_orbit.py index af0bdb90..d918f894 100755 --- a/examples/do_orbit.py +++ b/examples/do_orbit.py @@ -5,7 +5,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/failure_injection.py b/examples/failure_injection.py index 2cb18a02..348b966c 100755 --- a/examples/failure_injection.py +++ b/examples/failure_injection.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/firmware_version.py b/examples/firmware_version.py index 290b0d30..15d84fd7 100755 --- a/examples/firmware_version.py +++ b/examples/firmware_version.py @@ -6,7 +6,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/follow_me_example.py b/examples/follow_me_example.py index 6615eeab..7b9d7d43 100755 --- a/examples/follow_me_example.py +++ b/examples/follow_me_example.py @@ -25,7 +25,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/geofence.py b/examples/geofence.py index 12054d70..284815bb 100755 --- a/examples/geofence.py +++ b/examples/geofence.py @@ -21,7 +21,7 @@ async def run(): # Connect to the Simulation drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") # Wait for the drone to connect print("Waiting for drone to connect...") diff --git a/examples/gimbal.py b/examples/gimbal.py index 2325d048..b2cad3e8 100755 --- a/examples/gimbal.py +++ b/examples/gimbal.py @@ -33,7 +33,7 @@ async def fetch_gimbals(): async def run(): # Init the drone drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") gimbals = await get_gimbals(drone) diff --git a/examples/goto.py b/examples/goto.py index 01e3fc26..44c64a5d 100755 --- a/examples/goto.py +++ b/examples/goto.py @@ -6,7 +6,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/gripper.py b/examples/gripper.py index a6ecb172..ae78e682 100644 --- a/examples/gripper.py +++ b/examples/gripper.py @@ -6,7 +6,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/highres_imu.py b/examples/highres_imu.py index dce22fdf..59c45dbf 100644 --- a/examples/highres_imu.py +++ b/examples/highres_imu.py @@ -5,7 +5,7 @@ async def get_imu_data(): # Connect to the drone drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") # Wait for the drone to connect print("Waiting for drone to connect...") diff --git a/examples/logfile_download.py b/examples/logfile_download.py index a6b833ab..56935ca3 100755 --- a/examples/logfile_download.py +++ b/examples/logfile_download.py @@ -7,7 +7,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/manual_control.py b/examples/manual_control.py index f1a0c232..2db6cc0e 100755 --- a/examples/manual_control.py +++ b/examples/manual_control.py @@ -34,7 +34,7 @@ async def manual_controls(): """Main function to connect to the drone and input manual controls""" # Connect to the Simulation drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") # This waits till a mavlink based drone is connected print("Waiting for drone to connect...") diff --git a/examples/mission.py b/examples/mission.py index c80b7a2e..36a82e77 100755 --- a/examples/mission.py +++ b/examples/mission.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/mission_import.py b/examples/mission_import.py index 9fdf6795..9ea44578 100755 --- a/examples/mission_import.py +++ b/examples/mission_import.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/mission_raw.py b/examples/mission_raw.py index 00870ca8..c0c60e22 100755 --- a/examples/mission_raw.py +++ b/examples/mission_raw.py @@ -7,7 +7,7 @@ async def px4_connect_drone(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/offboard_attitude.py b/examples/offboard_attitude.py index 27e22024..49ee0674 100755 --- a/examples/offboard_attitude.py +++ b/examples/offboard_attitude.py @@ -15,7 +15,7 @@ async def run(): """ Does Offboard control using attitude commands. """ drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/offboard_from_csv/offboard_from_csv.py b/examples/offboard_from_csv/offboard_from_csv.py index f180c93a..83be885a 100644 --- a/examples/offboard_from_csv/offboard_from_csv.py +++ b/examples/offboard_from_csv/offboard_from_csv.py @@ -108,7 +108,7 @@ async def run(): # Connect to the drone drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") # Wait for the drone to connect print("Waiting for drone to connect...") diff --git a/examples/offboard_position_ned.py b/examples/offboard_position_ned.py index 9e495c3e..94bedaa4 100755 --- a/examples/offboard_position_ned.py +++ b/examples/offboard_position_ned.py @@ -18,7 +18,7 @@ async def run(): """ Does Offboard control using position NED coordinates. """ drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/offboard_position_velocity_ned.py b/examples/offboard_position_velocity_ned.py index f8f3b6ca..a2eb7fff 100755 --- a/examples/offboard_position_velocity_ned.py +++ b/examples/offboard_position_velocity_ned.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/offboard_velocity_body.py b/examples/offboard_velocity_body.py index b4886ec5..4e154330 100755 --- a/examples/offboard_velocity_body.py +++ b/examples/offboard_velocity_body.py @@ -11,7 +11,7 @@ async def run(): """ Does Offboard control using velocity body coordinates. """ drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/offboard_velocity_ned.py b/examples/offboard_velocity_ned.py index 716af9df..bc729b0d 100755 --- a/examples/offboard_velocity_ned.py +++ b/examples/offboard_velocity_ned.py @@ -11,7 +11,7 @@ async def run(): """ Does Offboard control using velocity NED coordinates. """ drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/px4_ev_automation.py b/examples/px4_ev_automation.py index f2067a5f..d1091d23 100644 --- a/examples/px4_ev_automation.py +++ b/examples/px4_ev_automation.py @@ -52,7 +52,7 @@ async def print_mode(drone): async def main(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/px4_ev_automation_keyboard.py b/examples/px4_ev_automation_keyboard.py index 9d530f60..fbe3c77c 100644 --- a/examples/px4_ev_automation_keyboard.py +++ b/examples/px4_ev_automation_keyboard.py @@ -32,7 +32,7 @@ async def set_params(system, params, announcement): async def main(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/send_status_message.py b/examples/send_status_message.py index 6a562447..7d073246 100755 --- a/examples/send_status_message.py +++ b/examples/send_status_message.py @@ -19,7 +19,7 @@ async def run(): drone = System(sysid=1) - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/shell.py b/examples/shell.py index f9a1b35b..296c0efd 100755 --- a/examples/shell.py +++ b/examples/shell.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") asyncio.ensure_future(observe_shell(drone)) diff --git a/examples/takeoff_and_land.py b/examples/takeoff_and_land.py index 2ad99aa5..622765bb 100755 --- a/examples/takeoff_and_land.py +++ b/examples/takeoff_and_land.py @@ -7,7 +7,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") status_text_task = asyncio.ensure_future(print_status_text(drone)) diff --git a/examples/telemetry.py b/examples/telemetry.py index 7fa831f7..3568d0e8 100755 --- a/examples/telemetry.py +++ b/examples/telemetry.py @@ -7,7 +7,7 @@ async def run(): # Init the drone drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") # Start the tasks asyncio.ensure_future(print_battery(drone)) diff --git a/examples/telemetry_flight_mode.py b/examples/telemetry_flight_mode.py index 611fff4d..4fff2249 100755 --- a/examples/telemetry_flight_mode.py +++ b/examples/telemetry_flight_mode.py @@ -6,7 +6,7 @@ async def print_flight_mode(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/telemetry_is_armed_is_in_air.py b/examples/telemetry_is_armed_is_in_air.py index 60ed4f53..deccf67c 100755 --- a/examples/telemetry_is_armed_is_in_air.py +++ b/examples/telemetry_is_armed_is_in_air.py @@ -6,7 +6,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") asyncio.ensure_future(print_is_armed(drone)) asyncio.ensure_future(print_is_in_air(drone)) diff --git a/examples/telemetry_status_text.py b/examples/telemetry_status_text.py index da8109cc..ecdf15d5 100755 --- a/examples/telemetry_status_text.py +++ b/examples/telemetry_status_text.py @@ -6,7 +6,7 @@ async def print_status_text(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/telemetry_takeoff_and_land.py b/examples/telemetry_takeoff_and_land.py index f22ee731..4c9b8a0a 100755 --- a/examples/telemetry_takeoff_and_land.py +++ b/examples/telemetry_takeoff_and_land.py @@ -26,7 +26,7 @@ async def run(): # Init the drone drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/tune.py b/examples/tune.py index 217642b3..5a7cd1b6 100755 --- a/examples/tune.py +++ b/examples/tune.py @@ -8,7 +8,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): diff --git a/examples/upload_params.py b/examples/upload_params.py index aa8c9503..9cc3bc06 100755 --- a/examples/upload_params.py +++ b/examples/upload_params.py @@ -10,7 +10,7 @@ def main(): parser = argparse.ArgumentParser() parser.add_argument( "connection", - help="Connection string (e.g. udp://:14540)") + help="Connection string (e.g. udpin://0.0.0.0:14540)") parser.add_argument( "param_file", help="Param file to be uploaded with .params format") diff --git a/examples/winch.py b/examples/winch.py index 3b15b54e..b655b949 100644 --- a/examples/winch.py +++ b/examples/winch.py @@ -6,7 +6,7 @@ async def run(): drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") print("Waiting for drone to connect...") async for state in drone.core.connection_state(): From ce5f09e1a8d9c6f087f383aa53edf5c7514f3760 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 29 Jun 2025 13:13:17 +1200 Subject: [PATCH 3/3] docs: update connection syntax --- mavsdk/source/index.rst | 10 +++++----- mavsdk/system.py | 8 +++++--- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/mavsdk/source/index.rst b/mavsdk/source/index.rst index 373ab580..73f1e951 100644 --- a/mavsdk/source/index.rst +++ b/mavsdk/source/index.rst @@ -46,7 +46,7 @@ The package contains ``mavsdk_server`` already (previously called "backend"), wh from mavsdk import System ... drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") Note: ``System()`` takes two named parameters: ``mavsdk_server_address`` and ``port``. When left empty, they default to ``None`` and ``50051``, respectively, and ``mavsdk_server -p 50051`` is run by ``await drone.connect()``. If ``mavsdk_server_address`` is set (e.g. to "localhost"), then ``await drone.connect()`` will not start the embedded ``mavsdk_server`` and will try to connect to a server running at this address. This is useful for platforms where ``mavsdk_server`` does not come embedded, for debugging purposes, and for running ``mavsdk_server`` in a place different than where the MAVSDK-Python script is run. @@ -76,7 +76,7 @@ For this case, let's assume the example was like this: .. code:: python drone = System() - await drone.connect(system_address="udp://:14540") + await drone.connect(system_address="udpin://0.0.0.0:14540") The mavsdk_server binary is installed using ``pip``. If installed with ``python -m pip install --upgrade mavsdk`` it is usually (at least for Linux) to be found in ``~/.local/lib/python3.10/site-packages/mavsdk/bin/`` (of course depending on the Python version used). @@ -85,21 +85,21 @@ It can then be run in a separate console with the ``system_address`` as an argum .. code:: bash - ~/.local/lib/python3.10/site-packages/mavsdk/bin/mavsdk_server udp://:14540 + ~/.local/lib/python3.10/site-packages/mavsdk/bin/mavsdk_server udpin://0.0.0.0:14540 Without an autopilot connecting, the output will look something like: .. code:: bash [02:36:31|Info ] MAVSDK version: v1.4.16 (mavsdk_impl.cpp:28) - [02:36:31|Info ] Waiting to discover system on udp://:14540... (connection_initiator.h:20) + [02:36:31|Info ] Waiting to discover system on udpin://0.0.0.0:14540... (connection_initiator.h:20) Once an autopilot is discovered, something like this should be printed: .. code:: bash [02:38:12|Info ] MAVSDK version: v1.4.16 (mavsdk_impl.cpp:28) - [02:38:12|Info ] Waiting to discover system on udp://:14540... (connection_initiator.h:20) + [02:38:12|Info ] Waiting to discover system on udpin://0.0.0.0:14540... (connection_initiator.h:20) [02:39:01|Info ] New system on: 127.0.0.1:14580 (with sysid: 1) (udp_connection.cpp:194) [02:39:01|Debug] New: System ID: 1 Comp ID: 1 (mavsdk_impl.cpp:484) [02:39:01|Debug] Component Autopilot (1) added. (system_impl.cpp:355) diff --git a/mavsdk/system.py b/mavsdk/system.py index 651ab2c5..6aacb786 100644 --- a/mavsdk/system.py +++ b/mavsdk/system.py @@ -96,11 +96,13 @@ async def connect(self, system_address=None): ---------- system_address: str The address of the remote system. If None, it will - default to udp://:14540. Supported URL formats: + default to udpin://0.0.0.0:14540. Supported URL formats: - Serial: serial:///path/to/serial/dev[:baudrate] - - UDP: udp://[bind_host][:bind_port] - - TCP: tcp://[server_host][:server_port] + - UDP in: udpin://bind_host:bind_port + - UDP out: udpout://dest_host:dest_port + - TCP in: tcpin://bind_host:bind_port + - TCP out: tcpout://dest_host:dest_port """