├── .github └── workflows │ └── main.yml ├── .gitignore ├── .gitmodules ├── LICENSE.txt ├── MANIFEST.in ├── MAVSDK_SERVER_VERSION ├── README.md ├── examples ├── all_params.py ├── calibration.py ├── camera.py ├── camera_params.py ├── do_orbit.py ├── example-mission.plan ├── failure_injection.py ├── firmware_version.py ├── follow_me_example.py ├── ftp_download_file.py ├── ftp_list_dir.py ├── geofence.py ├── gimbal.py ├── goto.py ├── gripper.py ├── highres_imu.py ├── logfile_download.py ├── manual_control.py ├── mission.py ├── mission_import.py ├── mission_raw.py ├── offboard_attitude.py ├── offboard_from_csv │ ├── active.csv │ ├── offboard_from_csv.py │ └── trajectory_plot.png ├── offboard_position_ned.py ├── offboard_position_velocity_ned.py ├── offboard_velocity_body.py ├── offboard_velocity_ned.py ├── px4_ev_automation.py ├── px4_ev_automation_keyboard.py ├── rtcm.py ├── rtk_base_ublox.py ├── send_status_message.py ├── shell.py ├── takeoff_and_land.py ├── telemetry.py ├── telemetry_flight_mode.py ├── telemetry_is_armed_is_in_air.py ├── telemetry_status_text.py ├── telemetry_takeoff_and_land.py ├── transponder.py ├── tune.py ├── upload_params.py └── winch.py ├── mavsdk ├── Makefile ├── __init__.py ├── _base.py ├── action.py ├── action_pb2.py ├── action_pb2_grpc.py ├── action_server.py ├── action_server_pb2.py ├── action_server_pb2_grpc.py ├── arm_authorizer_server.py ├── arm_authorizer_server_pb2.py ├── arm_authorizer_server_pb2_grpc.py ├── async_plugin_manager.py ├── bin │ ├── README.md │ └── __init__.py ├── calibration.py ├── calibration_pb2.py ├── calibration_pb2_grpc.py ├── camera.py ├── camera_pb2.py ├── camera_pb2_grpc.py ├── camera_server.py ├── camera_server_pb2.py ├── camera_server_pb2_grpc.py ├── component_information.py ├── component_information_pb2.py ├── component_information_pb2_grpc.py ├── component_information_server.py ├── component_information_server_pb2.py ├── component_information_server_pb2_grpc.py ├── component_metadata.py ├── component_metadata_pb2.py ├── component_metadata_pb2_grpc.py ├── component_metadata_server.py ├── component_metadata_server_pb2.py ├── component_metadata_server_pb2_grpc.py ├── core.py ├── core_pb2.py ├── core_pb2_grpc.py ├── events.py ├── events_pb2.py ├── events_pb2_grpc.py ├── failure.py ├── failure_pb2.py ├── failure_pb2_grpc.py ├── follow_me.py ├── follow_me_pb2.py ├── follow_me_pb2_grpc.py ├── ftp.py ├── ftp_pb2.py ├── ftp_pb2_grpc.py ├── ftp_server.py ├── ftp_server_pb2.py ├── ftp_server_pb2_grpc.py ├── geofence.py ├── geofence_pb2.py ├── geofence_pb2_grpc.py ├── gimbal.py ├── gimbal_pb2.py ├── gimbal_pb2_grpc.py ├── gripper.py ├── gripper_pb2.py ├── gripper_pb2_grpc.py ├── info.py ├── info_pb2.py ├── info_pb2_grpc.py ├── log_files.py ├── log_files_pb2.py ├── log_files_pb2_grpc.py ├── log_streaming.py ├── log_streaming_pb2.py ├── log_streaming_pb2_grpc.py ├── make.bat ├── manual_control.py ├── manual_control_pb2.py ├── manual_control_pb2_grpc.py ├── mavsdk_options_pb2.py ├── mavsdk_options_pb2_grpc.py ├── mission.py ├── mission_pb2.py ├── mission_pb2_grpc.py ├── mission_raw.py ├── mission_raw_pb2.py ├── mission_raw_pb2_grpc.py ├── mission_raw_server.py ├── mission_raw_server_pb2.py ├── mission_raw_server_pb2_grpc.py ├── mocap.py ├── mocap_pb2.py ├── mocap_pb2_grpc.py ├── offboard.py ├── offboard_pb2.py ├── offboard_pb2_grpc.py ├── param.py ├── param_pb2.py ├── param_pb2_grpc.py ├── param_server.py ├── param_server_pb2.py ├── param_server_pb2_grpc.py ├── rtk.py ├── rtk_pb2.py ├── rtk_pb2_grpc.py ├── server_utility.py ├── server_utility_pb2.py ├── server_utility_pb2_grpc.py ├── shell.py ├── shell_pb2.py ├── shell_pb2_grpc.py ├── source │ ├── conf.py │ ├── index.rst │ ├── jetson-nano-install.rst │ ├── nature_adapted │ │ ├── static │ │ │ ├── favicon.png │ │ │ ├── sdk_logo_full.png │ │ │ └── style.css │ │ └── theme.conf │ ├── plugins │ │ ├── action.rst │ │ ├── action_server.rst │ │ ├── arm_authorizer_server.rst │ │ ├── calibration.rst │ │ ├── camera.rst │ │ ├── camera_server.rst │ │ ├── component_information.rst │ │ ├── component_information_server.rst │ │ ├── component_metadata.rst │ │ ├── component_metadata_server.rst │ │ ├── core.rst │ │ ├── events.rst │ │ ├── failure.rst │ │ ├── follow_me.rst │ │ ├── ftp.rst │ │ ├── ftp_server.rst │ │ ├── geofence.rst │ │ ├── gimbal.rst │ │ ├── gripper.rst │ │ ├── index.rst │ │ ├── info.rst │ │ ├── log_files.rst │ │ ├── log_streaming.rst │ │ ├── manual_control.rst │ │ ├── mission.rst │ │ ├── mission_raw.rst │ │ ├── mission_raw_server.rst │ │ ├── mocap.rst │ │ ├── offboard.rst │ │ ├── param.rst │ │ ├── param_server.rst │ │ ├── rtk.rst │ │ ├── server_utility.rst │ │ ├── shell.rst │ │ ├── telemetry.rst │ │ ├── telemetry_server.rst │ │ ├── tracking_server.rst │ │ ├── transponder.rst │ │ ├── tune.rst │ │ └── winch.rst │ └── system.rst ├── system.py ├── telemetry.py ├── telemetry_pb2.py ├── telemetry_pb2_grpc.py ├── telemetry_server.py ├── telemetry_server_pb2.py ├── telemetry_server_pb2_grpc.py ├── tracking_server.py ├── tracking_server_pb2.py ├── tracking_server_pb2_grpc.py ├── transponder.py ├── transponder_pb2.py ├── transponder_pb2_grpc.py ├── tune.py ├── tune_pb2.py ├── tune_pb2_grpc.py ├── winch.py ├── winch_pb2.py └── winch_pb2_grpc.py ├── other ├── docker │ └── testing │ │ ├── Dockerfile │ │ ├── build_python.sh │ │ └── test.sh ├── templates │ ├── py │ │ ├── call.j2 │ │ ├── enum.j2 │ │ ├── file.j2 │ │ ├── request.j2 │ │ ├── stream.j2 │ │ ├── struct.j2 │ │ └── type_conversions │ └── rst │ │ ├── call.j2 │ │ ├── enum.j2 │ │ ├── file.j2 │ │ ├── request.j2 │ │ ├── stream.j2 │ │ ├── struct.j2 │ │ └── type_conversions └── tools │ ├── run_protoc.sh │ ├── run_tests.sh │ └── upload_docs.sh ├── requirements-dev.txt ├── requirements-docs.txt ├── requirements-test.txt ├── requirements.txt ├── setup.cfg ├── setup.py ├── tests └── .gitkeep └── tox.ini /.gitignore: -------------------------------------------------------------------------------- 1 | venv 2 | __pycache__ 3 | *.pyc 4 | *.egg* 5 | dist/ 6 | wheelhouse/ 7 | build/ 8 | *.proto 9 | .idea/ 10 | *.ropeproject/ 11 | .pytest_cache/ 12 | .tox/ 13 | mavsdk/bin/mavsdk_server 14 | mavsdk/bin/mavsdk_server.exe 15 | -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "proto"] 2 | path = proto 3 | url = https://github.com/Dronecode/DronecodeSDK-Proto.git 4 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | Copyright (c) 2020, MAVSDK Development Team 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 5 | 6 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 7 | 8 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 9 | 10 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 11 | 12 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 13 | -------------------------------------------------------------------------------- /MANIFEST.in: -------------------------------------------------------------------------------- 1 | include mavsdk/bin 2 | include mavsdk/bin/mavsdk_server 3 | -------------------------------------------------------------------------------- /MAVSDK_SERVER_VERSION: -------------------------------------------------------------------------------- 1 | v3.5.0 2 | -------------------------------------------------------------------------------- /examples/all_params.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | # Connect to the drone 9 | drone = System() 10 | await drone.connect(system_address="udp://:14540") 11 | 12 | # Get the list of parameters 13 | all_params = await drone.param.get_all_params() 14 | 15 | # Iterate through all int parameters 16 | for param in all_params.int_params: 17 | print(f"{param.name}: {param.value}") 18 | 19 | for param in all_params.float_params: 20 | print(f"{param.name}: {param.value}") 21 | 22 | # Run the asyncio loop 23 | asyncio.run(run()) 24 | -------------------------------------------------------------------------------- /examples/calibration.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | 9 | drone = System() 10 | await drone.connect(system_address="udp://:14540") 11 | 12 | print("-- Starting gyroscope calibration") 13 | async for progress_data in drone.calibration.calibrate_gyro(): 14 | print(progress_data) 15 | print("-- Gyroscope calibration finished") 16 | 17 | print("-- Starting accelerometer calibration") 18 | async for progress_data in drone.calibration.calibrate_accelerometer(): 19 | print(progress_data) 20 | print("-- Accelerometer calibration finished") 21 | 22 | print("-- Starting magnetometer calibration") 23 | async for progress_data in drone.calibration.calibrate_magnetometer(): 24 | print(progress_data) 25 | print("-- Magnetometer calibration finished") 26 | 27 | print("-- Starting board level horizon calibration") 28 | async for progress_data in drone.calibration.calibrate_level_horizon(): 29 | print(progress_data) 30 | print("-- Board level calibration finished") 31 | 32 | 33 | if __name__ == "__main__": 34 | # Run the asyncio loop 35 | asyncio.run(run()) 36 | -------------------------------------------------------------------------------- /examples/camera.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | 5 | from mavsdk.camera import (CameraError, Mode) 6 | from mavsdk import System 7 | 8 | 9 | async def run(): 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | print("Waiting for drone to connect...") 14 | async for state in drone.core.connection_state(): 15 | if state.is_connected: 16 | print(f"-- Connected to drone!") 17 | break 18 | 19 | print_mode_task = asyncio.ensure_future(print_mode(drone)) 20 | print_status_task = asyncio.ensure_future(print_status(drone)) 21 | running_tasks = [print_mode_task, print_status_task] 22 | 23 | print("Setting mode to 'PHOTO'") 24 | try: 25 | await drone.camera.set_mode(Mode.PHOTO) 26 | except CameraError as error: 27 | print(f"Setting mode failed with error code: {error._result.result}") 28 | 29 | await asyncio.sleep(2) 30 | 31 | print("Taking a photo") 32 | try: 33 | await drone.camera.take_photo() 34 | except CameraError as error: 35 | print(f"Couldn't take photo: {error._result.result}") 36 | 37 | # Shut down the running coroutines (here 'print_mode()' and 38 | # 'print_status()') 39 | for task in running_tasks: 40 | task.cancel() 41 | try: 42 | await task 43 | except asyncio.CancelledError: 44 | pass 45 | await asyncio.get_event_loop().shutdown_asyncgens() 46 | 47 | 48 | async def print_mode(drone): 49 | async for mode in drone.camera.mode(): 50 | print(f"Camera mode: {mode}") 51 | 52 | 53 | async def print_status(drone): 54 | async for status in drone.camera.status(): 55 | print(status) 56 | 57 | 58 | if __name__ == "__main__": 59 | # Run the asyncio loop 60 | asyncio.run(run()) 61 | -------------------------------------------------------------------------------- /examples/do_orbit.py: -------------------------------------------------------------------------------- 1 | import asyncio 2 | from mavsdk import System 3 | from mavsdk.action import OrbitYawBehavior 4 | 5 | 6 | async def run(): 7 | drone = System() 8 | await drone.connect(system_address="udp://:14540") 9 | 10 | print("Waiting for drone to connect...") 11 | async for state in drone.core.connection_state(): 12 | if state.is_connected: 13 | print("Drone discovered!") 14 | break 15 | 16 | print("Waiting for drone to have a global position estimate...") 17 | async for health in drone.telemetry.health(): 18 | if health.is_global_position_ok and health.is_home_position_ok: 19 | print("-- Global position estimate OK") 20 | break 21 | 22 | position = await drone.telemetry.position().__aiter__().__anext__() 23 | orbit_height = position.absolute_altitude_m+10 24 | yaw_behavior = OrbitYawBehavior.HOLD_FRONT_TO_CIRCLE_CENTER 25 | 26 | print("-- Arming") 27 | await drone.action.arm() 28 | 29 | print("--- Taking Off") 30 | await drone.action.takeoff() 31 | await asyncio.sleep(10) 32 | 33 | print('Do orbit at 10m height from the ground') 34 | await drone.action.do_orbit(radius_m=10, 35 | velocity_ms=2, 36 | yaw_behavior=yaw_behavior, 37 | latitude_deg=47.398036222362471, 38 | longitude_deg=8.5450146439425509, 39 | absolute_altitude_m=orbit_height) 40 | await asyncio.sleep(60) 41 | 42 | await drone.action.return_to_launch() 43 | print("--- Landing") 44 | 45 | if __name__ == "__main__": 46 | asyncio.run(run()) 47 | -------------------------------------------------------------------------------- /examples/example-mission.plan: -------------------------------------------------------------------------------- 1 | { 2 | "fileType": "Plan", 3 | "geoFence": { 4 | "circles": [ 5 | ], 6 | "polygons": [ 7 | ], 8 | "version": 2 9 | }, 10 | "groundStation": "QGroundControl", 11 | "mission": { 12 | "cruiseSpeed": 15, 13 | "firmwareType": 12, 14 | "globalPlanAltitudeMode": 1, 15 | "hoverSpeed": 5, 16 | "items": [ 17 | { 18 | "AMSLAltAboveTerrain": null, 19 | "Altitude": 50, 20 | "AltitudeMode": 1, 21 | "autoContinue": true, 22 | "command": 22, 23 | "doJumpId": 1, 24 | "frame": 3, 25 | "params": [ 26 | 0, 27 | 0, 28 | 0, 29 | null, 30 | 47.397763168426465, 31 | 8.545600849401296, 32 | 50 33 | ], 34 | "type": "SimpleItem" 35 | }, 36 | { 37 | "AMSLAltAboveTerrain": null, 38 | "Altitude": 50, 39 | "AltitudeMode": 1, 40 | "autoContinue": true, 41 | "command": 16, 42 | "doJumpId": 2, 43 | "frame": 3, 44 | "params": [ 45 | 0, 46 | 0, 47 | 0, 48 | null, 49 | 47.39871817095695, 50 | 8.545497855290222, 51 | 50 52 | ], 53 | "type": "SimpleItem" 54 | }, 55 | { 56 | "AMSLAltAboveTerrain": null, 57 | "Altitude": 50, 58 | "AltitudeMode": 1, 59 | "autoContinue": true, 60 | "command": 16, 61 | "doJumpId": 3, 62 | "frame": 3, 63 | "params": [ 64 | 0, 65 | 0, 66 | 0, 67 | null, 68 | 47.398700886684885, 69 | 8.544924200005596, 70 | 50 71 | ], 72 | "type": "SimpleItem" 73 | }, 74 | { 75 | "AMSLAltAboveTerrain": null, 76 | "Altitude": 50, 77 | "AltitudeMode": 1, 78 | "autoContinue": true, 79 | "command": 16, 80 | "doJumpId": 4, 81 | "frame": 3, 82 | "params": [ 83 | 0, 84 | 0, 85 | 0, 86 | null, 87 | 47.39774277601443, 88 | 8.544925937372682, 89 | 50 90 | ], 91 | "type": "SimpleItem" 92 | }, 93 | { 94 | "autoContinue": true, 95 | "command": 20, 96 | "doJumpId": 5, 97 | "frame": 2, 98 | "params": [ 99 | 0, 100 | 0, 101 | 0, 102 | 0, 103 | 0, 104 | 0, 105 | 0 106 | ], 107 | "type": "SimpleItem" 108 | } 109 | ], 110 | "plannedHomePosition": [ 111 | 47.397763168426465, 112 | 8.545600849401296, 113 | null 114 | ], 115 | "vehicleType": 2, 116 | "version": 2 117 | }, 118 | "rallyPoints": { 119 | "points": [ 120 | [ 121 | 47.3975777095593, 122 | 8.545262530782963, 123 | 0 124 | ], 125 | [ 126 | 47.39882862292046, 127 | 8.545234383318984, 128 | 0 129 | ] 130 | ], 131 | "version": 2 132 | }, 133 | "version": 1 134 | } 135 | -------------------------------------------------------------------------------- /examples/failure_injection.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | 5 | from mavsdk import System 6 | from mavsdk.failure import FailureType, FailureUnit 7 | 8 | 9 | async def run(): 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | print("Waiting for drone to connect...") 14 | async for state in drone.core.connection_state(): 15 | if state.is_connected: 16 | print(f"-- Connected to drone!") 17 | break 18 | 19 | print("Waiting for drone to have a global position estimate...") 20 | async for health in drone.telemetry.health(): 21 | if health.is_global_position_ok and health.is_home_position_ok: 22 | print("-- Global position estimate OK") 23 | break 24 | 25 | print("-- Enabling failure injection") 26 | await drone.param.set_param_int('SYS_FAILURE_EN', 1) 27 | 28 | print("-- Arming") 29 | await drone.action.arm() 30 | 31 | print("-- Taking off") 32 | await drone.action.takeoff() 33 | 34 | await asyncio.sleep(5) 35 | 36 | goto_lat = 0.0 37 | goto_lon = 0.0 38 | goto_alt = 0.0 39 | async for position in drone.telemetry.position(): 40 | # Only need position once 41 | if position.latitude_deg and position.longitude_deg: 42 | goto_lat = position.latitude_deg 43 | goto_lon = position.longitude_deg 44 | goto_alt = position.absolute_altitude_m 45 | break 46 | 47 | print("-- Flying up") 48 | flying_alt = goto_alt + 20.0 # To fly drone 20m above the ground plane 49 | await drone.action.goto_location(goto_lat, goto_lon, flying_alt, 0) 50 | 51 | await asyncio.sleep(5) 52 | 53 | print("-- Injecting GPS failure") 54 | await drone.failure.inject( 55 | FailureUnit.SENSOR_GPS, FailureType.OFF, instance=0) 56 | 57 | print("-- Waiting 20s before exiting script...") 58 | await asyncio.sleep(20) 59 | 60 | print("-- Disabling failure injection") 61 | await drone.param.set_param_int('SYS_FAILURE_EN', 0) 62 | 63 | if __name__ == "__main__": 64 | # Run the asyncio loop 65 | asyncio.run(run()) 66 | -------------------------------------------------------------------------------- /examples/firmware_version.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print(f"-- Connected to drone!") 15 | break 16 | 17 | info = await drone.info.get_version() 18 | print(info) 19 | 20 | 21 | if __name__ == "__main__": 22 | # Run the asyncio loop 23 | asyncio.run(run()) 24 | -------------------------------------------------------------------------------- /examples/follow_me_example.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | # This example shows how to use the follow me plugin 4 | 5 | import asyncio 6 | from mavsdk import System 7 | from mavsdk.follow_me import (Config, FollowMeError, TargetLocation) 8 | 9 | 10 | follow_height = 8.0 # in meters 11 | # distance between drone and target 12 | follow_distance = 2.0 # in meters 13 | responsiveness = 0.02 14 | altitude_mode = Config.FollowAltitudeMode.TARGET_GPS 15 | max_follow_vel = 10 16 | # direction relative to the target 17 | follow_angle_deg = 0 18 | 19 | # This list contains fake location coordinates 20 | # (These coordinates are obtained from mission.py example) 21 | fake_location = [[47.398039859999997, 8.5455725400000002], 22 | [47.398036222362471, 8.5450146439425509], 23 | [47.397825620791885, 8.5450092830163271]] 24 | 25 | 26 | async def run(): 27 | drone = System() 28 | await drone.connect(system_address="udp://:14540") 29 | 30 | print("Waiting for drone to connect...") 31 | async for state in drone.core.connection_state(): 32 | if state.is_connected: 33 | print(f"-- Connected to drone!") 34 | break 35 | 36 | print("Waiting for drone to have a global position estimate...") 37 | async for health in drone.telemetry.health(): 38 | if health.is_global_position_ok and health.is_home_position_ok: 39 | print("-- Global position estimate OK") 40 | break 41 | 42 | # Arming the drone 43 | print("-- Arming") 44 | await drone.action.arm() 45 | 46 | # Follow me Mode requires some configuration to be done before starting 47 | # the mode 48 | conf = Config(follow_height, follow_distance, responsiveness, 49 | altitude_mode, max_follow_vel, follow_angle_deg) 50 | await drone.follow_me.set_config(conf) 51 | 52 | print("-- Taking Off") 53 | await drone.action.takeoff() 54 | await asyncio.sleep(8) 55 | print("-- Starting Follow Me Mode") 56 | await drone.follow_me.start() 57 | await asyncio.sleep(8) 58 | 59 | # This for loop provides fake coordinates from the fake_location list for 60 | # the follow me mode to work. 61 | # In a simulator it won't make much sense though 62 | target = TargetLocation(0, 0, 0, 0, 0, 0) 63 | for latitude, longitude in fake_location: 64 | target.latitude_deg = latitude 65 | target.longitude_deg = longitude 66 | target.absolute_altitude_m = 480.0 67 | target.velocity_x_m_s = 0 68 | target.velocity_y_m_s = 0 69 | target.velocity_z_m_s = 0 70 | print("-- Following Target") 71 | await drone.follow_me.set_target_location(target) 72 | await asyncio.sleep(2) 73 | 74 | # Stopping the follow me mode 75 | print("-- Stopping Follow Me Mode") 76 | await drone.follow_me.stop() 77 | await asyncio.sleep(5) 78 | 79 | print("-- Landing") 80 | await drone.action.land() 81 | 82 | if __name__ == "__main__": 83 | # Run the asyncio loop 84 | asyncio.run(run()) 85 | -------------------------------------------------------------------------------- /examples/ftp_download_file.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | 9 | drone = System(mavsdk_server_address="localhost", port=50051) 10 | await drone.connect(system_address="serial:///dev/ttyACM0:57600") 11 | 12 | print("Waiting for drone to connect...") 13 | async for state in drone.core.connection_state(): 14 | if state.is_connected: 15 | print(f"-- Connected to drone!") 16 | break 17 | 18 | async for update in drone.ftp.download( 19 | "/etc/extras/px4_io-v2_default.bin", ".", use_burst=False 20 | ): 21 | print(f"Got {update.bytes_transferred} of {update.total_bytes} bytes") 22 | 23 | 24 | if __name__ == "__main__": 25 | # Run the asyncio loop 26 | asyncio.run(run()) 27 | -------------------------------------------------------------------------------- /examples/ftp_list_dir.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | 9 | drone = System(mavsdk_server_address='localhost', port=50051) 10 | await drone.connect(system_address="serial:///dev/ttyACM0:57600") 11 | 12 | print("Waiting for drone to connect...") 13 | async for state in drone.core.connection_state(): 14 | if state.is_connected: 15 | print(f"-- Connected to drone!") 16 | break 17 | 18 | print("directory list", await drone.ftp.list_directory("/")) 19 | 20 | 21 | if __name__ == "__main__": 22 | # Run the asyncio loop 23 | asyncio.run(run()) 24 | -------------------------------------------------------------------------------- /examples/geofence.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | from mavsdk.geofence import Point, Polygon, FenceType, GeofenceData, Circle 6 | 7 | """ 8 | This example shows how to use the geofence plugin. 9 | 10 | Note: The behavior when your vehicle hits the geofence is NOT configured 11 | in this example. 12 | 13 | FenceType: 14 | INCLUSION: The vehicle will not go outside the fence area. 15 | EXCLUSION: The vehicle will not come inside the fence area. 16 | 17 | """ 18 | 19 | 20 | async def run(): 21 | 22 | # Connect to the Simulation 23 | drone = System() 24 | await drone.connect(system_address="udp://:14540") 25 | 26 | # Wait for the drone to connect 27 | print("Waiting for drone to connect...") 28 | async for state in drone.core.connection_state(): 29 | if state.is_connected: 30 | print(f"-- Connected to drone!") 31 | break 32 | 33 | # Fetch the home location coordinates, in order to set a boundary around 34 | # the home location. 35 | print("Fetching home location coordinates...") 36 | async for terrain_info in drone.telemetry.home(): 37 | latitude = terrain_info.latitude_deg 38 | longitude = terrain_info.longitude_deg 39 | break 40 | 41 | await asyncio.sleep(1) 42 | 43 | # Define your geofence boundary 44 | p1 = Point(latitude - 0.0001, longitude - 0.0001) 45 | p2 = Point(latitude + 0.0001, longitude - 0.0001) 46 | p3 = Point(latitude + 0.0001, longitude + 0.0001) 47 | p4 = Point(latitude - 0.0001, longitude + 0.0001) 48 | 49 | # Create a polygon object using your points 50 | polygon = Polygon([p1, p2, p3, p4], FenceType.INCLUSION) 51 | 52 | # circle = Circle(p1, 10.0, FenceType.INCLUSION) 53 | 54 | # Sending the circle object is necessary in the geofence data, 55 | # so if you don't want to set the circular geofence, send it like this. 56 | circle = Circle(Point(0, 0), 0, FenceType.INCLUSION) 57 | 58 | geofenceData = GeofenceData([polygon], [circle]) 59 | 60 | # Upload the geofence to your vehicle 61 | print("Uploading geofence...") 62 | await drone.geofence.upload_geofence(geofenceData) 63 | 64 | print("Geofence uploaded!") 65 | 66 | 67 | if __name__ == "__main__": 68 | # Run the asyncio loop 69 | asyncio.run(run()) 70 | -------------------------------------------------------------------------------- /examples/goto.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print(f"-- Connected to drone!") 15 | break 16 | 17 | print("Waiting for drone to have a global position estimate...") 18 | async for health in drone.telemetry.health(): 19 | if health.is_global_position_ok and health.is_home_position_ok: 20 | print("-- Global position state is good enough for flying.") 21 | break 22 | 23 | print("Fetching amsl altitude at home location....") 24 | async for terrain_info in drone.telemetry.home(): 25 | absolute_altitude = terrain_info.absolute_altitude_m 26 | break 27 | 28 | print("-- Arming") 29 | await drone.action.arm() 30 | 31 | print("-- Taking off") 32 | await drone.action.takeoff() 33 | 34 | await asyncio.sleep(1) 35 | # To fly drone 20m above the ground plane 36 | flying_alt = absolute_altitude + 20.0 37 | # goto_location() takes Absolute MSL altitude 38 | await drone.action.goto_location(47.397606, 8.543060, flying_alt, 0) 39 | 40 | while True: 41 | print("Staying connected, press Ctrl-C to exit") 42 | await asyncio.sleep(1) 43 | 44 | 45 | if __name__ == "__main__": 46 | # Run the asyncio loop 47 | asyncio.run(run()) 48 | -------------------------------------------------------------------------------- /examples/gripper.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print(f"-- Connected to drone!") 15 | break 16 | 17 | print(f"-- Gripper Grab") 18 | await drone.gripper.grab(instance=1) 19 | 20 | await asyncio.sleep(1) 21 | 22 | print(f"-- Gripper Release") 23 | await drone.gripper.release(instance=1) 24 | 25 | while True: 26 | print("Staying connected, press Ctrl-C to exit") 27 | await asyncio.sleep(1) 28 | 29 | 30 | if __name__ == "__main__": 31 | # Run the asyncio loop 32 | asyncio.run(run()) 33 | -------------------------------------------------------------------------------- /examples/highres_imu.py: -------------------------------------------------------------------------------- 1 | import asyncio 2 | from mavsdk import System 3 | 4 | 5 | async def get_imu_data(): 6 | # Connect to the drone 7 | drone = System() 8 | await drone.connect(system_address="udp://:14540") 9 | 10 | # Wait for the drone to connect 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print("Drone is connected!") 15 | break 16 | 17 | telemetry = drone.telemetry 18 | 19 | # Set the rate at which IMU data is updated (in Hz) 20 | await telemetry.set_rate_imu(200.0) 21 | 22 | # Fetch and print IMU data 23 | print("Fetching IMU data...") 24 | async for imu in telemetry.imu(): 25 | # Print data in HIGHRES_IMU format 26 | print(f"HIGHRES_IMU (105)") 27 | print(f"Time (us): {imu.timestamp_us}") 28 | print(f"X Acceleration (m/s^2): {imu.acceleration_frd.forward_m_s2}") 29 | print(f"Y Acceleration (m/s^2): {imu.acceleration_frd.right_m_s2}") 30 | print(f"Z Acceleration (m/s^2): {imu.acceleration_frd.down_m_s2}") 31 | print(f"X Gyro (rad/s): {imu.angular_velocity_frd.forward_rad_s}") 32 | print(f"Y Gyro (rad/s): {imu.angular_velocity_frd.right_rad_s}") 33 | print(f"Z Gyro (rad/s): {imu.angular_velocity_frd.down_rad_s}") 34 | print(f"X Mag (gauss): {imu.magnetic_field_frd.forward_gauss}") 35 | print(f"Y Mag (gauss): {imu.magnetic_field_frd.right_gauss}") 36 | print(f"Z Mag (gauss): {imu.magnetic_field_frd.down_gauss}") 37 | print(f"Temperature (°C): {imu.temperature_degc}") 38 | print("-----------------------------------------") 39 | 40 | if __name__ == "__main__": 41 | loop = asyncio.get_event_loop() 42 | loop.run_until_complete(get_imu_data()) 43 | -------------------------------------------------------------------------------- /examples/logfile_download.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | import sys 6 | 7 | 8 | async def run(): 9 | drone = System() 10 | await drone.connect(system_address="udp://:14540") 11 | 12 | print("Waiting for drone to connect...") 13 | async for state in drone.core.connection_state(): 14 | if state.is_connected: 15 | print(f"-- Connected to drone!") 16 | break 17 | 18 | entries = await get_entries(drone) 19 | for entry in entries: 20 | await download_log(drone, entry) 21 | 22 | 23 | async def download_log(drone, entry): 24 | date_without_colon = entry.date.replace(":", "-") 25 | filename = f"./log-{date_without_colon}.ulog" 26 | print(f"Downloading: log {entry.id} from {entry.date} to {filename}") 27 | previous_progress = -1 28 | async for progress in drone.log_files.download_log_file(entry, filename): 29 | new_progress = round(progress.progress*100) 30 | if new_progress != previous_progress: 31 | sys.stdout.write(f"\r{new_progress} %") 32 | sys.stdout.flush() 33 | previous_progress = new_progress 34 | print() 35 | 36 | 37 | async def get_entries(drone): 38 | entries = await drone.log_files.get_entries() 39 | for entry in entries: 40 | print(f"Log {entry.id} from {entry.date}") 41 | return entries 42 | 43 | 44 | if __name__ == "__main__": 45 | # Run the asyncio loop 46 | asyncio.run(run()) 47 | -------------------------------------------------------------------------------- /examples/manual_control.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | """ 4 | This example shows how to use the manual controls plugin. 5 | 6 | Note: Manual inputs are taken from a test set in this example to decrease 7 | complexity. Manual inputs can be received from devices such as a joystick 8 | using third-party python extensions. 9 | 10 | Note: Taking off the drone is not necessary before enabling manual inputs. 11 | It is acceptable to send positive throttle input to leave the ground. 12 | Takeoff is used in this example to decrease complexity 13 | """ 14 | 15 | import asyncio 16 | import random 17 | from mavsdk import System 18 | 19 | # Test set of manual inputs. Format: [roll, pitch, throttle, yaw] 20 | manual_inputs = [ 21 | [0, 0, 0.5, 0], # no movement 22 | [-1, 0, 0.5, 0], # minimum roll 23 | [1, 0, 0.5, 0], # maximum roll 24 | [0, -1, 0.5, 0], # minimum pitch 25 | [0, 1, 0.5, 0], # maximum pitch 26 | [0, 0, 0.5, -1], # minimum yaw 27 | [0, 0, 0.5, 1], # maximum yaw 28 | [0, 0, 1, 0], # max throttle 29 | [0, 0, 0, 0], # minimum throttle 30 | ] 31 | 32 | 33 | async def manual_controls(): 34 | """Main function to connect to the drone and input manual controls""" 35 | # Connect to the Simulation 36 | drone = System() 37 | await drone.connect(system_address="udp://:14540") 38 | 39 | # This waits till a mavlink based drone is connected 40 | print("Waiting for drone to connect...") 41 | async for state in drone.core.connection_state(): 42 | if state.is_connected: 43 | print(f"-- Connected to drone!") 44 | break 45 | 46 | # Checking if Global Position Estimate is ok 47 | async for health in drone.telemetry.health(): 48 | if health.is_global_position_ok and health.is_home_position_ok: 49 | print("-- Global position state is good enough for flying.") 50 | break 51 | 52 | # set the manual control input after arming 53 | await drone.manual_control.set_manual_control_input( 54 | float(0), float(0), float(0.5), float(0) 55 | ) 56 | 57 | # Arming the drone 58 | print("-- Arming") 59 | await drone.action.arm() 60 | 61 | # Takeoff the vehicle 62 | print("-- Taking off") 63 | await drone.action.takeoff() 64 | await asyncio.sleep(5) 65 | 66 | # set the manual control input after arming 67 | await drone.manual_control.set_manual_control_input( 68 | float(0), float(0), float(0.5), float(0) 69 | ) 70 | 71 | # start manual control 72 | print("-- Starting manual control") 73 | await drone.manual_control.start_position_control() 74 | 75 | while True: 76 | # grabs a random input from the test list 77 | # WARNING - your simulation vehicle may crash if its unlucky enough 78 | input_index = random.randint(0, len(manual_inputs) - 1) 79 | input_list = manual_inputs[input_index] 80 | 81 | # get current state of roll axis (between -1 and 1) 82 | roll = float(input_list[0]) 83 | # get current state of pitch axis (between -1 and 1) 84 | pitch = float(input_list[1]) 85 | # get current state of throttle axis 86 | # (between -1 and 1, but between 0 and 1 is expected) 87 | throttle = float(input_list[2]) 88 | # get current state of yaw axis (between -1 and 1) 89 | yaw = float(input_list[3]) 90 | 91 | await drone.manual_control.set_manual_control_input( 92 | pitch, roll, throttle, yaw) 93 | 94 | await asyncio.sleep(0.1) 95 | 96 | 97 | if __name__ == "__main__": 98 | # Run the asyncio loop 99 | asyncio.run(manual_controls()) 100 | -------------------------------------------------------------------------------- /examples/mission.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | 5 | from mavsdk import System 6 | from mavsdk.mission import (MissionItem, MissionPlan) 7 | 8 | 9 | async def run(): 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | print("Waiting for drone to connect...") 14 | async for state in drone.core.connection_state(): 15 | if state.is_connected: 16 | print(f"-- Connected to drone!") 17 | break 18 | 19 | print_mission_progress_task = asyncio.ensure_future( 20 | print_mission_progress(drone)) 21 | 22 | running_tasks = [print_mission_progress_task] 23 | termination_task = asyncio.ensure_future( 24 | observe_is_in_air(drone, running_tasks)) 25 | 26 | mission_items = [] 27 | mission_items.append(MissionItem(47.398039859999997, 28 | 8.5455725400000002, 29 | 25, 30 | 10, 31 | True, 32 | float('nan'), 33 | float('nan'), 34 | MissionItem.CameraAction.NONE, 35 | float('nan'), 36 | float('nan'), 37 | float('nan'), 38 | float('nan'), 39 | float('nan'), 40 | MissionItem.VehicleAction.NONE)) 41 | mission_items.append(MissionItem(47.398036222362471, 42 | 8.5450146439425509, 43 | 25, 44 | 10, 45 | True, 46 | float('nan'), 47 | float('nan'), 48 | MissionItem.CameraAction.NONE, 49 | float('nan'), 50 | float('nan'), 51 | float('nan'), 52 | float('nan'), 53 | float('nan'), 54 | MissionItem.VehicleAction.NONE)) 55 | mission_items.append(MissionItem(47.397825620791885, 56 | 8.5450092830163271, 57 | 25, 58 | 10, 59 | True, 60 | float('nan'), 61 | float('nan'), 62 | MissionItem.CameraAction.NONE, 63 | float('nan'), 64 | float('nan'), 65 | float('nan'), 66 | float('nan'), 67 | float('nan'), 68 | MissionItem.VehicleAction.NONE)) 69 | 70 | mission_plan = MissionPlan(mission_items) 71 | 72 | await drone.mission.set_return_to_launch_after_mission(True) 73 | 74 | print("-- Uploading mission") 75 | await drone.mission.upload_mission(mission_plan) 76 | 77 | print("Waiting for drone to have a global position estimate...") 78 | async for health in drone.telemetry.health(): 79 | if health.is_global_position_ok and health.is_home_position_ok: 80 | print("-- Global position estimate OK") 81 | break 82 | 83 | print("-- Arming") 84 | await drone.action.arm() 85 | 86 | print("-- Starting mission") 87 | await drone.mission.start_mission() 88 | 89 | await termination_task 90 | 91 | 92 | async def print_mission_progress(drone): 93 | async for mission_progress in drone.mission.mission_progress(): 94 | print(f"Mission progress: " 95 | f"{mission_progress.current}/" 96 | f"{mission_progress.total}") 97 | 98 | 99 | async def observe_is_in_air(drone, running_tasks): 100 | """ Monitors whether the drone is flying or not and 101 | returns after landing """ 102 | 103 | was_in_air = False 104 | 105 | async for is_in_air in drone.telemetry.in_air(): 106 | if is_in_air: 107 | was_in_air = is_in_air 108 | 109 | if was_in_air and not is_in_air: 110 | for task in running_tasks: 111 | task.cancel() 112 | try: 113 | await task 114 | except asyncio.CancelledError: 115 | pass 116 | await asyncio.get_event_loop().shutdown_asyncgens() 117 | 118 | return 119 | 120 | 121 | if __name__ == "__main__": 122 | # Run the asyncio loop 123 | asyncio.run(run()) 124 | -------------------------------------------------------------------------------- /examples/mission_import.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | 5 | from mavsdk import System 6 | import mavsdk.mission_raw 7 | 8 | 9 | async def run(): 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | print("Waiting for drone to connect...") 14 | async for state in drone.core.connection_state(): 15 | if state.is_connected: 16 | print(f"-- Connected to drone!") 17 | break 18 | 19 | out = await drone.mission_raw.import_qgroundcontrol_mission( 20 | "example-mission.plan") 21 | 22 | print(f"{len(out.mission_items)} mission items and" 23 | f"{len(out.rally_items)} rally items imported.") 24 | 25 | await drone.mission_raw.upload_mission(out.mission_items) 26 | await drone.mission_raw.upload_rally_points(out.rally_items) 27 | 28 | print("Mission uploaded") 29 | 30 | 31 | if __name__ == "__main__": 32 | # Run the asyncio loop 33 | asyncio.run(run()) 34 | -------------------------------------------------------------------------------- /examples/mission_raw.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | from mavsdk import mission_raw 6 | 7 | 8 | async def px4_connect_drone(): 9 | drone = System() 10 | await drone.connect(system_address="udp://:14540") 11 | 12 | print("Waiting for drone to connect...") 13 | async for state in drone.core.connection_state(): 14 | if state.is_connected: 15 | print("-- Connected to drone!") 16 | return drone 17 | 18 | 19 | async def run(): 20 | drone = await px4_connect_drone() 21 | await run_drone(drone) 22 | 23 | 24 | async def run_drone(drone): 25 | mission_items = [] 26 | 27 | mission_items.append(mission_raw.MissionItem( 28 | # start seq at 0 29 | 0, 30 | # MAV_FRAME command. 3 is WGS84 + relative altitude 31 | 3, 32 | # command. 16 is a basic waypoint 33 | 16, 34 | # first one is current 35 | 1, 36 | # auto-continue. 1: True, 0: False 37 | 1, 38 | # param1 39 | 0, 40 | # param2 - Acceptance radius 41 | 10, 42 | # param3 - 0 (pass through the waypoint normally) 43 | 0, 44 | # param4 - Desired yaw angle at waypoint 45 | float('nan'), 46 | # param5 - latitude 47 | int(47.40271757 * 10**7), 48 | # param6 - longitude 49 | int(8.54285027 * 10**7), 50 | # param7 - altitude 51 | 30.0, 52 | # mission_type. 53 | 0 54 | )) 55 | 56 | mission_items.append(mission_raw.MissionItem( 57 | 1, 58 | 3, 59 | 16, 60 | 0, 61 | 1, 62 | 0, 63 | 10, 64 | 0, 65 | float('nan'), 66 | int(47.40271757 * 10**7), 67 | int(8.54361892 * 10**7), 68 | 30.0, 69 | 0 70 | )) 71 | 72 | print("-- Uploading mission") 73 | await drone.mission_raw.upload_mission(mission_items) 74 | print("-- Done") 75 | 76 | 77 | if __name__ == "__main__": 78 | # Run the asyncio loop 79 | asyncio.run(run()) 80 | -------------------------------------------------------------------------------- /examples/offboard_attitude.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | # Warning: Only try this in simulation! 4 | # The direct attitude interface is a low level interface to be used 5 | # with caution. On real vehicles the thrust values are likely not 6 | # adjusted properly and you need to close the loop using altitude. 7 | 8 | import asyncio 9 | 10 | from mavsdk import System 11 | from mavsdk.offboard import (Attitude, OffboardError) 12 | 13 | 14 | async def run(): 15 | """ Does Offboard control using attitude commands. """ 16 | 17 | drone = System() 18 | await drone.connect(system_address="udp://:14540") 19 | 20 | print("Waiting for drone to connect...") 21 | async for state in drone.core.connection_state(): 22 | if state.is_connected: 23 | print(f"-- Connected to drone!") 24 | break 25 | 26 | print("Waiting for drone to have a global position estimate...") 27 | async for health in drone.telemetry.health(): 28 | if health.is_global_position_ok and health.is_home_position_ok: 29 | print("-- Global position estimate OK") 30 | break 31 | 32 | print("-- Arming") 33 | await drone.action.arm() 34 | 35 | print("-- Setting initial setpoint") 36 | await drone.offboard.set_attitude(Attitude(0.0, 0.0, 0.0, 0.0)) 37 | 38 | print("-- Starting offboard") 39 | try: 40 | await drone.offboard.start() 41 | except OffboardError as error: 42 | print(f"Starting offboard mode failed with error code: \ 43 | {error._result.result}") 44 | print("-- Disarming") 45 | await drone.action.disarm() 46 | return 47 | 48 | print("-- Go up at 70% thrust") 49 | await drone.offboard.set_attitude(Attitude(0.0, 0.0, 0.0, 0.7)) 50 | await asyncio.sleep(2) 51 | 52 | print("-- Roll 30 at 60% thrust") 53 | await drone.offboard.set_attitude(Attitude(30.0, 0.0, 0.0, 0.6)) 54 | await asyncio.sleep(2) 55 | 56 | print("-- Roll -30 at 60% thrust") 57 | await drone.offboard.set_attitude(Attitude(-30.0, 0.0, 0.0, 0.6)) 58 | await asyncio.sleep(2) 59 | 60 | print("-- Hover at 60% thrust") 61 | await drone.offboard.set_attitude(Attitude(0.0, 0.0, 0.0, 0.6)) 62 | await asyncio.sleep(2) 63 | 64 | print("-- Stopping offboard") 65 | try: 66 | await drone.offboard.stop() 67 | except OffboardError as error: 68 | print(f"Stopping offboard mode failed with error code: \ 69 | {error._result.result}") 70 | 71 | await drone.action.land() 72 | 73 | 74 | if __name__ == "__main__": 75 | # Run the asyncio loop 76 | asyncio.run(run()) 77 | -------------------------------------------------------------------------------- /examples/offboard_from_csv/trajectory_plot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/examples/offboard_from_csv/trajectory_plot.png -------------------------------------------------------------------------------- /examples/offboard_position_ned.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | """ 4 | Caveat when attempting to run the examples in non-gps environments: 5 | 6 | `drone.offboard.stop()` will return a `COMMAND_DENIED` result because it 7 | requires a mode switch to HOLD, something that is currently not supported in a 8 | non-gps environment. 9 | """ 10 | 11 | import asyncio 12 | 13 | from mavsdk import System 14 | from mavsdk.offboard import (OffboardError, PositionNedYaw) 15 | 16 | 17 | async def run(): 18 | """ Does Offboard control using position NED coordinates. """ 19 | 20 | drone = System() 21 | await drone.connect(system_address="udp://:14540") 22 | 23 | print("Waiting for drone to connect...") 24 | async for state in drone.core.connection_state(): 25 | if state.is_connected: 26 | print(f"-- Connected to drone!") 27 | break 28 | 29 | print("Waiting for drone to have a global position estimate...") 30 | async for health in drone.telemetry.health(): 31 | if health.is_global_position_ok and health.is_home_position_ok: 32 | print("-- Global position estimate OK") 33 | break 34 | 35 | print("-- Arming") 36 | await drone.action.arm() 37 | 38 | print("-- Setting initial setpoint") 39 | await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, 0.0, 0.0)) 40 | 41 | print("-- Starting offboard") 42 | try: 43 | await drone.offboard.start() 44 | except OffboardError as error: 45 | print(f"Starting offboard mode failed \ 46 | with error code: {error._result.result}") 47 | print("-- Disarming") 48 | await drone.action.disarm() 49 | return 50 | 51 | print("-- Go 0m North, 0m East, -5m Down \ 52 | within local coordinate system") 53 | await drone.offboard.set_position_ned( 54 | PositionNedYaw(0.0, 0.0, -5.0, 0.0)) 55 | await asyncio.sleep(10) 56 | 57 | print("-- Go 5m North, 0m East, -5m Down \ 58 | within local coordinate system, turn to face East") 59 | await drone.offboard.set_position_ned( 60 | PositionNedYaw(5.0, 0.0, -5.0, 90.0)) 61 | await asyncio.sleep(10) 62 | 63 | print("-- Go 5m North, 10m East, -5m Down \ 64 | within local coordinate system") 65 | await drone.offboard.set_position_ned( 66 | PositionNedYaw(5.0, 10.0, -5.0, 90.0)) 67 | await asyncio.sleep(15) 68 | 69 | print("-- Go 0m North, 10m East, 0m Down \ 70 | within local coordinate system, turn to face South") 71 | await drone.offboard.set_position_ned( 72 | PositionNedYaw(0.0, 10.0, 0.0, 180.0)) 73 | await asyncio.sleep(10) 74 | 75 | print("-- Stopping offboard") 76 | try: 77 | await drone.offboard.stop() 78 | except OffboardError as error: 79 | print(f"Stopping offboard mode failed \ 80 | with error code: {error._result.result}") 81 | 82 | 83 | if __name__ == "__main__": 84 | # Run the asyncio loop 85 | asyncio.run(run()) 86 | -------------------------------------------------------------------------------- /examples/offboard_position_velocity_ned.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | 5 | from mavsdk import System 6 | from mavsdk.offboard import (PositionNedYaw, VelocityNedYaw, OffboardError) 7 | 8 | 9 | async def run(): 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | print("Waiting for drone to connect...") 14 | async for state in drone.core.connection_state(): 15 | if state.is_connected: 16 | print(f"-- Connected to drone!") 17 | break 18 | 19 | print("Waiting for drone to have a global position estimate...") 20 | async for health in drone.telemetry.health(): 21 | if health.is_global_position_ok and health.is_home_position_ok: 22 | print("-- Global position estimate OK") 23 | break 24 | 25 | print("-- Arming") 26 | await drone.action.arm() 27 | 28 | print("-- Setting initial setpoint") 29 | await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, 0.0, 0.0)) 30 | 31 | print("-- Starting offboard") 32 | try: 33 | await drone.offboard.start() 34 | except OffboardError as error: 35 | print(f"Starting offboard mode failed with \ 36 | error code: {error._result.result}") 37 | print("-- Disarming") 38 | await drone.action.disarm() 39 | return 40 | 41 | async def print_z_velocity(drone): 42 | async for odom in drone.telemetry.position_velocity_ned(): 43 | print(f"{odom.velocity.north_m_s} {odom.velocity.down_m_s}") 44 | 45 | asyncio.ensure_future(print_z_velocity(drone)) 46 | 47 | print("-- Go 0m North, 0m East, -10m Down within local coordinate system") 48 | await drone.offboard.set_position_velocity_ned( 49 | PositionNedYaw(0.0, 0.0, -10.0, 0.0), 50 | VelocityNedYaw(0.0, 0.0, -1.0, 0.0)) 51 | await asyncio.sleep(10) 52 | 53 | print("-- Go 10m North, 0m East, 0m Down within local coordinate system") 54 | await drone.offboard.set_position_velocity_ned( 55 | PositionNedYaw(50.0, 0.0, -10.0, 0.0), 56 | VelocityNedYaw(1.0, 0.0, 0.0, 0.0)) 57 | await asyncio.sleep(20) 58 | 59 | await drone.action.land() 60 | 61 | print("-- Stopping offboard") 62 | try: 63 | await drone.offboard.stop() 64 | except OffboardError as error: 65 | print(f"Stopping offboard mode failed with \ 66 | error code: {error._result.result}") 67 | 68 | 69 | if __name__ == "__main__": 70 | # Run the asyncio loop 71 | asyncio.run(run()) 72 | -------------------------------------------------------------------------------- /examples/offboard_velocity_body.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | 4 | import asyncio 5 | 6 | from mavsdk import System 7 | from mavsdk.offboard import (OffboardError, VelocityBodyYawspeed) 8 | 9 | 10 | async def run(): 11 | """ Does Offboard control using velocity body coordinates. """ 12 | 13 | drone = System() 14 | await drone.connect(system_address="udp://:14540") 15 | 16 | print("Waiting for drone to connect...") 17 | async for state in drone.core.connection_state(): 18 | if state.is_connected: 19 | print(f"-- Connected to drone!") 20 | break 21 | 22 | print("Waiting for drone to have a global position estimate...") 23 | async for health in drone.telemetry.health(): 24 | if health.is_global_position_ok and health.is_home_position_ok: 25 | print("-- Global position estimate OK") 26 | break 27 | 28 | print("-- Arming") 29 | await drone.action.arm() 30 | 31 | print("-- Setting initial setpoint") 32 | await drone.offboard.set_velocity_body( 33 | VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) 34 | 35 | print("-- Starting offboard") 36 | try: 37 | await drone.offboard.start() 38 | except OffboardError as error: 39 | print(f"Starting offboard mode failed with error code: \ 40 | {error._result.result}") 41 | print("-- Disarming") 42 | await drone.action.disarm() 43 | return 44 | 45 | print("-- Turn clock-wise and climb") 46 | await drone.offboard.set_velocity_body( 47 | VelocityBodyYawspeed(0.0, 0.0, -1.0, 60.0)) 48 | await asyncio.sleep(5) 49 | 50 | print("-- Turn back anti-clockwise") 51 | await drone.offboard.set_velocity_body( 52 | VelocityBodyYawspeed(0.0, 0.0, 0.0, -60.0)) 53 | await asyncio.sleep(5) 54 | 55 | print("-- Wait for a bit") 56 | await drone.offboard.set_velocity_body( 57 | VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) 58 | await asyncio.sleep(2) 59 | 60 | print("-- Fly a circle") 61 | await drone.offboard.set_velocity_body( 62 | VelocityBodyYawspeed(5.0, 0.0, 0.0, 30.0)) 63 | await asyncio.sleep(15) 64 | 65 | print("-- Wait for a bit") 66 | await drone.offboard.set_velocity_body( 67 | VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) 68 | await asyncio.sleep(5) 69 | 70 | print("-- Fly a circle sideways") 71 | await drone.offboard.set_velocity_body( 72 | VelocityBodyYawspeed(0.0, -5.0, 0.0, 30.0)) 73 | await asyncio.sleep(15) 74 | 75 | print("-- Wait for a bit") 76 | await drone.offboard.set_velocity_body( 77 | VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) 78 | await asyncio.sleep(8) 79 | 80 | print("-- Stopping offboard") 81 | try: 82 | await drone.offboard.stop() 83 | except OffboardError as error: 84 | print(f"Stopping offboard mode failed with error code: \ 85 | {error._result.result}") 86 | 87 | 88 | if __name__ == "__main__": 89 | # Run the asyncio loop 90 | asyncio.run(run()) 91 | -------------------------------------------------------------------------------- /examples/offboard_velocity_ned.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | 4 | import asyncio 5 | 6 | from mavsdk import System 7 | from mavsdk.offboard import (OffboardError, VelocityNedYaw) 8 | 9 | 10 | async def run(): 11 | """ Does Offboard control using velocity NED coordinates. """ 12 | 13 | drone = System() 14 | await drone.connect(system_address="udp://:14540") 15 | 16 | print("Waiting for drone to connect...") 17 | async for state in drone.core.connection_state(): 18 | if state.is_connected: 19 | print(f"-- Connected to drone!") 20 | break 21 | 22 | print("Waiting for drone to have a global position estimate...") 23 | async for health in drone.telemetry.health(): 24 | if health.is_global_position_ok and health.is_home_position_ok: 25 | print("-- Global position estimate OK") 26 | break 27 | 28 | print("-- Arming") 29 | await drone.action.arm() 30 | 31 | print("-- Setting initial setpoint") 32 | await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 0.0, 0.0, 0.0)) 33 | 34 | print("-- Starting offboard") 35 | try: 36 | await drone.offboard.start() 37 | except OffboardError as error: 38 | print(f"Starting offboard mode failed with error code: \ 39 | {error._result.result}") 40 | print("-- Disarming") 41 | await drone.action.disarm() 42 | return 43 | 44 | print("-- Go up 2 m/s") 45 | await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 0.0, -2.0, 0.0)) 46 | await asyncio.sleep(4) 47 | 48 | print("-- Go North 2 m/s, turn to face East") 49 | await drone.offboard.set_velocity_ned(VelocityNedYaw(2.0, 0.0, 0.0, 90.0)) 50 | await asyncio.sleep(4) 51 | 52 | print("-- Go South 2 m/s, turn to face West") 53 | await drone.offboard.set_velocity_ned( 54 | VelocityNedYaw(-2.0, 0.0, 0.0, 270.0)) 55 | await asyncio.sleep(4) 56 | 57 | print("-- Go West 2 m/s, turn to face East") 58 | await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, -2.0, 0.0, 90.0)) 59 | await asyncio.sleep(4) 60 | 61 | print("-- Go East 2 m/s") 62 | await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 2.0, 0.0, 90.0)) 63 | await asyncio.sleep(4) 64 | 65 | print("-- Turn to face South") 66 | await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 0.0, 0.0, 180.0)) 67 | await asyncio.sleep(2) 68 | 69 | print("-- Go down 1 m/s, turn to face North") 70 | await drone.offboard.set_velocity_ned(VelocityNedYaw(0.0, 0.0, 1.0, 0.0)) 71 | await asyncio.sleep(4) 72 | 73 | print("-- Stopping offboard") 74 | try: 75 | await drone.offboard.stop() 76 | except OffboardError as error: 77 | print(f"Stopping offboard mode failed with error code: \ 78 | {error._result.result}") 79 | 80 | 81 | if __name__ == "__main__": 82 | # Run the asyncio loop 83 | asyncio.run(run()) 84 | -------------------------------------------------------------------------------- /examples/px4_ev_automation.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | """ 4 | This example can be used to switch between External Vision or 5 | MOCAP (EV) fusion and GNSS data fusion in PX4 firmware (v1.14 and later) 6 | with time-based switching. 7 | 8 | The mechanism is such that it puts the flight controller to fuse both GNSS and 9 | EV at the beginning (such that EKF2 decides which one to consume). 10 | 11 | More information: 12 | https://docs.px4.io/main/en/ros/external_position_estimation.html 13 | """ 14 | 15 | import asyncio 16 | from mavsdk import System 17 | 18 | 19 | async def set_params(system, params, announcement): 20 | print(announcement) 21 | 22 | async for _ in system.telemetry.landed_state(): 23 | break 24 | 25 | async for state in system.telemetry.landed_state(): 26 | break 27 | 28 | print(f"Landed state: {state}") 29 | 30 | 31 | async def print_status(drone): 32 | async for flight_mode in drone.telemetry.flight_mode(): 33 | print(f"Flight Mode: {flight_mode}") 34 | 35 | async for health in drone.telemetry.health(): 36 | print(f"System status: {health.is_gyrometer_calibration_ok}") 37 | 38 | async for battery in drone.telemetry.battery(): 39 | print(f"Battery: {battery.remaining_percent}%") 40 | 41 | async for in_air in drone.telemetry.in_air(): 42 | print(f"In air: {in_air}") 43 | 44 | async for armed in drone.telemetry.armed(): 45 | print(f"Armed: {armed}") 46 | 47 | 48 | async def print_mode(drone): 49 | async for flight_mode in drone.telemetry.flight_mode(): 50 | print(f"Flight Mode: {flight_mode}") 51 | 52 | 53 | async def main(): 54 | drone = System() 55 | await drone.connect(system_address="udp://:14540") 56 | 57 | print("Waiting for drone to connect...") 58 | async for state in drone.core.connection_state(): 59 | if state.is_connected: 60 | print("-- Connected to drone!") 61 | break 62 | 63 | params_preflight = [ 64 | ("EKF2_HGT_REF", 0), 65 | ("EKF2_EV_CTRL", 15), 66 | ("EKF2_GPS_CTRL", 7) 67 | ] 68 | await set_params(drone, params_preflight, "Setting preflight params...") 69 | 70 | # Wait for 5 seconds 71 | await asyncio.sleep(5) 72 | 73 | params_gps_required = [ 74 | ("EKF2_HGT_REF", 1), 75 | ("EKF2_EV_CTRL", 0), 76 | ("EKF2_GPS_CTRL", 7) 77 | ] 78 | await set_params(drone, params_gps_required, "Setting GPS params...") 79 | 80 | # Wait for 10 seconds 81 | await asyncio.sleep(10) 82 | 83 | params_ev_required = [ 84 | ("EKF2_HGT_REF", 3), 85 | ("EKF2_EV_CTRL", 15), 86 | ("EKF2_GPS_CTRL", 0) 87 | ] 88 | await set_params(drone, params_ev_required, "Setting EV params...") 89 | 90 | # Start the tasks to print flight mode and system status 91 | print_mode_task = asyncio.ensure_future(print_mode(drone)) 92 | print_status_task = asyncio.ensure_future(print_status(drone)) 93 | running_tasks = [print_mode_task, print_status_task] 94 | 95 | # Wait for the tasks to complete 96 | await asyncio.gather(*running_tasks) 97 | 98 | await drone.close() 99 | 100 | 101 | if __name__ == "__main__": 102 | asyncio.run(main()) 103 | -------------------------------------------------------------------------------- /examples/px4_ev_automation_keyboard.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | """ 4 | This example can be used to switch between External Vision or MOCAP (EV) 5 | fusion and GNSS data fusion in PX4 firmware (v1.14 and on) by using 6 | keyboard inputs from the user. 7 | 8 | The mechanism is such that it puts the flight controller to fuse both GNSS and 9 | EV at the beginning (such that EKF2 decides which one to consume). 10 | 11 | The user can later choose between different fusion types by keyboard later. 12 | 13 | More information: 14 | https://docs.px4.io/main/en/ros/external_position_estimation.html 15 | """ 16 | 17 | import asyncio 18 | from mavsdk import System 19 | 20 | 21 | async def set_params(system, params, announcement): 22 | print(announcement) 23 | 24 | async for _ in system.telemetry.landed_state(): 25 | break 26 | 27 | async for state in system.telemetry.landed_state(): 28 | break 29 | 30 | print(f"Landed state: {state}") 31 | 32 | 33 | async def main(): 34 | drone = System() 35 | await drone.connect(system_address="udp://:14540") 36 | 37 | print("Waiting for drone to connect...") 38 | async for state in drone.core.connection_state(): 39 | if state.is_connected: 40 | print("-- Connected to drone!") 41 | break 42 | 43 | params_preflight = [ 44 | ("EKF2_HGT_REF", 0), 45 | ("EKF2_EV_CTRL", 15), 46 | ("EKF2_GPS_CTRL", 7) 47 | ] 48 | await set_params(drone, params_preflight, "Setting preflight params...") 49 | 50 | params_gps_required = [ 51 | ("EKF2_HGT_REF", 1), 52 | ("EKF2_EV_CTRL", 0), 53 | ("EKF2_GPS_CTRL", 7), 54 | ] 55 | 56 | params_ev_required = [ 57 | ("EKF2_HGT_REF", 3), 58 | ("EKF2_EV_CTRL", 15), 59 | ("EKF2_GPS_CTRL", 0), 60 | ] 61 | 62 | while True: 63 | async for is_armed in drone.telemetry.armed(): 64 | if not is_armed: 65 | break 66 | 67 | async for in_air in drone.telemetry.in_air(): 68 | if not in_air: 69 | break 70 | 71 | mode = input("Enter mode ('EV', 'GPS', or 'Multi-fusion'): ") 72 | if mode.lower() == "ev": 73 | await set_params( 74 | drone, 75 | params_ev_required, 76 | "Setting airborne (EV Required) parameters..." 77 | ) 78 | break 79 | elif mode.lower() == "gps": 80 | await set_params( 81 | drone, 82 | params_gps_required, 83 | "Setting airborne (GPS Required) parameters..." 84 | ) 85 | break 86 | elif mode.lower() == "multi-fusion": 87 | await set_params( 88 | drone, 89 | params_preflight, 90 | "Setting airborne (Multi-fusion) parameters..." 91 | ) 92 | break 93 | else: 94 | print("Invalid mode: 'ev', 'gps', or 'multi-fusion'.") 95 | 96 | await drone.telemetry.close() 97 | 98 | 99 | if __name__ == "__main__": 100 | asyncio.run(main()) 101 | -------------------------------------------------------------------------------- /examples/rtcm.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | import base64 5 | from mavsdk import System 6 | from mavsdk.rtk import RtcmData 7 | 8 | 9 | async def send_data(data): 10 | drone = System() 11 | await drone.connect() 12 | await drone.rtk.send_rtcm_data(data) 13 | 14 | 15 | if __name__ == '__main__': 16 | rtcm_data = bytearray(b'\xd3\x00mCP\x00\x8c2\x16\x82\x00\x00,@\x88\x00\x00\x00\x00\x00 \x00\x00\x00~\x9c\xa4\x9a\x90\xa2\x8c\x00\x00\x01\xa7\xa2\x1e=gv\x8f\x1fq{\\x13_\xc9\xdf\x17\x02L$\xb6\xdd\x17\x9a.\xe8\xba\x94\x02U6^\xa2^\x08\xac\xf5\xf4\x1d\xcc\n\x9d\xe7\xeb\x04R\x15\x92\x93\xf9o\xf2\xc1\xb5-j\xba\xf12`@\r\x83\xc0\xe8B\x0f\x05\xec\x8c\xfc\xc4\x88l\xac\x7f\xf1\x1aR\xc2\xbc\x87') # noqa: E501 17 | # In MAVSDK 3.0.0 the data is expected to be base64 encoded string 18 | base64_rtcm_data = base64.b64encode(rtcm_data).decode('utf-8') 19 | asyncio.run(send_data(RtcmData(base64_rtcm_data))) 20 | -------------------------------------------------------------------------------- /examples/send_status_message.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | from mavsdk.server_utility import StatusTextType 6 | 7 | """ 8 | This example shows how to use server_utility plugin to send status messages. 9 | 10 | The messages will appear in GCS log. In order to debug messages you can use: 11 | - QGroundControll MAVLink Inspector 12 | - Wireshark (https://mavlink.io/en/guide/wireshark.html) 13 | 14 | In this example we are changing sysid in order to show our message along the 15 | other messages in QGroundControll interface. 16 | """ 17 | 18 | 19 | async def run(): 20 | 21 | drone = System(sysid=1) 22 | await drone.connect(system_address="udp://:14540") 23 | 24 | print("Waiting for drone to connect...") 25 | async for state in drone.core.connection_state(): 26 | if state.is_connected: 27 | print(f"-- Connected to drone!") 28 | await drone.server_utility.send_status_text( 29 | StatusTextType.INFO, "Hello world!") 30 | break 31 | 32 | if __name__ == "__main__": 33 | # Run the asyncio loop 34 | asyncio.run(run()) 35 | -------------------------------------------------------------------------------- /examples/shell.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | import sys 5 | 6 | from mavsdk import System 7 | 8 | 9 | async def run(): 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | asyncio.ensure_future(observe_shell(drone)) 14 | 15 | print("Waiting for drone to connect...") 16 | async for state in drone.core.connection_state(): 17 | if state.is_connected: 18 | print(f"-- Connected to drone!") 19 | break 20 | 21 | asyncio.get_event_loop().add_reader(sys.stdin, got_stdin_data, drone) 22 | print("nsh> ", end='', flush=True) 23 | 24 | 25 | async def observe_shell(drone): 26 | async for output in drone.shell.receive(): 27 | print(f"\n{output} ", end='', flush=True) 28 | 29 | 30 | def got_stdin_data(drone): 31 | asyncio.ensure_future(send(drone, sys.stdin.readline())) 32 | 33 | 34 | async def send(drone, command): 35 | await drone.shell.send(command) 36 | 37 | 38 | if __name__ == "__main__": 39 | asyncio.ensure_future(run()) 40 | 41 | try: 42 | asyncio.get_event_loop().run_forever() 43 | except KeyboardInterrupt: 44 | pass 45 | -------------------------------------------------------------------------------- /examples/takeoff_and_land.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | 9 | drone = System() 10 | await drone.connect(system_address="udp://:14540") 11 | 12 | status_text_task = asyncio.ensure_future(print_status_text(drone)) 13 | 14 | print("Waiting for drone to connect...") 15 | async for state in drone.core.connection_state(): 16 | if state.is_connected: 17 | print(f"-- Connected to drone!") 18 | break 19 | 20 | print("Waiting for drone to have a global position estimate...") 21 | async for health in drone.telemetry.health(): 22 | if health.is_global_position_ok and health.is_home_position_ok: 23 | print("-- Global position estimate OK") 24 | break 25 | 26 | print("-- Arming") 27 | await drone.action.arm() 28 | 29 | print("-- Taking off") 30 | await drone.action.takeoff() 31 | 32 | await asyncio.sleep(10) 33 | 34 | print("-- Landing") 35 | await drone.action.land() 36 | 37 | status_text_task.cancel() 38 | 39 | 40 | async def print_status_text(drone): 41 | try: 42 | async for status_text in drone.telemetry.status_text(): 43 | print(f"Status: {status_text.type}: {status_text.text}") 44 | except asyncio.CancelledError: 45 | return 46 | 47 | 48 | if __name__ == "__main__": 49 | # Run the asyncio loop 50 | asyncio.run(run()) 51 | -------------------------------------------------------------------------------- /examples/telemetry.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | # Init the drone 9 | drone = System() 10 | await drone.connect(system_address="udp://:14540") 11 | 12 | # Start the tasks 13 | asyncio.ensure_future(print_battery(drone)) 14 | asyncio.ensure_future(print_gps_info(drone)) 15 | asyncio.ensure_future(print_in_air(drone)) 16 | asyncio.ensure_future(print_position(drone)) 17 | 18 | while True: 19 | await asyncio.sleep(1) 20 | 21 | 22 | async def print_battery(drone): 23 | async for battery in drone.telemetry.battery(): 24 | print(f"Battery: {battery.remaining_percent}") 25 | 26 | 27 | async def print_gps_info(drone): 28 | async for gps_info in drone.telemetry.gps_info(): 29 | print(f"GPS info: {gps_info}") 30 | 31 | 32 | async def print_in_air(drone): 33 | async for in_air in drone.telemetry.in_air(): 34 | print(f"In air: {in_air}") 35 | 36 | 37 | async def print_position(drone): 38 | async for position in drone.telemetry.position(): 39 | print(position) 40 | 41 | 42 | if __name__ == "__main__": 43 | # Start the main function 44 | asyncio.run(run()) 45 | -------------------------------------------------------------------------------- /examples/telemetry_flight_mode.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def print_flight_mode(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print(f"-- Connected to drone!") 15 | break 16 | 17 | async for flight_mode in drone.telemetry.flight_mode(): 18 | print("FlightMode:", flight_mode) 19 | 20 | 21 | if __name__ == "__main__": 22 | # Start the main function 23 | asyncio.run(print_flight_mode()) 24 | -------------------------------------------------------------------------------- /examples/telemetry_is_armed_is_in_air.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | asyncio.ensure_future(print_is_armed(drone)) 12 | asyncio.ensure_future(print_is_in_air(drone)) 13 | 14 | while True: 15 | await asyncio.sleep(1) 16 | 17 | 18 | async def print_is_armed(drone): 19 | async for is_armed in drone.telemetry.armed(): 20 | print("Is_armed:", is_armed) 21 | 22 | 23 | async def print_is_in_air(drone): 24 | async for is_in_air in drone.telemetry.in_air(): 25 | print("Is_in_air:", is_in_air) 26 | 27 | 28 | if __name__ == "__main__": 29 | # Start the main function 30 | asyncio.run(run()) 31 | -------------------------------------------------------------------------------- /examples/telemetry_status_text.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def print_status_text(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print(f"-- Connected to drone!") 15 | break 16 | 17 | async for status_text in drone.telemetry.status_text(): 18 | print("Statustext:", status_text) 19 | 20 | 21 | if __name__ == "__main__": 22 | asyncio.run(print_status_text()) 23 | -------------------------------------------------------------------------------- /examples/telemetry_takeoff_and_land.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | """ 9 | This is the "main" function. 10 | It first creates the drone object and initializes it. 11 | 12 | Then it registers tasks to be run in parallel (one can think of them as 13 | threads): 14 | - print_altitude: print the altitude 15 | - print_flight_mode: print the flight mode 16 | - observe_is_in_air: this monitors the flight mode and returns when the 17 | drone has been in air and is back on the ground. 18 | 19 | Finally, it goes to the actual works: arm the drone, initiate a takeoff 20 | and finally land. 21 | 22 | Note that "observe_is_in_air" is not necessary, but it ensures that the 23 | script waits until the drone is actually landed, so that we receive 24 | feedback during the landing as well. 25 | """ 26 | 27 | # Init the drone 28 | drone = System() 29 | await drone.connect(system_address="udp://:14540") 30 | 31 | print("Waiting for drone to connect...") 32 | async for state in drone.core.connection_state(): 33 | if state.is_connected: 34 | print(f"-- Connected to drone!") 35 | break 36 | 37 | # Start parallel tasks 38 | print_altitude_task = asyncio.ensure_future(print_altitude(drone)) 39 | print_flight_mode_task = asyncio.ensure_future(print_flight_mode(drone)) 40 | 41 | running_tasks = [print_altitude_task, print_flight_mode_task] 42 | termination_task = asyncio.ensure_future( 43 | observe_is_in_air(drone, running_tasks)) 44 | 45 | async for health in drone.telemetry.health(): 46 | if health.is_global_position_ok and health.is_home_position_ok: 47 | print("-- Global position state is good enough for flying.") 48 | break 49 | 50 | # Execute the maneuvers 51 | print("-- Arming") 52 | await drone.action.arm() 53 | 54 | print("-- Taking off") 55 | await drone.action.set_takeoff_altitude(10.0) 56 | await drone.action.takeoff() 57 | 58 | await asyncio.sleep(10) 59 | 60 | print("-- Landing") 61 | await drone.action.land() 62 | 63 | # Wait until the drone is landed (instead of exiting after 'land' is sent) 64 | await termination_task 65 | 66 | 67 | async def print_altitude(drone): 68 | """ Prints the altitude when it changes """ 69 | 70 | previous_altitude = None 71 | 72 | async for position in drone.telemetry.position(): 73 | altitude = round(position.relative_altitude_m) 74 | if altitude != previous_altitude: 75 | previous_altitude = altitude 76 | print(f"Altitude: {altitude}") 77 | 78 | 79 | async def print_flight_mode(drone): 80 | """ Prints the flight mode when it changes """ 81 | 82 | previous_flight_mode = None 83 | 84 | async for flight_mode in drone.telemetry.flight_mode(): 85 | if flight_mode != previous_flight_mode: 86 | previous_flight_mode = flight_mode 87 | print(f"Flight mode: {flight_mode}") 88 | 89 | 90 | async def observe_is_in_air(drone, running_tasks): 91 | """ Monitors whether the drone is flying or not and 92 | returns after landing """ 93 | 94 | was_in_air = False 95 | 96 | async for is_in_air in drone.telemetry.in_air(): 97 | if is_in_air: 98 | was_in_air = is_in_air 99 | 100 | if was_in_air and not is_in_air: 101 | for task in running_tasks: 102 | task.cancel() 103 | try: 104 | await task 105 | except asyncio.CancelledError: 106 | pass 107 | await asyncio.get_event_loop().shutdown_asyncgens() 108 | return 109 | 110 | 111 | if __name__ == "__main__": 112 | # Start the main function 113 | asyncio.run(run()) 114 | -------------------------------------------------------------------------------- /examples/transponder.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | # Init the drone 9 | drone = System() 10 | await drone.connect() 11 | 12 | # Start the tasks 13 | asyncio.ensure_future(print_transponders(drone)) 14 | 15 | # Runs the event loop until the program is canceled with e.g. CTRL-C 16 | while True: 17 | print("Waiting for transponder messages") 18 | await asyncio.sleep(1) 19 | 20 | 21 | async def print_transponders(drone): 22 | async for transponder in drone.transponder.transponder(): 23 | print(transponder) 24 | 25 | 26 | if __name__ == "__main__": 27 | # Start the main function 28 | asyncio.run(run()) 29 | -------------------------------------------------------------------------------- /examples/tune.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | from mavsdk.tune import (SongElement, TuneDescription, TuneError) 6 | 7 | 8 | async def run(): 9 | 10 | drone = System() 11 | await drone.connect(system_address="udp://:14540") 12 | 13 | print("Waiting for drone to connect...") 14 | async for state in drone.core.connection_state(): 15 | if state.is_connected: 16 | print(f"-- Connected to drone!") 17 | break 18 | 19 | song_elements = [] 20 | song_elements.append(SongElement.DURATION_4) 21 | song_elements.append(SongElement.NOTE_G) 22 | song_elements.append(SongElement.NOTE_A) 23 | song_elements.append(SongElement.NOTE_B) 24 | song_elements.append(SongElement.FLAT) 25 | song_elements.append(SongElement.OCTAVE_UP) 26 | song_elements.append(SongElement.DURATION_1) 27 | song_elements.append(SongElement.NOTE_E) 28 | song_elements.append(SongElement.FLAT) 29 | song_elements.append(SongElement.OCTAVE_DOWN) 30 | song_elements.append(SongElement.DURATION_4) 31 | song_elements.append(SongElement.NOTE_PAUSE) 32 | song_elements.append(SongElement.NOTE_F) 33 | song_elements.append(SongElement.NOTE_G) 34 | song_elements.append(SongElement.NOTE_A) 35 | song_elements.append(SongElement.OCTAVE_UP) 36 | song_elements.append(SongElement.DURATION_2) 37 | song_elements.append(SongElement.NOTE_D) 38 | song_elements.append(SongElement.NOTE_D) 39 | song_elements.append(SongElement.OCTAVE_DOWN) 40 | song_elements.append(SongElement.DURATION_4) 41 | song_elements.append(SongElement.NOTE_PAUSE) 42 | song_elements.append(SongElement.NOTE_E) 43 | song_elements.append(SongElement.FLAT) 44 | song_elements.append(SongElement.NOTE_F) 45 | song_elements.append(SongElement.NOTE_G) 46 | song_elements.append(SongElement.OCTAVE_UP) 47 | song_elements.append(SongElement.DURATION_1) 48 | song_elements.append(SongElement.NOTE_C) 49 | song_elements.append(SongElement.OCTAVE_DOWN) 50 | song_elements.append(SongElement.DURATION_4) 51 | song_elements.append(SongElement.NOTE_PAUSE) 52 | song_elements.append(SongElement.NOTE_A) 53 | song_elements.append(SongElement.OCTAVE_UP) 54 | song_elements.append(SongElement.NOTE_C) 55 | song_elements.append(SongElement.OCTAVE_DOWN) 56 | song_elements.append(SongElement.NOTE_B) 57 | song_elements.append(SongElement.FLAT) 58 | song_elements.append(SongElement.DURATION_2) 59 | song_elements.append(SongElement.NOTE_G) 60 | 61 | tune_description = TuneDescription(song_elements, 200) 62 | await drone.tune.play_tune(tune_description) 63 | 64 | print("Tune played") 65 | 66 | if __name__ == "__main__": 67 | # Run the asyncio loop 68 | asyncio.run(run()) 69 | -------------------------------------------------------------------------------- /examples/upload_params.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import asyncio 4 | import argparse 5 | from mavsdk import System 6 | from tqdm import tqdm 7 | 8 | 9 | def main(): 10 | parser = argparse.ArgumentParser() 11 | parser.add_argument( 12 | "connection", 13 | help="Connection string (e.g. udp://:14540)") 14 | parser.add_argument( 15 | "param_file", help="Param file to be uploaded with .params format") 16 | 17 | args = parser.parse_args() 18 | 19 | asyncio.run(set_params(args)) 20 | 21 | 22 | async def set_params(args): 23 | drone = System() 24 | await drone.connect(system_address=args.connection) 25 | print("Connected to the Vehicle") 26 | param_plugin = drone.param 27 | params = await param_plugin.get_all_params() 28 | float_params = params.float_params 29 | int_params = params.int_params 30 | custom_params = params.custom_params 31 | int_param_names = [p.name for p in int_params] 32 | float_param_names = [p.name for p in float_params] 33 | custom_param_names = [p.name for p in custom_params] 34 | 35 | async for is_in_air in drone.telemetry.in_air(): 36 | if is_in_air: 37 | print("Waiting until vehicle is landed...") 38 | else: 39 | break 40 | 41 | with open(args.param_file, "r") as param_file: 42 | print("Uploading Parameters... Please do not arm the vehicle!") 43 | for line in tqdm(param_file, unit='lines'): 44 | if line.startswith("#"): 45 | continue 46 | 47 | columns = line.strip().split("\t") 48 | vehicle_id = columns[0] 49 | component_id = columns[1] 50 | name = columns[2] 51 | value = columns[3] 52 | type = columns[4] 53 | if name in int_param_names: 54 | await drone.param.set_param_int(name, int(value)) 55 | elif name in float_param_names: 56 | await drone.param.set_param_float(name, float(value)) 57 | elif name in custom_param_names: 58 | await drone.param.set_param_custom(name, value) 59 | 60 | print("Params uploaded!") 61 | 62 | 63 | if __name__ == "__main__": 64 | main() 65 | -------------------------------------------------------------------------------- /examples/winch.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import asyncio 4 | from mavsdk import System 5 | 6 | 7 | async def run(): 8 | drone = System() 9 | await drone.connect(system_address="udp://:14540") 10 | 11 | print("Waiting for drone to connect...") 12 | async for state in drone.core.connection_state(): 13 | if state.is_connected: 14 | print(f"-- Connected to drone!") 15 | break 16 | 17 | print(f"-- Winch action: load payload") 18 | await drone.winch.load_payload(instance=1) 19 | 20 | while True: 21 | print("Staying connected, press Ctrl-C to exit") 22 | await asyncio.sleep(1) 23 | 24 | 25 | if __name__ == "__main__": 26 | # Run the asyncio loop 27 | asyncio.run(run()) 28 | -------------------------------------------------------------------------------- /mavsdk/Makefile: -------------------------------------------------------------------------------- 1 | # Minimal makefile for Sphinx documentation 2 | # 3 | 4 | # You can set these variables from the command line, and also 5 | # from the environment for the first two. 6 | SPHINXOPTS ?= 7 | SPHINXBUILD ?= sphinx-build 8 | SOURCEDIR = source 9 | BUILDDIR = build 10 | 11 | # Put it first so that "make" without argument is like "make help". 12 | help: 13 | @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 14 | 15 | .PHONY: help Makefile 16 | 17 | # Catch-all target: route all unknown targets to Sphinx using the new 18 | # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). 19 | %: Makefile 20 | @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 21 | -------------------------------------------------------------------------------- /mavsdk/__init__.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | import asyncio 4 | import platform 5 | import sys 6 | 7 | from .system import System 8 | 9 | # Check for compatibility 10 | (major, minor, _) = platform.python_version_tuple() 11 | if not ((int(major) >= 3 and int(minor) >= 6) or (int(major) >= 4)): 12 | print("[!] MAVSDK-Python is only available on Python >= 3.6") 13 | sys.exit(1) 14 | 15 | # Do asyncio specific initialization 16 | try: 17 | # Try to import uvloop, provides _MUCH_ better performance compared to the 18 | # standart unix selector event loop 19 | import uvloop 20 | asyncio.set_event_loop_policy(uvloop.EventLoopPolicy()) 21 | except ImportError: 22 | # No uvloop installed on the system; the default eventloop works as well! 23 | pass 24 | -------------------------------------------------------------------------------- /mavsdk/_base.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | 3 | 4 | class AsyncBase: 5 | """ 6 | Base implementation for the async gRPC connection 7 | """ 8 | 9 | def __init__(self, async_plugin_manager): 10 | self._init_plugin(async_plugin_manager) 11 | 12 | def _init_plugin(self, async_plugin_manager): 13 | """ 14 | Sort of "registers" the plugin to the backend 15 | """ 16 | if async_plugin_manager: 17 | self._setup_stub(async_plugin_manager.channel) 18 | 19 | def _setup_stub(self, channel): 20 | """ 21 | Actual stub setup for the Plugins 22 | """ 23 | raise NotImplementedError() 24 | -------------------------------------------------------------------------------- /mavsdk/async_plugin_manager.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | import logging 3 | from grpc import aio 4 | 5 | 6 | class AsyncPluginManager: 7 | """ 8 | Connects to a running mavsdk server or starts one and manages plugins 9 | """ 10 | @classmethod 11 | async def create(cls, host, port=50051): 12 | 13 | self = AsyncPluginManager() 14 | 15 | self.host = host 16 | self.port = port 17 | self.plugins = {} 18 | 19 | await self._connect_backend() 20 | 21 | return self 22 | 23 | async def _connect_backend(self): 24 | """ 25 | Initializes the connection to the running backend 26 | """ 27 | 28 | #: gRPC channel 29 | self._channel = aio.insecure_channel( 30 | "{}:{}".format(self.host, self.port) 31 | ) 32 | 33 | logger = logging.getLogger(__name__) 34 | logger.addHandler(logging.NullHandler()) # Avoid errors when user has not configured logging 35 | 36 | logger.debug("Waiting for mavsdk_server to be ready...") 37 | await self._channel.channel_ready() 38 | logger.debug("Connected to mavsdk_server!") 39 | 40 | @property 41 | def channel(self): 42 | """ 43 | gRPC channel to the backend 44 | """ 45 | return self._channel 46 | -------------------------------------------------------------------------------- /mavsdk/bin/README.md: -------------------------------------------------------------------------------- 1 | It is expected that the grpc server binary `mavsdk_server` is present here when the wheel is built with: 2 | 3 | python3 setup.py bdist_wheel 4 | -------------------------------------------------------------------------------- /mavsdk/bin/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/mavsdk/bin/__init__.py -------------------------------------------------------------------------------- /mavsdk/component_metadata_server.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # DO NOT EDIT! This file is auto-generated from 3 | # https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py 4 | from ._base import AsyncBase 5 | from . import component_metadata_server_pb2, component_metadata_server_pb2_grpc 6 | from enum import Enum 7 | 8 | 9 | class MetadataType(Enum): 10 | """ 11 | The metadata type 12 | 13 | Values 14 | ------ 15 | PARAMETER 16 | Parameter metadata 17 | 18 | EVENTS 19 | Event definitions 20 | 21 | ACTUATORS 22 | Actuator definitions 23 | 24 | """ 25 | 26 | 27 | PARAMETER = 0 28 | EVENTS = 1 29 | ACTUATORS = 2 30 | 31 | def translate_to_rpc(self): 32 | if self == MetadataType.PARAMETER: 33 | return component_metadata_server_pb2.METADATA_TYPE_PARAMETER 34 | if self == MetadataType.EVENTS: 35 | return component_metadata_server_pb2.METADATA_TYPE_EVENTS 36 | if self == MetadataType.ACTUATORS: 37 | return component_metadata_server_pb2.METADATA_TYPE_ACTUATORS 38 | 39 | @staticmethod 40 | def translate_from_rpc(rpc_enum_value): 41 | """ Parses a gRPC response """ 42 | if rpc_enum_value == component_metadata_server_pb2.METADATA_TYPE_PARAMETER: 43 | return MetadataType.PARAMETER 44 | if rpc_enum_value == component_metadata_server_pb2.METADATA_TYPE_EVENTS: 45 | return MetadataType.EVENTS 46 | if rpc_enum_value == component_metadata_server_pb2.METADATA_TYPE_ACTUATORS: 47 | return MetadataType.ACTUATORS 48 | 49 | def __str__(self): 50 | return self.name 51 | 52 | 53 | class Metadata: 54 | """ 55 | The metadata type and content 56 | 57 | Parameters 58 | ---------- 59 | type : MetadataType 60 | The metadata type 61 | 62 | json_metadata : std::string 63 | The JSON metadata 64 | 65 | """ 66 | 67 | 68 | 69 | def __init__( 70 | self, 71 | type, 72 | json_metadata): 73 | """ Initializes the Metadata object """ 74 | self.type = type 75 | self.json_metadata = json_metadata 76 | 77 | def __eq__(self, to_compare): 78 | """ Checks if two Metadata are the same """ 79 | try: 80 | # Try to compare - this likely fails when it is compared to a non 81 | # Metadata object 82 | return \ 83 | (self.type == to_compare.type) and \ 84 | (self.json_metadata == to_compare.json_metadata) 85 | 86 | except AttributeError: 87 | return False 88 | 89 | def __str__(self): 90 | """ Metadata in string representation """ 91 | struct_repr = ", ".join([ 92 | "type: " + str(self.type), 93 | "json_metadata: " + str(self.json_metadata) 94 | ]) 95 | 96 | return f"Metadata: [{struct_repr}]" 97 | 98 | @staticmethod 99 | def translate_from_rpc(rpcMetadata): 100 | """ Translates a gRPC struct to the SDK equivalent """ 101 | return Metadata( 102 | 103 | MetadataType.translate_from_rpc(rpcMetadata.type), 104 | 105 | 106 | rpcMetadata.json_metadata 107 | ) 108 | 109 | def translate_to_rpc(self, rpcMetadata): 110 | """ Translates this SDK object into its gRPC equivalent """ 111 | 112 | 113 | 114 | 115 | rpcMetadata.type = self.type.translate_to_rpc() 116 | 117 | 118 | 119 | 120 | 121 | rpcMetadata.json_metadata = self.json_metadata 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | class ComponentMetadataServer(AsyncBase): 130 | """ 131 | Provide component metadata json definitions, such as parameters. 132 | 133 | Generated by dcsdkgen - MAVSDK ComponentMetadataServer API 134 | """ 135 | 136 | # Plugin name 137 | name = "ComponentMetadataServer" 138 | 139 | def _setup_stub(self, channel): 140 | """ Setups the api stub """ 141 | self._stub = component_metadata_server_pb2_grpc.ComponentMetadataServerServiceStub(channel) 142 | 143 | 144 | 145 | async def set_metadata(self, metadata): 146 | """ 147 | Provide metadata (can only be called once) 148 | 149 | Parameters 150 | ---------- 151 | metadata : [Metadata] 152 | List of metadata 153 | 154 | 155 | """ 156 | 157 | request = component_metadata_server_pb2.SetMetadataRequest() 158 | 159 | rpc_elems_list = [] 160 | for elem in metadata: 161 | 162 | rpc_elem = component_metadata_server_pb2.Metadata() 163 | elem.translate_to_rpc(rpc_elem) 164 | rpc_elems_list.append(rpc_elem) 165 | 166 | request.metadata.extend(rpc_elems_list) 167 | 168 | 169 | response = await self._stub.SetMetadata(request) 170 | 171 | -------------------------------------------------------------------------------- /mavsdk/component_metadata_server_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: component_metadata_server/component_metadata_server.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'component_metadata_server/component_metadata_server.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n9component_metadata_server/component_metadata_server.proto\x12$mavsdk.rpc.component_metadata_server\x1a\x14mavsdk_options.proto\"V\n\x12SetMetadataRequest\x12@\n\x08metadata\x18\x01 \x03(\x0b\x32..mavsdk.rpc.component_metadata_server.Metadata\"\x15\n\x13SetMetadataResponse\"c\n\x08Metadata\x12@\n\x04type\x18\x01 \x01(\x0e\x32\x32.mavsdk.rpc.component_metadata_server.MetadataType\x12\x15\n\rjson_metadata\x18\x02 \x01(\t*b\n\x0cMetadataType\x12\x1b\n\x17METADATA_TYPE_PARAMETER\x10\x00\x12\x18\n\x14METADATA_TYPE_EVENTS\x10\x01\x12\x1b\n\x17METADATA_TYPE_ACTUATORS\x10\x02\x32\xab\x01\n\x1e\x43omponentMetadataServerService\x12\x88\x01\n\x0bSetMetadata\x12\x38.mavsdk.rpc.component_metadata_server.SetMetadataRequest\x1a\x39.mavsdk.rpc.component_metadata_server.SetMetadataResponse\"\x04\x80\xb5\x18\x01\x42\x43\n#io.mavsdk.component_metadata_serverB\x1c\x43omponentMetadataServerProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'component_metadata_server.component_metadata_server_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n#io.mavsdk.component_metadata_serverB\034ComponentMetadataServerProto' 36 | _globals['_COMPONENTMETADATASERVERSERVICE'].methods_by_name['SetMetadata']._loaded_options = None 37 | _globals['_COMPONENTMETADATASERVERSERVICE'].methods_by_name['SetMetadata']._serialized_options = b'\200\265\030\001' 38 | _globals['_METADATATYPE']._serialized_start=333 39 | _globals['_METADATATYPE']._serialized_end=431 40 | _globals['_SETMETADATAREQUEST']._serialized_start=121 41 | _globals['_SETMETADATAREQUEST']._serialized_end=207 42 | _globals['_SETMETADATARESPONSE']._serialized_start=209 43 | _globals['_SETMETADATARESPONSE']._serialized_end=230 44 | _globals['_METADATA']._serialized_start=232 45 | _globals['_METADATA']._serialized_end=331 46 | _globals['_COMPONENTMETADATASERVERSERVICE']._serialized_start=434 47 | _globals['_COMPONENTMETADATASERVERSERVICE']._serialized_end=605 48 | # @@protoc_insertion_point(module_scope) 49 | -------------------------------------------------------------------------------- /mavsdk/component_metadata_server_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | from . import component_metadata_server_pb2 as component__metadata__server_dot_component__metadata__server__pb2 7 | 8 | GRPC_GENERATED_VERSION = '1.71.0' 9 | GRPC_VERSION = grpc.__version__ 10 | _version_not_supported = False 11 | 12 | try: 13 | from grpc._utilities import first_version_is_lower 14 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 15 | except ImportError: 16 | _version_not_supported = True 17 | 18 | if _version_not_supported: 19 | raise RuntimeError( 20 | f'The grpc package installed is at version {GRPC_VERSION},' 21 | + f' but the generated code in component_metadata_server/component_metadata_server_pb2_grpc.py depends on' 22 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 23 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 24 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 25 | ) 26 | 27 | 28 | class ComponentMetadataServerServiceStub(object): 29 | """Provide component metadata json definitions, such as parameters. 30 | """ 31 | 32 | def __init__(self, channel): 33 | """Constructor. 34 | 35 | Args: 36 | channel: A grpc.Channel. 37 | """ 38 | self.SetMetadata = channel.unary_unary( 39 | '/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata', 40 | request_serializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.SerializeToString, 41 | response_deserializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.FromString, 42 | _registered_method=True) 43 | 44 | 45 | class ComponentMetadataServerServiceServicer(object): 46 | """Provide component metadata json definitions, such as parameters. 47 | """ 48 | 49 | def SetMetadata(self, request, context): 50 | """ 51 | Provide metadata (can only be called once) 52 | """ 53 | context.set_code(grpc.StatusCode.UNIMPLEMENTED) 54 | context.set_details('Method not implemented!') 55 | raise NotImplementedError('Method not implemented!') 56 | 57 | 58 | def add_ComponentMetadataServerServiceServicer_to_server(servicer, server): 59 | rpc_method_handlers = { 60 | 'SetMetadata': grpc.unary_unary_rpc_method_handler( 61 | servicer.SetMetadata, 62 | request_deserializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.FromString, 63 | response_serializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.SerializeToString, 64 | ), 65 | } 66 | generic_handler = grpc.method_handlers_generic_handler( 67 | 'mavsdk.rpc.component_metadata_server.ComponentMetadataServerService', rpc_method_handlers) 68 | server.add_generic_rpc_handlers((generic_handler,)) 69 | server.add_registered_method_handlers('mavsdk.rpc.component_metadata_server.ComponentMetadataServerService', rpc_method_handlers) 70 | 71 | 72 | # This class is part of an EXPERIMENTAL API. 73 | class ComponentMetadataServerService(object): 74 | """Provide component metadata json definitions, such as parameters. 75 | """ 76 | 77 | @staticmethod 78 | def SetMetadata(request, 79 | target, 80 | options=(), 81 | channel_credentials=None, 82 | call_credentials=None, 83 | insecure=False, 84 | compression=None, 85 | wait_for_ready=None, 86 | timeout=None, 87 | metadata=None): 88 | return grpc.experimental.unary_unary( 89 | request, 90 | target, 91 | '/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata', 92 | component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.SerializeToString, 93 | component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.FromString, 94 | options, 95 | channel_credentials, 96 | insecure, 97 | call_credentials, 98 | compression, 99 | wait_for_ready, 100 | timeout, 101 | metadata, 102 | _registered_method=True) 103 | -------------------------------------------------------------------------------- /mavsdk/core.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # DO NOT EDIT! This file is auto-generated from 3 | # https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py 4 | from ._base import AsyncBase 5 | from . import core_pb2, core_pb2_grpc 6 | from enum import Enum 7 | 8 | 9 | class ConnectionState: 10 | """ 11 | Connection state type. 12 | 13 | Parameters 14 | ---------- 15 | is_connected : bool 16 | Whether the vehicle got connected or disconnected 17 | 18 | """ 19 | 20 | 21 | 22 | def __init__( 23 | self, 24 | is_connected): 25 | """ Initializes the ConnectionState object """ 26 | self.is_connected = is_connected 27 | 28 | def __eq__(self, to_compare): 29 | """ Checks if two ConnectionState are the same """ 30 | try: 31 | # Try to compare - this likely fails when it is compared to a non 32 | # ConnectionState object 33 | return \ 34 | (self.is_connected == to_compare.is_connected) 35 | 36 | except AttributeError: 37 | return False 38 | 39 | def __str__(self): 40 | """ ConnectionState in string representation """ 41 | struct_repr = ", ".join([ 42 | "is_connected: " + str(self.is_connected) 43 | ]) 44 | 45 | return f"ConnectionState: [{struct_repr}]" 46 | 47 | @staticmethod 48 | def translate_from_rpc(rpcConnectionState): 49 | """ Translates a gRPC struct to the SDK equivalent """ 50 | return ConnectionState( 51 | 52 | rpcConnectionState.is_connected 53 | ) 54 | 55 | def translate_to_rpc(self, rpcConnectionState): 56 | """ Translates this SDK object into its gRPC equivalent """ 57 | 58 | 59 | 60 | 61 | rpcConnectionState.is_connected = self.is_connected 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | class Core(AsyncBase): 70 | """ 71 | Access to the connection state and core configurations 72 | 73 | Generated by dcsdkgen - MAVSDK Core API 74 | """ 75 | 76 | # Plugin name 77 | name = "Core" 78 | 79 | def _setup_stub(self, channel): 80 | """ Setups the api stub """ 81 | self._stub = core_pb2_grpc.CoreServiceStub(channel) 82 | 83 | 84 | 85 | async def connection_state(self): 86 | """ 87 | Subscribe to 'connection state' updates. 88 | 89 | Yields 90 | ------- 91 | connection_state : ConnectionState 92 | Connection state 93 | 94 | 95 | """ 96 | 97 | request = core_pb2.SubscribeConnectionStateRequest() 98 | connection_state_stream = self._stub.SubscribeConnectionState(request) 99 | 100 | try: 101 | async for response in connection_state_stream: 102 | 103 | 104 | 105 | yield ConnectionState.translate_from_rpc(response.connection_state) 106 | finally: 107 | connection_state_stream.cancel() 108 | 109 | async def set_mavlink_timeout(self, timeout_s): 110 | """ 111 | Set timeout of MAVLink transfers. 112 | 113 | The default timeout used is generally (0.5 seconds) seconds. 114 | If MAVSDK is used on the same host this timeout can be reduced, while 115 | if MAVSDK has to communicate over links with high latency it might 116 | need to be increased to prevent timeouts. 117 | 118 | Parameters 119 | ---------- 120 | timeout_s : double 121 | Timeout in seconds 122 | 123 | 124 | """ 125 | 126 | request = core_pb2.SetMavlinkTimeoutRequest() 127 | request.timeout_s = timeout_s 128 | response = await self._stub.SetMavlinkTimeout(request) 129 | 130 | -------------------------------------------------------------------------------- /mavsdk/core_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: core/core.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'core/core.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | 26 | 27 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x0f\x63ore/core.proto\x12\x0fmavsdk.rpc.core\"!\n\x1fSubscribeConnectionStateRequest\"U\n\x17\x43onnectionStateResponse\x12:\n\x10\x63onnection_state\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.core.ConnectionState\"-\n\x18SetMavlinkTimeoutRequest\x12\x11\n\ttimeout_s\x18\x01 \x01(\x01\"\x1b\n\x19SetMavlinkTimeoutResponse\"\'\n\x0f\x43onnectionState\x12\x14\n\x0cis_connected\x18\x02 \x01(\x08\x32\xf7\x01\n\x0b\x43oreService\x12z\n\x18SubscribeConnectionState\x12\x30.mavsdk.rpc.core.SubscribeConnectionStateRequest\x1a(.mavsdk.rpc.core.ConnectionStateResponse\"\x00\x30\x01\x12l\n\x11SetMavlinkTimeout\x12).mavsdk.rpc.core.SetMavlinkTimeoutRequest\x1a*.mavsdk.rpc.core.SetMavlinkTimeoutResponse\"\x00\x42\x1b\n\x0eio.mavsdk.coreB\tCoreProtob\x06proto3') 28 | 29 | _globals = globals() 30 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 31 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'core.core_pb2', _globals) 32 | if not _descriptor._USE_C_DESCRIPTORS: 33 | _globals['DESCRIPTOR']._loaded_options = None 34 | _globals['DESCRIPTOR']._serialized_options = b'\n\016io.mavsdk.coreB\tCoreProto' 35 | _globals['_SUBSCRIBECONNECTIONSTATEREQUEST']._serialized_start=36 36 | _globals['_SUBSCRIBECONNECTIONSTATEREQUEST']._serialized_end=69 37 | _globals['_CONNECTIONSTATERESPONSE']._serialized_start=71 38 | _globals['_CONNECTIONSTATERESPONSE']._serialized_end=156 39 | _globals['_SETMAVLINKTIMEOUTREQUEST']._serialized_start=158 40 | _globals['_SETMAVLINKTIMEOUTREQUEST']._serialized_end=203 41 | _globals['_SETMAVLINKTIMEOUTRESPONSE']._serialized_start=205 42 | _globals['_SETMAVLINKTIMEOUTRESPONSE']._serialized_end=232 43 | _globals['_CONNECTIONSTATE']._serialized_start=234 44 | _globals['_CONNECTIONSTATE']._serialized_end=273 45 | _globals['_CORESERVICE']._serialized_start=276 46 | _globals['_CORESERVICE']._serialized_end=523 47 | # @@protoc_insertion_point(module_scope) 48 | -------------------------------------------------------------------------------- /mavsdk/failure_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: failure/failure.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'failure/failure.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x15\x66\x61ilure/failure.proto\x12\x12mavsdk.rpc.failure\x1a\x14mavsdk_options.proto\"\x8f\x01\n\rInjectRequest\x12\x35\n\x0c\x66\x61ilure_unit\x18\x01 \x01(\x0e\x32\x1f.mavsdk.rpc.failure.FailureUnit\x12\x35\n\x0c\x66\x61ilure_type\x18\x02 \x01(\x0e\x32\x1f.mavsdk.rpc.failure.FailureType\x12\x10\n\x08instance\x18\x03 \x01(\x05\"K\n\x0eInjectResponse\x12\x39\n\x0e\x66\x61ilure_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.failure.FailureResult\"\x97\x02\n\rFailureResult\x12\x38\n\x06result\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.failure.FailureResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xb7\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x04\x12\x11\n\rRESULT_DENIED\x10\x05\x12\x13\n\x0fRESULT_DISABLED\x10\x06\x12\x12\n\x0eRESULT_TIMEOUT\x10\x07*\xfd\x03\n\x0b\x46\x61ilureUnit\x12\x1c\n\x18\x46\x41ILURE_UNIT_SENSOR_GYRO\x10\x00\x12\x1d\n\x19\x46\x41ILURE_UNIT_SENSOR_ACCEL\x10\x01\x12\x1b\n\x17\x46\x41ILURE_UNIT_SENSOR_MAG\x10\x02\x12\x1c\n\x18\x46\x41ILURE_UNIT_SENSOR_BARO\x10\x03\x12\x1b\n\x17\x46\x41ILURE_UNIT_SENSOR_GPS\x10\x04\x12$\n FAILURE_UNIT_SENSOR_OPTICAL_FLOW\x10\x05\x12\x1b\n\x17\x46\x41ILURE_UNIT_SENSOR_VIO\x10\x06\x12\'\n#FAILURE_UNIT_SENSOR_DISTANCE_SENSOR\x10\x07\x12 \n\x1c\x46\x41ILURE_UNIT_SENSOR_AIRSPEED\x10\x08\x12\x1f\n\x1b\x46\x41ILURE_UNIT_SYSTEM_BATTERY\x10\x64\x12\x1d\n\x19\x46\x41ILURE_UNIT_SYSTEM_MOTOR\x10\x65\x12\x1d\n\x19\x46\x41ILURE_UNIT_SYSTEM_SERVO\x10\x66\x12!\n\x1d\x46\x41ILURE_UNIT_SYSTEM_AVOIDANCE\x10g\x12!\n\x1d\x46\x41ILURE_UNIT_SYSTEM_RC_SIGNAL\x10h\x12&\n\"FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL\x10i*\xd2\x01\n\x0b\x46\x61ilureType\x12\x13\n\x0f\x46\x41ILURE_TYPE_OK\x10\x00\x12\x14\n\x10\x46\x41ILURE_TYPE_OFF\x10\x01\x12\x16\n\x12\x46\x41ILURE_TYPE_STUCK\x10\x02\x12\x18\n\x14\x46\x41ILURE_TYPE_GARBAGE\x10\x03\x12\x16\n\x12\x46\x41ILURE_TYPE_WRONG\x10\x04\x12\x15\n\x11\x46\x41ILURE_TYPE_SLOW\x10\x05\x12\x18\n\x14\x46\x41ILURE_TYPE_DELAYED\x10\x06\x12\x1d\n\x19\x46\x41ILURE_TYPE_INTERMITTENT\x10\x07\x32g\n\x0e\x46\x61ilureService\x12U\n\x06Inject\x12!.mavsdk.rpc.failure.InjectRequest\x1a\".mavsdk.rpc.failure.InjectResponse\"\x04\x80\xb5\x18\x01\x42!\n\x11io.mavsdk.failureB\x0c\x46\x61ilureProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'failure.failure_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\021io.mavsdk.failureB\014FailureProto' 36 | _globals['_FAILURESERVICE'].methods_by_name['Inject']._loaded_options = None 37 | _globals['_FAILURESERVICE'].methods_by_name['Inject']._serialized_options = b'\200\265\030\001' 38 | _globals['_FAILUREUNIT']._serialized_start=573 39 | _globals['_FAILUREUNIT']._serialized_end=1082 40 | _globals['_FAILURETYPE']._serialized_start=1085 41 | _globals['_FAILURETYPE']._serialized_end=1295 42 | _globals['_INJECTREQUEST']._serialized_start=68 43 | _globals['_INJECTREQUEST']._serialized_end=211 44 | _globals['_INJECTRESPONSE']._serialized_start=213 45 | _globals['_INJECTRESPONSE']._serialized_end=288 46 | _globals['_FAILURERESULT']._serialized_start=291 47 | _globals['_FAILURERESULT']._serialized_end=570 48 | _globals['_FAILURERESULT_RESULT']._serialized_start=387 49 | _globals['_FAILURERESULT_RESULT']._serialized_end=570 50 | _globals['_FAILURESERVICE']._serialized_start=1297 51 | _globals['_FAILURESERVICE']._serialized_end=1400 52 | # @@protoc_insertion_point(module_scope) 53 | -------------------------------------------------------------------------------- /mavsdk/failure_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | from . import failure_pb2 as failure_dot_failure__pb2 7 | 8 | GRPC_GENERATED_VERSION = '1.71.0' 9 | GRPC_VERSION = grpc.__version__ 10 | _version_not_supported = False 11 | 12 | try: 13 | from grpc._utilities import first_version_is_lower 14 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 15 | except ImportError: 16 | _version_not_supported = True 17 | 18 | if _version_not_supported: 19 | raise RuntimeError( 20 | f'The grpc package installed is at version {GRPC_VERSION},' 21 | + f' but the generated code in failure/failure_pb2_grpc.py depends on' 22 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 23 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 24 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 25 | ) 26 | 27 | 28 | class FailureServiceStub(object): 29 | """Inject failures into system to test failsafes. 30 | """ 31 | 32 | def __init__(self, channel): 33 | """Constructor. 34 | 35 | Args: 36 | channel: A grpc.Channel. 37 | """ 38 | self.Inject = channel.unary_unary( 39 | '/mavsdk.rpc.failure.FailureService/Inject', 40 | request_serializer=failure_dot_failure__pb2.InjectRequest.SerializeToString, 41 | response_deserializer=failure_dot_failure__pb2.InjectResponse.FromString, 42 | _registered_method=True) 43 | 44 | 45 | class FailureServiceServicer(object): 46 | """Inject failures into system to test failsafes. 47 | """ 48 | 49 | def Inject(self, request, context): 50 | """Injects a failure. 51 | """ 52 | context.set_code(grpc.StatusCode.UNIMPLEMENTED) 53 | context.set_details('Method not implemented!') 54 | raise NotImplementedError('Method not implemented!') 55 | 56 | 57 | def add_FailureServiceServicer_to_server(servicer, server): 58 | rpc_method_handlers = { 59 | 'Inject': grpc.unary_unary_rpc_method_handler( 60 | servicer.Inject, 61 | request_deserializer=failure_dot_failure__pb2.InjectRequest.FromString, 62 | response_serializer=failure_dot_failure__pb2.InjectResponse.SerializeToString, 63 | ), 64 | } 65 | generic_handler = grpc.method_handlers_generic_handler( 66 | 'mavsdk.rpc.failure.FailureService', rpc_method_handlers) 67 | server.add_generic_rpc_handlers((generic_handler,)) 68 | server.add_registered_method_handlers('mavsdk.rpc.failure.FailureService', rpc_method_handlers) 69 | 70 | 71 | # This class is part of an EXPERIMENTAL API. 72 | class FailureService(object): 73 | """Inject failures into system to test failsafes. 74 | """ 75 | 76 | @staticmethod 77 | def Inject(request, 78 | target, 79 | options=(), 80 | channel_credentials=None, 81 | call_credentials=None, 82 | insecure=False, 83 | compression=None, 84 | wait_for_ready=None, 85 | timeout=None, 86 | metadata=None): 87 | return grpc.experimental.unary_unary( 88 | request, 89 | target, 90 | '/mavsdk.rpc.failure.FailureService/Inject', 91 | failure_dot_failure__pb2.InjectRequest.SerializeToString, 92 | failure_dot_failure__pb2.InjectResponse.FromString, 93 | options, 94 | channel_credentials, 95 | insecure, 96 | call_credentials, 97 | compression, 98 | wait_for_ready, 99 | timeout, 100 | metadata, 101 | _registered_method=True) 102 | -------------------------------------------------------------------------------- /mavsdk/ftp_server_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: ftp_server/ftp_server.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'ftp_server/ftp_server.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x1b\x66tp_server/ftp_server.proto\x12\x15mavsdk.rpc.ftp_server\x1a\x14mavsdk_options.proto\"!\n\x11SetRootDirRequest\x12\x0c\n\x04path\x18\x01 \x01(\t\"W\n\x12SetRootDirResponse\x12\x41\n\x11\x66tp_server_result\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.ftp_server.FtpServerResult\"\xc2\x01\n\x0f\x46tpServerResult\x12=\n\x06result\x18\x01 \x01(\x0e\x32-.mavsdk.rpc.ftp_server.FtpServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\\\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x19\n\x15RESULT_DOES_NOT_EXIST\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x32{\n\x10\x46tpServerService\x12g\n\nSetRootDir\x12(.mavsdk.rpc.ftp_server.SetRootDirRequest\x1a).mavsdk.rpc.ftp_server.SetRootDirResponse\"\x04\x80\xb5\x18\x01\x42&\n\x14io.mavsdk.ftp_serverB\x0e\x46tpServerProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'ftp_server.ftp_server_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\024io.mavsdk.ftp_serverB\016FtpServerProto' 36 | _globals['_FTPSERVERSERVICE'].methods_by_name['SetRootDir']._loaded_options = None 37 | _globals['_FTPSERVERSERVICE'].methods_by_name['SetRootDir']._serialized_options = b'\200\265\030\001' 38 | _globals['_SETROOTDIRREQUEST']._serialized_start=76 39 | _globals['_SETROOTDIRREQUEST']._serialized_end=109 40 | _globals['_SETROOTDIRRESPONSE']._serialized_start=111 41 | _globals['_SETROOTDIRRESPONSE']._serialized_end=198 42 | _globals['_FTPSERVERRESULT']._serialized_start=201 43 | _globals['_FTPSERVERRESULT']._serialized_end=395 44 | _globals['_FTPSERVERRESULT_RESULT']._serialized_start=303 45 | _globals['_FTPSERVERRESULT_RESULT']._serialized_end=395 46 | _globals['_FTPSERVERSERVICE']._serialized_start=397 47 | _globals['_FTPSERVERSERVICE']._serialized_end=520 48 | # @@protoc_insertion_point(module_scope) 49 | -------------------------------------------------------------------------------- /mavsdk/ftp_server_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | from . import ftp_server_pb2 as ftp__server_dot_ftp__server__pb2 7 | 8 | GRPC_GENERATED_VERSION = '1.71.0' 9 | GRPC_VERSION = grpc.__version__ 10 | _version_not_supported = False 11 | 12 | try: 13 | from grpc._utilities import first_version_is_lower 14 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 15 | except ImportError: 16 | _version_not_supported = True 17 | 18 | if _version_not_supported: 19 | raise RuntimeError( 20 | f'The grpc package installed is at version {GRPC_VERSION},' 21 | + f' but the generated code in ftp_server/ftp_server_pb2_grpc.py depends on' 22 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 23 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 24 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 25 | ) 26 | 27 | 28 | class FtpServerServiceStub(object): 29 | """Provide files or directories to transfer. 30 | """ 31 | 32 | def __init__(self, channel): 33 | """Constructor. 34 | 35 | Args: 36 | channel: A grpc.Channel. 37 | """ 38 | self.SetRootDir = channel.unary_unary( 39 | '/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir', 40 | request_serializer=ftp__server_dot_ftp__server__pb2.SetRootDirRequest.SerializeToString, 41 | response_deserializer=ftp__server_dot_ftp__server__pb2.SetRootDirResponse.FromString, 42 | _registered_method=True) 43 | 44 | 45 | class FtpServerServiceServicer(object): 46 | """Provide files or directories to transfer. 47 | """ 48 | 49 | def SetRootDir(self, request, context): 50 | """ 51 | Set root directory. 52 | 53 | This is the directory that can then be accessed by a client. 54 | The directory needs to exist when this is called. 55 | The permissions are the same as the file permission for the user running the server. 56 | The root directory can't be changed while an FTP process is in progress. 57 | """ 58 | context.set_code(grpc.StatusCode.UNIMPLEMENTED) 59 | context.set_details('Method not implemented!') 60 | raise NotImplementedError('Method not implemented!') 61 | 62 | 63 | def add_FtpServerServiceServicer_to_server(servicer, server): 64 | rpc_method_handlers = { 65 | 'SetRootDir': grpc.unary_unary_rpc_method_handler( 66 | servicer.SetRootDir, 67 | request_deserializer=ftp__server_dot_ftp__server__pb2.SetRootDirRequest.FromString, 68 | response_serializer=ftp__server_dot_ftp__server__pb2.SetRootDirResponse.SerializeToString, 69 | ), 70 | } 71 | generic_handler = grpc.method_handlers_generic_handler( 72 | 'mavsdk.rpc.ftp_server.FtpServerService', rpc_method_handlers) 73 | server.add_generic_rpc_handlers((generic_handler,)) 74 | server.add_registered_method_handlers('mavsdk.rpc.ftp_server.FtpServerService', rpc_method_handlers) 75 | 76 | 77 | # This class is part of an EXPERIMENTAL API. 78 | class FtpServerService(object): 79 | """Provide files or directories to transfer. 80 | """ 81 | 82 | @staticmethod 83 | def SetRootDir(request, 84 | target, 85 | options=(), 86 | channel_credentials=None, 87 | call_credentials=None, 88 | insecure=False, 89 | compression=None, 90 | wait_for_ready=None, 91 | timeout=None, 92 | metadata=None): 93 | return grpc.experimental.unary_unary( 94 | request, 95 | target, 96 | '/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir', 97 | ftp__server_dot_ftp__server__pb2.SetRootDirRequest.SerializeToString, 98 | ftp__server_dot_ftp__server__pb2.SetRootDirResponse.FromString, 99 | options, 100 | channel_credentials, 101 | insecure, 102 | call_credentials, 103 | compression, 104 | wait_for_ready, 105 | timeout, 106 | metadata, 107 | _registered_method=True) 108 | -------------------------------------------------------------------------------- /mavsdk/geofence_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: geofence/geofence.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'geofence/geofence.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x17geofence/geofence.proto\x12\x13mavsdk.rpc.geofence\x1a\x14mavsdk_options.proto\"4\n\x05Point\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\"i\n\x07Polygon\x12*\n\x06points\x18\x01 \x03(\x0b\x32\x1a.mavsdk.rpc.geofence.Point\x12\x32\n\nfence_type\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.geofence.FenceType\"\x80\x01\n\x06\x43ircle\x12)\n\x05point\x18\x01 \x01(\x0b\x32\x1a.mavsdk.rpc.geofence.Point\x12\x17\n\x06radius\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x32\n\nfence_type\x18\x03 \x01(\x0e\x32\x1e.mavsdk.rpc.geofence.FenceType\"l\n\x0cGeofenceData\x12.\n\x08polygons\x18\x01 \x03(\x0b\x32\x1c.mavsdk.rpc.geofence.Polygon\x12,\n\x07\x63ircles\x18\x02 \x03(\x0b\x32\x1b.mavsdk.rpc.geofence.Circle\"Q\n\x15UploadGeofenceRequest\x12\x38\n\rgeofence_data\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.geofence.GeofenceData\"V\n\x16UploadGeofenceResponse\x12<\n\x0fgeofence_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.geofence.GeofenceResult\"\x16\n\x14\x43learGeofenceRequest\"U\n\x15\x43learGeofenceResponse\x12<\n\x0fgeofence_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.geofence.GeofenceResult\"\xa1\x02\n\x0eGeofenceResult\x12:\n\x06result\x18\x01 \x01(\x0e\x32*.mavsdk.rpc.geofence.GeofenceResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xbe\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x10\n\x0cRESULT_ERROR\x10\x02\x12\"\n\x1eRESULT_TOO_MANY_GEOFENCE_ITEMS\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x12\n\x0eRESULT_TIMEOUT\x10\x05\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07*?\n\tFenceType\x12\x18\n\x14\x46\x45NCE_TYPE_INCLUSION\x10\x00\x12\x18\n\x14\x46\x45NCE_TYPE_EXCLUSION\x10\x01\x32\xe8\x01\n\x0fGeofenceService\x12k\n\x0eUploadGeofence\x12*.mavsdk.rpc.geofence.UploadGeofenceRequest\x1a+.mavsdk.rpc.geofence.UploadGeofenceResponse\"\x00\x12h\n\rClearGeofence\x12).mavsdk.rpc.geofence.ClearGeofenceRequest\x1a*.mavsdk.rpc.geofence.ClearGeofenceResponse\"\x00\x42#\n\x12io.mavsdk.geofenceB\rGeofenceProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'geofence.geofence_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\022io.mavsdk.geofenceB\rGeofenceProto' 36 | _globals['_CIRCLE'].fields_by_name['radius']._loaded_options = None 37 | _globals['_CIRCLE'].fields_by_name['radius']._serialized_options = b'\202\265\030\003NaN' 38 | _globals['_FENCETYPE']._serialized_start=1046 39 | _globals['_FENCETYPE']._serialized_end=1109 40 | _globals['_POINT']._serialized_start=70 41 | _globals['_POINT']._serialized_end=122 42 | _globals['_POLYGON']._serialized_start=124 43 | _globals['_POLYGON']._serialized_end=229 44 | _globals['_CIRCLE']._serialized_start=232 45 | _globals['_CIRCLE']._serialized_end=360 46 | _globals['_GEOFENCEDATA']._serialized_start=362 47 | _globals['_GEOFENCEDATA']._serialized_end=470 48 | _globals['_UPLOADGEOFENCEREQUEST']._serialized_start=472 49 | _globals['_UPLOADGEOFENCEREQUEST']._serialized_end=553 50 | _globals['_UPLOADGEOFENCERESPONSE']._serialized_start=555 51 | _globals['_UPLOADGEOFENCERESPONSE']._serialized_end=641 52 | _globals['_CLEARGEOFENCEREQUEST']._serialized_start=643 53 | _globals['_CLEARGEOFENCEREQUEST']._serialized_end=665 54 | _globals['_CLEARGEOFENCERESPONSE']._serialized_start=667 55 | _globals['_CLEARGEOFENCERESPONSE']._serialized_end=752 56 | _globals['_GEOFENCERESULT']._serialized_start=755 57 | _globals['_GEOFENCERESULT']._serialized_end=1044 58 | _globals['_GEOFENCERESULT_RESULT']._serialized_start=854 59 | _globals['_GEOFENCERESULT_RESULT']._serialized_end=1044 60 | _globals['_GEOFENCESERVICE']._serialized_start=1112 61 | _globals['_GEOFENCESERVICE']._serialized_end=1344 62 | # @@protoc_insertion_point(module_scope) 63 | -------------------------------------------------------------------------------- /mavsdk/gripper_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: gripper/gripper.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'gripper/gripper.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | 26 | 27 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x15gripper/gripper.proto\x12\x12mavsdk.rpc.gripper\"\x1f\n\x0bGrabRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"I\n\x0cGrabResponse\x12\x39\n\x0egripper_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.gripper.GripperResult\"\"\n\x0eReleaseRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"L\n\x0fReleaseResponse\x12\x39\n\x0egripper_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.gripper.GripperResult\"\xf6\x01\n\rGripperResult\x12\x38\n\x06result\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.gripper.GripperResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x96\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x12\x12\n\x0eRESULT_TIMEOUT\x10\x04\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x05\x12\x11\n\rRESULT_FAILED\x10\x06*D\n\rGripperAction\x12\x1a\n\x16GRIPPER_ACTION_RELEASE\x10\x00\x12\x17\n\x13GRIPPER_ACTION_GRAB\x10\x01\x32\xb3\x01\n\x0eGripperService\x12K\n\x04Grab\x12\x1f.mavsdk.rpc.gripper.GrabRequest\x1a .mavsdk.rpc.gripper.GrabResponse\"\x00\x12T\n\x07Release\x12\".mavsdk.rpc.gripper.ReleaseRequest\x1a#.mavsdk.rpc.gripper.ReleaseResponse\"\x00\x42!\n\x11io.mavsdk.gripperB\x0cGripperProtob\x06proto3') 28 | 29 | _globals = globals() 30 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 31 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'gripper.gripper_pb2', _globals) 32 | if not _descriptor._USE_C_DESCRIPTORS: 33 | _globals['DESCRIPTOR']._loaded_options = None 34 | _globals['DESCRIPTOR']._serialized_options = b'\n\021io.mavsdk.gripperB\014GripperProto' 35 | _globals['_GRIPPERACTION']._serialized_start=516 36 | _globals['_GRIPPERACTION']._serialized_end=584 37 | _globals['_GRABREQUEST']._serialized_start=45 38 | _globals['_GRABREQUEST']._serialized_end=76 39 | _globals['_GRABRESPONSE']._serialized_start=78 40 | _globals['_GRABRESPONSE']._serialized_end=151 41 | _globals['_RELEASEREQUEST']._serialized_start=153 42 | _globals['_RELEASEREQUEST']._serialized_end=187 43 | _globals['_RELEASERESPONSE']._serialized_start=189 44 | _globals['_RELEASERESPONSE']._serialized_end=265 45 | _globals['_GRIPPERRESULT']._serialized_start=268 46 | _globals['_GRIPPERRESULT']._serialized_end=514 47 | _globals['_GRIPPERRESULT_RESULT']._serialized_start=364 48 | _globals['_GRIPPERRESULT_RESULT']._serialized_end=514 49 | _globals['_GRIPPERSERVICE']._serialized_start=587 50 | _globals['_GRIPPERSERVICE']._serialized_end=766 51 | # @@protoc_insertion_point(module_scope) 52 | -------------------------------------------------------------------------------- /mavsdk/log_streaming_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: log_streaming/log_streaming.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'log_streaming/log_streaming.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n!log_streaming/log_streaming.proto\x12\x18mavsdk.rpc.log_streaming\x1a\x14mavsdk_options.proto\"\x1a\n\x18StartLogStreamingRequest\"g\n\x19StartLogStreamingResponse\x12J\n\x14log_streaming_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.log_streaming.LogStreamingResult\"\x19\n\x17StopLogStreamingRequest\"f\n\x18StopLogStreamingResponse\x12J\n\x14log_streaming_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.log_streaming.LogStreamingResult\"!\n\x1fSubscribeLogStreamingRawRequest\"Y\n\x17LogStreamingRawResponse\x12>\n\x0blogging_raw\x18\x01 \x01(\x0b\x32).mavsdk.rpc.log_streaming.LogStreamingRaw\"&\n\x0fLogStreamingRaw\x12\x13\n\x0b\x64\x61ta_base64\x18\x01 \x01(\t\"\xab\x02\n\x12LogStreamingResult\x12\x43\n\x06result\x18\x01 \x01(\x0e\x32\x33.mavsdk.rpc.log_streaming.LogStreamingResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xbb\x01\n\x06Result\x12\x12\n\x0eRESULT_SUCCESS\x10\x00\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x01\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x04\x12\x12\n\x0eRESULT_TIMEOUT\x10\x05\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x06\x12\x12\n\x0eRESULT_UNKNOWN\x10\x07\x32\xa5\x03\n\x13LogStreamingService\x12~\n\x11StartLogStreaming\x12\x32.mavsdk.rpc.log_streaming.StartLogStreamingRequest\x1a\x33.mavsdk.rpc.log_streaming.StartLogStreamingResponse\"\x00\x12{\n\x10StopLogStreaming\x12\x31.mavsdk.rpc.log_streaming.StopLogStreamingRequest\x1a\x32.mavsdk.rpc.log_streaming.StopLogStreamingResponse\"\x00\x12\x90\x01\n\x18SubscribeLogStreamingRaw\x12\x39.mavsdk.rpc.log_streaming.SubscribeLogStreamingRawRequest\x1a\x31.mavsdk.rpc.log_streaming.LogStreamingRawResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42,\n\x17io.mavsdk.log_streamingB\x11LogStreamingProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'log_streaming.log_streaming_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\027io.mavsdk.log_streamingB\021LogStreamingProto' 36 | _globals['_LOGSTREAMINGSERVICE'].methods_by_name['SubscribeLogStreamingRaw']._loaded_options = None 37 | _globals['_LOGSTREAMINGSERVICE'].methods_by_name['SubscribeLogStreamingRaw']._serialized_options = b'\200\265\030\000' 38 | _globals['_STARTLOGSTREAMINGREQUEST']._serialized_start=85 39 | _globals['_STARTLOGSTREAMINGREQUEST']._serialized_end=111 40 | _globals['_STARTLOGSTREAMINGRESPONSE']._serialized_start=113 41 | _globals['_STARTLOGSTREAMINGRESPONSE']._serialized_end=216 42 | _globals['_STOPLOGSTREAMINGREQUEST']._serialized_start=218 43 | _globals['_STOPLOGSTREAMINGREQUEST']._serialized_end=243 44 | _globals['_STOPLOGSTREAMINGRESPONSE']._serialized_start=245 45 | _globals['_STOPLOGSTREAMINGRESPONSE']._serialized_end=347 46 | _globals['_SUBSCRIBELOGSTREAMINGRAWREQUEST']._serialized_start=349 47 | _globals['_SUBSCRIBELOGSTREAMINGRAWREQUEST']._serialized_end=382 48 | _globals['_LOGSTREAMINGRAWRESPONSE']._serialized_start=384 49 | _globals['_LOGSTREAMINGRAWRESPONSE']._serialized_end=473 50 | _globals['_LOGSTREAMINGRAW']._serialized_start=475 51 | _globals['_LOGSTREAMINGRAW']._serialized_end=513 52 | _globals['_LOGSTREAMINGRESULT']._serialized_start=516 53 | _globals['_LOGSTREAMINGRESULT']._serialized_end=815 54 | _globals['_LOGSTREAMINGRESULT_RESULT']._serialized_start=628 55 | _globals['_LOGSTREAMINGRESULT_RESULT']._serialized_end=815 56 | _globals['_LOGSTREAMINGSERVICE']._serialized_start=818 57 | _globals['_LOGSTREAMINGSERVICE']._serialized_end=1239 58 | # @@protoc_insertion_point(module_scope) 59 | -------------------------------------------------------------------------------- /mavsdk/make.bat: -------------------------------------------------------------------------------- 1 | @ECHO OFF 2 | 3 | pushd %~dp0 4 | 5 | REM Command file for Sphinx documentation 6 | 7 | if "%SPHINXBUILD%" == "" ( 8 | set SPHINXBUILD=sphinx-build 9 | ) 10 | set SOURCEDIR=source 11 | set BUILDDIR=build 12 | 13 | if "%1" == "" goto help 14 | 15 | %SPHINXBUILD% >NUL 2>NUL 16 | if errorlevel 9009 ( 17 | echo. 18 | echo.The 'sphinx-build' command was not found. Make sure you have Sphinx 19 | echo.installed, then set the SPHINXBUILD environment variable to point 20 | echo.to the full path of the 'sphinx-build' executable. Alternatively you 21 | echo.may add the Sphinx directory to PATH. 22 | echo. 23 | echo.If you don't have Sphinx installed, grab it from 24 | echo.http://sphinx-doc.org/ 25 | exit /b 1 26 | ) 27 | 28 | %SPHINXBUILD% -M %1 %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% 29 | goto end 30 | 31 | :help 32 | %SPHINXBUILD% -M help %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% 33 | 34 | :end 35 | popd 36 | -------------------------------------------------------------------------------- /mavsdk/manual_control_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: manual_control/manual_control.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'manual_control/manual_control.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n#manual_control/manual_control.proto\x12\x19mavsdk.rpc.manual_control\x1a\x14mavsdk_options.proto\"\x1d\n\x1bStartPositionControlRequest\"m\n\x1cStartPositionControlResponse\x12M\n\x15manual_control_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.manual_control.ManualControlResult\"\x1d\n\x1bStartAltitudeControlRequest\"m\n\x1cStartAltitudeControlResponse\x12M\n\x15manual_control_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.manual_control.ManualControlResult\"J\n\x1cSetManualControlInputRequest\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01r\x18\x04 \x01(\x02\"n\n\x1dSetManualControlInputResponse\x12M\n\x15manual_control_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.manual_control.ManualControlResult\"\xcf\x02\n\x13ManualControlResult\x12\x45\n\x06result\x18\x01 \x01(\x0e\x32\x35.mavsdk.rpc.manual_control.ManualControlResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xdc\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x1d\n\x19RESULT_INPUT_OUT_OF_RANGE\x10\x07\x12\x18\n\x14RESULT_INPUT_NOT_SET\x10\x08\x32\xc1\x03\n\x14ManualControlService\x12\x89\x01\n\x14StartPositionControl\x12\x36.mavsdk.rpc.manual_control.StartPositionControlRequest\x1a\x37.mavsdk.rpc.manual_control.StartPositionControlResponse\"\x00\x12\x89\x01\n\x14StartAltitudeControl\x12\x36.mavsdk.rpc.manual_control.StartAltitudeControlRequest\x1a\x37.mavsdk.rpc.manual_control.StartAltitudeControlResponse\"\x00\x12\x90\x01\n\x15SetManualControlInput\x12\x37.mavsdk.rpc.manual_control.SetManualControlInputRequest\x1a\x38.mavsdk.rpc.manual_control.SetManualControlInputResponse\"\x04\x80\xb5\x18\x01\x42.\n\x18io.mavsdk.manual_controlB\x12ManualControlProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'manual_control.manual_control_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\030io.mavsdk.manual_controlB\022ManualControlProto' 36 | _globals['_MANUALCONTROLSERVICE'].methods_by_name['SetManualControlInput']._loaded_options = None 37 | _globals['_MANUALCONTROLSERVICE'].methods_by_name['SetManualControlInput']._serialized_options = b'\200\265\030\001' 38 | _globals['_STARTPOSITIONCONTROLREQUEST']._serialized_start=88 39 | _globals['_STARTPOSITIONCONTROLREQUEST']._serialized_end=117 40 | _globals['_STARTPOSITIONCONTROLRESPONSE']._serialized_start=119 41 | _globals['_STARTPOSITIONCONTROLRESPONSE']._serialized_end=228 42 | _globals['_STARTALTITUDECONTROLREQUEST']._serialized_start=230 43 | _globals['_STARTALTITUDECONTROLREQUEST']._serialized_end=259 44 | _globals['_STARTALTITUDECONTROLRESPONSE']._serialized_start=261 45 | _globals['_STARTALTITUDECONTROLRESPONSE']._serialized_end=370 46 | _globals['_SETMANUALCONTROLINPUTREQUEST']._serialized_start=372 47 | _globals['_SETMANUALCONTROLINPUTREQUEST']._serialized_end=446 48 | _globals['_SETMANUALCONTROLINPUTRESPONSE']._serialized_start=448 49 | _globals['_SETMANUALCONTROLINPUTRESPONSE']._serialized_end=558 50 | _globals['_MANUALCONTROLRESULT']._serialized_start=561 51 | _globals['_MANUALCONTROLRESULT']._serialized_end=896 52 | _globals['_MANUALCONTROLRESULT_RESULT']._serialized_start=676 53 | _globals['_MANUALCONTROLRESULT_RESULT']._serialized_end=896 54 | _globals['_MANUALCONTROLSERVICE']._serialized_start=899 55 | _globals['_MANUALCONTROLSERVICE']._serialized_end=1348 56 | # @@protoc_insertion_point(module_scope) 57 | -------------------------------------------------------------------------------- /mavsdk/mavsdk_options_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: mavsdk_options.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'mavsdk_options.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from google.protobuf import descriptor_pb2 as google_dot_protobuf_dot_descriptor__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x14mavsdk_options.proto\x12\x0emavsdk.options\x1a google/protobuf/descriptor.proto**\n\tAsyncType\x12\t\n\x05\x41SYNC\x10\x00\x12\x08\n\x04SYNC\x10\x01\x12\x08\n\x04\x42OTH\x10\x02:6\n\rdefault_value\x12\x1d.google.protobuf.FieldOptions\x18\xd0\x86\x03 \x01(\t:0\n\x07\x65psilon\x12\x1d.google.protobuf.FieldOptions\x18\xd1\x86\x03 \x01(\x01:O\n\nasync_type\x12\x1e.google.protobuf.MethodOptions\x18\xd0\x86\x03 \x01(\x0e\x32\x19.mavsdk.options.AsyncType:3\n\tis_finite\x12\x1e.google.protobuf.MethodOptions\x18\xd1\x86\x03 \x01(\x08\x42\x10\n\x0eoptions.mavsdkb\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mavsdk_options_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\016options.mavsdk' 36 | _globals['_ASYNCTYPE']._serialized_start=74 37 | _globals['_ASYNCTYPE']._serialized_end=116 38 | # @@protoc_insertion_point(module_scope) 39 | -------------------------------------------------------------------------------- /mavsdk/mavsdk_options_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | 7 | GRPC_GENERATED_VERSION = '1.71.0' 8 | GRPC_VERSION = grpc.__version__ 9 | _version_not_supported = False 10 | 11 | try: 12 | from grpc._utilities import first_version_is_lower 13 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 14 | except ImportError: 15 | _version_not_supported = True 16 | 17 | if _version_not_supported: 18 | raise RuntimeError( 19 | f'The grpc package installed is at version {GRPC_VERSION},' 20 | + f' but the generated code in mavsdk_options_pb2_grpc.py depends on' 21 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 22 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 23 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 24 | ) 25 | -------------------------------------------------------------------------------- /mavsdk/rtk_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: rtk/rtk.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'rtk/rtk.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\rrtk/rtk.proto\x12\x0emavsdk.rpc.rtk\x1a\x14mavsdk_options.proto\"\x1f\n\x08RtcmData\x12\x13\n\x0b\x64\x61ta_base64\x18\x01 \x01(\t\"B\n\x13SendRtcmDataRequest\x12+\n\trtcm_data\x18\x01 \x01(\x0b\x32\x18.mavsdk.rpc.rtk.RtcmData\"E\n\x14SendRtcmDataResponse\x12-\n\nrtk_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.rtk.RtkResult\"\xcb\x01\n\tRtkResult\x12\x30\n\x06result\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.rtk.RtkResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"x\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x13\n\x0fRESULT_TOO_LONG\x10\x02\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x05\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x06\x32m\n\nRtkService\x12_\n\x0cSendRtcmData\x12#.mavsdk.rpc.rtk.SendRtcmDataRequest\x1a$.mavsdk.rpc.rtk.SendRtcmDataResponse\"\x04\x80\xb5\x18\x01\x42\x19\n\rio.mavsdk.rtkB\x08RtkProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'rtk.rtk_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\rio.mavsdk.rtkB\010RtkProto' 36 | _globals['_RTKSERVICE'].methods_by_name['SendRtcmData']._loaded_options = None 37 | _globals['_RTKSERVICE'].methods_by_name['SendRtcmData']._serialized_options = b'\200\265\030\001' 38 | _globals['_RTCMDATA']._serialized_start=55 39 | _globals['_RTCMDATA']._serialized_end=86 40 | _globals['_SENDRTCMDATAREQUEST']._serialized_start=88 41 | _globals['_SENDRTCMDATAREQUEST']._serialized_end=154 42 | _globals['_SENDRTCMDATARESPONSE']._serialized_start=156 43 | _globals['_SENDRTCMDATARESPONSE']._serialized_end=225 44 | _globals['_RTKRESULT']._serialized_start=228 45 | _globals['_RTKRESULT']._serialized_end=431 46 | _globals['_RTKRESULT_RESULT']._serialized_start=311 47 | _globals['_RTKRESULT_RESULT']._serialized_end=431 48 | _globals['_RTKSERVICE']._serialized_start=433 49 | _globals['_RTKSERVICE']._serialized_end=542 50 | # @@protoc_insertion_point(module_scope) 51 | -------------------------------------------------------------------------------- /mavsdk/rtk_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | from . import rtk_pb2 as rtk_dot_rtk__pb2 7 | 8 | GRPC_GENERATED_VERSION = '1.71.0' 9 | GRPC_VERSION = grpc.__version__ 10 | _version_not_supported = False 11 | 12 | try: 13 | from grpc._utilities import first_version_is_lower 14 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 15 | except ImportError: 16 | _version_not_supported = True 17 | 18 | if _version_not_supported: 19 | raise RuntimeError( 20 | f'The grpc package installed is at version {GRPC_VERSION},' 21 | + f' but the generated code in rtk/rtk_pb2_grpc.py depends on' 22 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 23 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 24 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 25 | ) 26 | 27 | 28 | class RtkServiceStub(object): 29 | """Service to send RTK corrections to the vehicle. 30 | """ 31 | 32 | def __init__(self, channel): 33 | """Constructor. 34 | 35 | Args: 36 | channel: A grpc.Channel. 37 | """ 38 | self.SendRtcmData = channel.unary_unary( 39 | '/mavsdk.rpc.rtk.RtkService/SendRtcmData', 40 | request_serializer=rtk_dot_rtk__pb2.SendRtcmDataRequest.SerializeToString, 41 | response_deserializer=rtk_dot_rtk__pb2.SendRtcmDataResponse.FromString, 42 | _registered_method=True) 43 | 44 | 45 | class RtkServiceServicer(object): 46 | """Service to send RTK corrections to the vehicle. 47 | """ 48 | 49 | def SendRtcmData(self, request, context): 50 | """Send RTCM data. 51 | """ 52 | context.set_code(grpc.StatusCode.UNIMPLEMENTED) 53 | context.set_details('Method not implemented!') 54 | raise NotImplementedError('Method not implemented!') 55 | 56 | 57 | def add_RtkServiceServicer_to_server(servicer, server): 58 | rpc_method_handlers = { 59 | 'SendRtcmData': grpc.unary_unary_rpc_method_handler( 60 | servicer.SendRtcmData, 61 | request_deserializer=rtk_dot_rtk__pb2.SendRtcmDataRequest.FromString, 62 | response_serializer=rtk_dot_rtk__pb2.SendRtcmDataResponse.SerializeToString, 63 | ), 64 | } 65 | generic_handler = grpc.method_handlers_generic_handler( 66 | 'mavsdk.rpc.rtk.RtkService', rpc_method_handlers) 67 | server.add_generic_rpc_handlers((generic_handler,)) 68 | server.add_registered_method_handlers('mavsdk.rpc.rtk.RtkService', rpc_method_handlers) 69 | 70 | 71 | # This class is part of an EXPERIMENTAL API. 72 | class RtkService(object): 73 | """Service to send RTK corrections to the vehicle. 74 | """ 75 | 76 | @staticmethod 77 | def SendRtcmData(request, 78 | target, 79 | options=(), 80 | channel_credentials=None, 81 | call_credentials=None, 82 | insecure=False, 83 | compression=None, 84 | wait_for_ready=None, 85 | timeout=None, 86 | metadata=None): 87 | return grpc.experimental.unary_unary( 88 | request, 89 | target, 90 | '/mavsdk.rpc.rtk.RtkService/SendRtcmData', 91 | rtk_dot_rtk__pb2.SendRtcmDataRequest.SerializeToString, 92 | rtk_dot_rtk__pb2.SendRtcmDataResponse.FromString, 93 | options, 94 | channel_credentials, 95 | insecure, 96 | call_credentials, 97 | compression, 98 | wait_for_ready, 99 | timeout, 100 | metadata, 101 | _registered_method=True) 102 | -------------------------------------------------------------------------------- /mavsdk/server_utility_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: server_utility/server_utility.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'server_utility/server_utility.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n#server_utility/server_utility.proto\x12\x19mavsdk.rpc.server_utility\x1a\x14mavsdk_options.proto\"^\n\x15SendStatusTextRequest\x12\x37\n\x04type\x18\x01 \x01(\x0e\x32).mavsdk.rpc.server_utility.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t\"g\n\x16SendStatusTextResponse\x12M\n\x15server_utility_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.server_utility.ServerUtilityResult\"\xf3\x01\n\x13ServerUtilityResult\x12\x45\n\x06result\x18\x01 \x01(\x0e\x32\x35.mavsdk.rpc.server_utility.ServerUtilityResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x80\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x04*\xf9\x01\n\x0eStatusTextType\x12\x1a\n\x16STATUS_TEXT_TYPE_DEBUG\x10\x00\x12\x19\n\x15STATUS_TEXT_TYPE_INFO\x10\x01\x12\x1b\n\x17STATUS_TEXT_TYPE_NOTICE\x10\x02\x12\x1c\n\x18STATUS_TEXT_TYPE_WARNING\x10\x03\x12\x1a\n\x16STATUS_TEXT_TYPE_ERROR\x10\x04\x12\x1d\n\x19STATUS_TEXT_TYPE_CRITICAL\x10\x05\x12\x1a\n\x16STATUS_TEXT_TYPE_ALERT\x10\x06\x12\x1e\n\x1aSTATUS_TEXT_TYPE_EMERGENCY\x10\x07\x32\x93\x01\n\x14ServerUtilityService\x12{\n\x0eSendStatusText\x12\x30.mavsdk.rpc.server_utility.SendStatusTextRequest\x1a\x31.mavsdk.rpc.server_utility.SendStatusTextResponse\"\x04\x80\xb5\x18\x01\x42.\n\x18io.mavsdk.server_utilityB\x12ServerUtilityProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'server_utility.server_utility_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\030io.mavsdk.server_utilityB\022ServerUtilityProto' 36 | _globals['_SERVERUTILITYSERVICE'].methods_by_name['SendStatusText']._loaded_options = None 37 | _globals['_SERVERUTILITYSERVICE'].methods_by_name['SendStatusText']._serialized_options = b'\200\265\030\001' 38 | _globals['_STATUSTEXTTYPE']._serialized_start=536 39 | _globals['_STATUSTEXTTYPE']._serialized_end=785 40 | _globals['_SENDSTATUSTEXTREQUEST']._serialized_start=88 41 | _globals['_SENDSTATUSTEXTREQUEST']._serialized_end=182 42 | _globals['_SENDSTATUSTEXTRESPONSE']._serialized_start=184 43 | _globals['_SENDSTATUSTEXTRESPONSE']._serialized_end=287 44 | _globals['_SERVERUTILITYRESULT']._serialized_start=290 45 | _globals['_SERVERUTILITYRESULT']._serialized_end=533 46 | _globals['_SERVERUTILITYRESULT_RESULT']._serialized_start=405 47 | _globals['_SERVERUTILITYRESULT_RESULT']._serialized_end=533 48 | _globals['_SERVERUTILITYSERVICE']._serialized_start=788 49 | _globals['_SERVERUTILITYSERVICE']._serialized_end=935 50 | # @@protoc_insertion_point(module_scope) 51 | -------------------------------------------------------------------------------- /mavsdk/server_utility_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | from . import server_utility_pb2 as server__utility_dot_server__utility__pb2 7 | 8 | GRPC_GENERATED_VERSION = '1.71.0' 9 | GRPC_VERSION = grpc.__version__ 10 | _version_not_supported = False 11 | 12 | try: 13 | from grpc._utilities import first_version_is_lower 14 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 15 | except ImportError: 16 | _version_not_supported = True 17 | 18 | if _version_not_supported: 19 | raise RuntimeError( 20 | f'The grpc package installed is at version {GRPC_VERSION},' 21 | + f' but the generated code in server_utility/server_utility_pb2_grpc.py depends on' 22 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 23 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 24 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 25 | ) 26 | 27 | 28 | class ServerUtilityServiceStub(object): 29 | """ 30 | Utility for onboard MAVSDK instances for common "server" tasks. 31 | """ 32 | 33 | def __init__(self, channel): 34 | """Constructor. 35 | 36 | Args: 37 | channel: A grpc.Channel. 38 | """ 39 | self.SendStatusText = channel.unary_unary( 40 | '/mavsdk.rpc.server_utility.ServerUtilityService/SendStatusText', 41 | request_serializer=server__utility_dot_server__utility__pb2.SendStatusTextRequest.SerializeToString, 42 | response_deserializer=server__utility_dot_server__utility__pb2.SendStatusTextResponse.FromString, 43 | _registered_method=True) 44 | 45 | 46 | class ServerUtilityServiceServicer(object): 47 | """ 48 | Utility for onboard MAVSDK instances for common "server" tasks. 49 | """ 50 | 51 | def SendStatusText(self, request, context): 52 | """Sends a statustext. 53 | """ 54 | context.set_code(grpc.StatusCode.UNIMPLEMENTED) 55 | context.set_details('Method not implemented!') 56 | raise NotImplementedError('Method not implemented!') 57 | 58 | 59 | def add_ServerUtilityServiceServicer_to_server(servicer, server): 60 | rpc_method_handlers = { 61 | 'SendStatusText': grpc.unary_unary_rpc_method_handler( 62 | servicer.SendStatusText, 63 | request_deserializer=server__utility_dot_server__utility__pb2.SendStatusTextRequest.FromString, 64 | response_serializer=server__utility_dot_server__utility__pb2.SendStatusTextResponse.SerializeToString, 65 | ), 66 | } 67 | generic_handler = grpc.method_handlers_generic_handler( 68 | 'mavsdk.rpc.server_utility.ServerUtilityService', rpc_method_handlers) 69 | server.add_generic_rpc_handlers((generic_handler,)) 70 | server.add_registered_method_handlers('mavsdk.rpc.server_utility.ServerUtilityService', rpc_method_handlers) 71 | 72 | 73 | # This class is part of an EXPERIMENTAL API. 74 | class ServerUtilityService(object): 75 | """ 76 | Utility for onboard MAVSDK instances for common "server" tasks. 77 | """ 78 | 79 | @staticmethod 80 | def SendStatusText(request, 81 | target, 82 | options=(), 83 | channel_credentials=None, 84 | call_credentials=None, 85 | insecure=False, 86 | compression=None, 87 | wait_for_ready=None, 88 | timeout=None, 89 | metadata=None): 90 | return grpc.experimental.unary_unary( 91 | request, 92 | target, 93 | '/mavsdk.rpc.server_utility.ServerUtilityService/SendStatusText', 94 | server__utility_dot_server__utility__pb2.SendStatusTextRequest.SerializeToString, 95 | server__utility_dot_server__utility__pb2.SendStatusTextResponse.FromString, 96 | options, 97 | channel_credentials, 98 | insecure, 99 | call_credentials, 100 | compression, 101 | wait_for_ready, 102 | timeout, 103 | metadata, 104 | _registered_method=True) 105 | -------------------------------------------------------------------------------- /mavsdk/shell_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: shell/shell.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'shell/shell.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | from . import mavsdk_options_pb2 as mavsdk__options__pb2 26 | 27 | 28 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x11shell/shell.proto\x12\x10mavsdk.rpc.shell\x1a\x14mavsdk_options.proto\"\x1e\n\x0bSendRequest\x12\x0f\n\x07\x63ommand\x18\x01 \x01(\t\"C\n\x0cSendResponse\x12\x33\n\x0cshell_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.shell.ShellResult\"\x19\n\x17SubscribeReceiveRequest\"\x1f\n\x0fReceiveResponse\x12\x0c\n\x04\x64\x61ta\x18\x01 \x01(\t\"\xe6\x01\n\x0bShellResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.shell.ShellResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x8c\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x16\n\x12RESULT_NO_RESPONSE\x10\x04\x12\x0f\n\x0bRESULT_BUSY\x10\x05\x32\xc5\x01\n\x0cShellService\x12K\n\x04Send\x12\x1d.mavsdk.rpc.shell.SendRequest\x1a\x1e.mavsdk.rpc.shell.SendResponse\"\x04\x80\xb5\x18\x01\x12h\n\x10SubscribeReceive\x12).mavsdk.rpc.shell.SubscribeReceiveRequest\x1a!.mavsdk.rpc.shell.ReceiveResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42\x1d\n\x0fio.mavsdk.shellB\nShellProtob\x06proto3') 29 | 30 | _globals = globals() 31 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 32 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'shell.shell_pb2', _globals) 33 | if not _descriptor._USE_C_DESCRIPTORS: 34 | _globals['DESCRIPTOR']._loaded_options = None 35 | _globals['DESCRIPTOR']._serialized_options = b'\n\017io.mavsdk.shellB\nShellProto' 36 | _globals['_SHELLSERVICE'].methods_by_name['Send']._loaded_options = None 37 | _globals['_SHELLSERVICE'].methods_by_name['Send']._serialized_options = b'\200\265\030\001' 38 | _globals['_SHELLSERVICE'].methods_by_name['SubscribeReceive']._loaded_options = None 39 | _globals['_SHELLSERVICE'].methods_by_name['SubscribeReceive']._serialized_options = b'\200\265\030\000' 40 | _globals['_SENDREQUEST']._serialized_start=61 41 | _globals['_SENDREQUEST']._serialized_end=91 42 | _globals['_SENDRESPONSE']._serialized_start=93 43 | _globals['_SENDRESPONSE']._serialized_end=160 44 | _globals['_SUBSCRIBERECEIVEREQUEST']._serialized_start=162 45 | _globals['_SUBSCRIBERECEIVEREQUEST']._serialized_end=187 46 | _globals['_RECEIVERESPONSE']._serialized_start=189 47 | _globals['_RECEIVERESPONSE']._serialized_end=220 48 | _globals['_SHELLRESULT']._serialized_start=223 49 | _globals['_SHELLRESULT']._serialized_end=453 50 | _globals['_SHELLRESULT_RESULT']._serialized_start=313 51 | _globals['_SHELLRESULT_RESULT']._serialized_end=453 52 | _globals['_SHELLSERVICE']._serialized_start=456 53 | _globals['_SHELLSERVICE']._serialized_end=653 54 | # @@protoc_insertion_point(module_scope) 55 | -------------------------------------------------------------------------------- /mavsdk/source/conf.py: -------------------------------------------------------------------------------- 1 | # Configuration file for the Sphinx documentation builder. 2 | # 3 | # This file only contains a selection of the most common options. For a full 4 | # list see the documentation: 5 | # https://www.sphinx-doc.org/en/master/usage/configuration.html 6 | 7 | import os 8 | import subprocess 9 | import sys 10 | 11 | # -- Path setup -------------------------------------------------------------- 12 | 13 | # If extensions (or modules to document with autodoc) are in another directory, 14 | # add these directories to sys.path here. If the directory is relative to the 15 | # documentation root, use os.path.abspath to make it absolute, like shown here. 16 | sys.path.insert(0, os.path.abspath('../..')) 17 | 18 | # -- Project information ----------------------------------------------------- 19 | 20 | project = 'MAVSDK-Python' 21 | copyright = '2020, Jonas Vautherin, Julian Oes' 22 | author = 'Jonas Vautherin, Julian Oes' 23 | 24 | result = subprocess.run(['git', 'describe', '--tag', '--abbrev=0'], 25 | stdout=subprocess.PIPE) 26 | 27 | # The full version, including alpha/beta/rc tags 28 | release = result.stdout.decode('utf-8') 29 | 30 | 31 | # -- General configuration --------------------------------------------------- 32 | 33 | # Add any Sphinx extension module names here, as strings. They can be 34 | # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom 35 | # ones. 36 | extensions = [ 37 | 'sphinx.ext.autodoc', 38 | 'sphinx.ext.napoleon' 39 | ] 40 | 41 | # Add any paths that contain templates here, relative to this directory. 42 | templates_path = ['_templates'] 43 | 44 | # List of patterns, relative to source directory, that match files and 45 | # directories to ignore when looking for source files. 46 | # This pattern also affects html_static_path and html_extra_path. 47 | exclude_patterns = [] 48 | 49 | 50 | # -- Options for HTML output ------------------------------------------------- 51 | 52 | # The theme to use for HTML and HTML Help pages. See the documentation for 53 | # a list of builtin themes. 54 | # 55 | html_theme = 'nature_adapted' 56 | html_theme_path = ["."] 57 | 58 | # Add any paths that contain custom static files (such as style sheets) here, 59 | # relative to this directory. They are copied after the builtin static files, 60 | # so a file named "default.css" will overwrite the builtin "default.css". 61 | html_static_path = ['nature_adapted/static'] 62 | 63 | html_favicon = "nature_adapted/static/favicon.png" 64 | -------------------------------------------------------------------------------- /mavsdk/source/index.rst: -------------------------------------------------------------------------------- 1 | .. MAVSDK-Python documentation main file, created by 2 | sphinx-quickstart on Sat May 30 10:40:26 2020. 3 | You can adapt this file completely to your liking, but it should at least 4 | contain the root `toctree` directive. 5 | 6 | | 7 | 8 | .. image:: nature_adapted/static/sdk_logo_full.png 9 | :alt: MAVSDK logo 10 | :scale: 30% 11 | 12 | MAVSDK-Python API reference 13 | =========================== 14 | 15 | 16 | .. toctree:: 17 | :maxdepth: 2 18 | :caption: Contents: 19 | 20 | system 21 | plugins/index 22 | jetson-nano-install 23 | 24 | Important Notes 25 | --------------- 26 | 27 | - Python 3.7+ is required. 28 | - You may need to run ``pip3`` instead of ``pip`` and ``python3`` instead of ``python``, depending of your system defaults. 29 | - Auterion has a _Getting started with MAVSDK-Python: https://auterion.com/getting-started-with-mavsdk-python/ guide if you're a beginner and not sure where to start. 30 | 31 | Install using pip from PyPi 32 | --------------------------- 33 | 34 | To install simply run: 35 | 36 | .. code:: bash 37 | 38 | python -m pip install --upgrade mavsdk 39 | 40 | 41 | The package contains ``mavsdk_server`` already (previously called "backend"), which is started automatically when connecting (e.g. ``await drone.connect()``). Have a look at the examples to see it used in practice. It will be something like: 42 | 43 | .. code:: python 44 | 45 | python 46 | from mavsdk import System 47 | ... 48 | drone = System() 49 | await drone.connect(system_address="udp://:14540") 50 | 51 | 52 | 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. 53 | 54 | For specific platforms, check the detailed install instructions: 55 | 56 | * :ref:`jetson-nano-install` 57 | 58 | Run the examples 59 | ---------------- 60 | 61 | Once the package has been installed, the examples can be run: 62 | 63 | .. code:: bash 64 | 65 | examples/takeoff_and_land.py 66 | 67 | The examples assume that the embedded ``mavsdk_server`` binary can be run. In some cases (e.g. on Raspberry Pi), it may be necessary to run ``mavsdk_server`` manually, and therefore to set ``mavsdk_server_address='localhost'`` as described above. 68 | 69 | Debug connection issues 70 | ----------------------- 71 | 72 | In order to get more debugging information, it is possible to run the mavsdk_server binary separately. 73 | 74 | For this case, let's assume the example was like this: 75 | 76 | .. code:: python 77 | 78 | drone = System() 79 | await drone.connect(system_address="udp://:14540") 80 | 81 | 82 | 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). 83 | 84 | It can then be run in a separate console with the ``system_address`` as an argument: 85 | 86 | .. code:: bash 87 | 88 | ~/.local/lib/python3.10/site-packages/mavsdk/bin/mavsdk_server udp://:14540 89 | 90 | Without an autopilot connecting, the output will look something like: 91 | 92 | .. code:: bash 93 | 94 | [02:36:31|Info ] MAVSDK version: v1.4.16 (mavsdk_impl.cpp:28) 95 | [02:36:31|Info ] Waiting to discover system on udp://:14540... (connection_initiator.h:20) 96 | 97 | Once an autopilot is discovered, something like this should be printed: 98 | 99 | .. code:: bash 100 | 101 | [02:38:12|Info ] MAVSDK version: v1.4.16 (mavsdk_impl.cpp:28) 102 | [02:38:12|Info ] Waiting to discover system on udp://:14540... (connection_initiator.h:20) 103 | [02:39:01|Info ] New system on: 127.0.0.1:14580 (with sysid: 1) (udp_connection.cpp:194) 104 | [02:39:01|Debug] New: System ID: 1 Comp ID: 1 (mavsdk_impl.cpp:484) 105 | [02:39:01|Debug] Component Autopilot (1) added. (system_impl.cpp:355) 106 | [02:39:02|Debug] Discovered 1 component(s) (system_impl.cpp:523) 107 | [02:39:02|Info ] System discovered (connection_initiator.h:63) 108 | [02:39:02|Info ] Server started (grpc_server.cpp:52) 109 | [02:39:02|Info ] Server set to listen on 0.0.0.0:50051 (grpc_server.cpp:53) 110 | 111 | This would look promising, and the example can now be run against this server, however, without ``system_address``: 112 | 113 | 114 | .. code:: python 115 | 116 | drone = System() 117 | await drone.connect() 118 | 119 | 120 | Indices and tables 121 | ================== 122 | 123 | * :ref:`genindex` 124 | * :ref:`modindex` 125 | * :ref:`search` 126 | -------------------------------------------------------------------------------- /mavsdk/source/jetson-nano-install.rst: -------------------------------------------------------------------------------- 1 | .. _jetson-nano-install: 2 | 3 | Jetson Nano Install 4 | =================== 5 | 6 | Ubuntu 18.04 7 | ------------ 8 | 9 | To install MAVSDK-Python on a Jetson Nano with Ubuntu 18.04 (which is old and pas end-of-life, by the way), you need to get a newer version of Python 3 and make sure pip is up-to-date. 10 | 11 | Install Python 3.8: 12 | 13 | .. code:: bash 14 | 15 | sudo apt update 16 | sudo apt install python3.8 17 | 18 | 19 | Upgrade pip: 20 | 21 | .. code:: bash 22 | 23 | python3.8 -m pip install --upgrade pip 24 | 25 | Now install mavsdk: 26 | 27 | .. code:: bash 28 | 29 | python3.8 -m pip install --upgrade mavsdk 30 | 31 | Ubuntu 20.04 32 | ------------ 33 | 34 | The normal instructions should work with Ubuntu 20.04: 35 | 36 | Install mavsdk: 37 | 38 | .. code:: bash 39 | 40 | python3 -m pip install --upgrade mavsdk 41 | -------------------------------------------------------------------------------- /mavsdk/source/nature_adapted/static/favicon.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/mavsdk/source/nature_adapted/static/favicon.png -------------------------------------------------------------------------------- /mavsdk/source/nature_adapted/static/sdk_logo_full.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/mavsdk/source/nature_adapted/static/sdk_logo_full.png -------------------------------------------------------------------------------- /mavsdk/source/nature_adapted/static/style.css: -------------------------------------------------------------------------------- 1 | @import url("nature.css"); 2 | 3 | div.related { 4 | background-color: #f26622; 5 | } 6 | 7 | div.body h1, div.body h2, div.body h3, div.body h4, div.body h5, div.body h6 { 8 | background-color: #cccccc; 9 | } 10 | -------------------------------------------------------------------------------- /mavsdk/source/nature_adapted/theme.conf: -------------------------------------------------------------------------------- 1 | [theme] 2 | inherit = nature 3 | stylesheet = style.css 4 | -------------------------------------------------------------------------------- /mavsdk/source/plugins/action.rst: -------------------------------------------------------------------------------- 1 | Action 2 | ==== 3 | 4 | .. automodule:: mavsdk.action 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/action_server.rst: -------------------------------------------------------------------------------- 1 | ActionServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.action_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/arm_authorizer_server.rst: -------------------------------------------------------------------------------- 1 | ArmAuthorizerServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.arm_authorizer_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/calibration.rst: -------------------------------------------------------------------------------- 1 | Calibration 2 | ==== 3 | 4 | .. automodule:: mavsdk.calibration 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/camera.rst: -------------------------------------------------------------------------------- 1 | Camera 2 | ==== 3 | 4 | .. automodule:: mavsdk.camera 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/camera_server.rst: -------------------------------------------------------------------------------- 1 | CameraServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.camera_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/component_information.rst: -------------------------------------------------------------------------------- 1 | ComponentInformation 2 | ==== 3 | 4 | .. automodule:: mavsdk.component_information 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/component_information_server.rst: -------------------------------------------------------------------------------- 1 | ComponentInformationServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.component_information_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/component_metadata.rst: -------------------------------------------------------------------------------- 1 | ComponentMetadata 2 | ==== 3 | 4 | .. automodule:: mavsdk.component_metadata 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/component_metadata_server.rst: -------------------------------------------------------------------------------- 1 | ComponentMetadataServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.component_metadata_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/core.rst: -------------------------------------------------------------------------------- 1 | Core 2 | ==== 3 | 4 | .. automodule:: mavsdk.core 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/events.rst: -------------------------------------------------------------------------------- 1 | Events 2 | ==== 3 | 4 | .. automodule:: mavsdk.events 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/failure.rst: -------------------------------------------------------------------------------- 1 | Failure 2 | ==== 3 | 4 | .. automodule:: mavsdk.failure 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/follow_me.rst: -------------------------------------------------------------------------------- 1 | FollowMe 2 | ==== 3 | 4 | .. automodule:: mavsdk.follow_me 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/ftp.rst: -------------------------------------------------------------------------------- 1 | Ftp 2 | ==== 3 | 4 | .. automodule:: mavsdk.ftp 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/ftp_server.rst: -------------------------------------------------------------------------------- 1 | FtpServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.ftp_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/geofence.rst: -------------------------------------------------------------------------------- 1 | Geofence 2 | ==== 3 | 4 | .. automodule:: mavsdk.geofence 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/gimbal.rst: -------------------------------------------------------------------------------- 1 | Gimbal 2 | ==== 3 | 4 | .. automodule:: mavsdk.gimbal 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/gripper.rst: -------------------------------------------------------------------------------- 1 | Gripper 2 | ==== 3 | 4 | .. automodule:: mavsdk.gripper 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/index.rst: -------------------------------------------------------------------------------- 1 | Plugins 2 | ======= 3 | 4 | .. toctree:: 5 | :titlesonly: 6 | 7 | action 8 | action_server 9 | arm_authorizer_server 10 | calibration 11 | camera 12 | camera_server 13 | component_information 14 | component_information_server 15 | component_metadata 16 | component_metadata_server 17 | core 18 | failure 19 | follow_me 20 | ftp 21 | ftp_server 22 | geofence 23 | gimbal 24 | gripper 25 | info 26 | log_files 27 | log_streaming 28 | manual_control 29 | mission 30 | mission_raw 31 | mission_raw_server 32 | mocap 33 | offboard 34 | param 35 | param_server 36 | rtk 37 | server_utility 38 | shell 39 | telemetry 40 | telemetry_server 41 | tracking_server 42 | transponder 43 | tune 44 | winch 45 | arm_authorizer_server 46 | component_metadata 47 | component_metadata_server 48 | log_streaming 49 | events 50 | -------------------------------------------------------------------------------- /mavsdk/source/plugins/info.rst: -------------------------------------------------------------------------------- 1 | Info 2 | ==== 3 | 4 | .. automodule:: mavsdk.info 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/log_files.rst: -------------------------------------------------------------------------------- 1 | LogFiles 2 | ==== 3 | 4 | .. automodule:: mavsdk.log_files 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/log_streaming.rst: -------------------------------------------------------------------------------- 1 | LogStreaming 2 | ==== 3 | 4 | .. automodule:: mavsdk.log_streaming 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/manual_control.rst: -------------------------------------------------------------------------------- 1 | ManualControl 2 | ==== 3 | 4 | .. automodule:: mavsdk.manual_control 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/mission.rst: -------------------------------------------------------------------------------- 1 | Mission 2 | ==== 3 | 4 | .. automodule:: mavsdk.mission 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/mission_raw.rst: -------------------------------------------------------------------------------- 1 | MissionRaw 2 | ==== 3 | 4 | .. automodule:: mavsdk.mission_raw 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/mission_raw_server.rst: -------------------------------------------------------------------------------- 1 | MissionRawServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.mission_raw_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/mocap.rst: -------------------------------------------------------------------------------- 1 | Mocap 2 | ==== 3 | 4 | .. automodule:: mavsdk.mocap 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/offboard.rst: -------------------------------------------------------------------------------- 1 | Offboard 2 | ==== 3 | 4 | .. automodule:: mavsdk.offboard 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/param.rst: -------------------------------------------------------------------------------- 1 | Param 2 | ==== 3 | 4 | .. automodule:: mavsdk.param 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/param_server.rst: -------------------------------------------------------------------------------- 1 | ParamServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.param_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/rtk.rst: -------------------------------------------------------------------------------- 1 | Rtk 2 | ==== 3 | 4 | .. automodule:: mavsdk.rtk 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/server_utility.rst: -------------------------------------------------------------------------------- 1 | ServerUtility 2 | ==== 3 | 4 | .. automodule:: mavsdk.server_utility 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/shell.rst: -------------------------------------------------------------------------------- 1 | Shell 2 | ==== 3 | 4 | .. automodule:: mavsdk.shell 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/telemetry.rst: -------------------------------------------------------------------------------- 1 | Telemetry 2 | ==== 3 | 4 | .. automodule:: mavsdk.telemetry 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/telemetry_server.rst: -------------------------------------------------------------------------------- 1 | TelemetryServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.telemetry_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/tracking_server.rst: -------------------------------------------------------------------------------- 1 | TrackingServer 2 | ==== 3 | 4 | .. automodule:: mavsdk.tracking_server 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/transponder.rst: -------------------------------------------------------------------------------- 1 | Transponder 2 | ==== 3 | 4 | .. automodule:: mavsdk.transponder 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/tune.rst: -------------------------------------------------------------------------------- 1 | Tune 2 | ==== 3 | 4 | .. automodule:: mavsdk.tune 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/plugins/winch.rst: -------------------------------------------------------------------------------- 1 | Winch 2 | ==== 3 | 4 | .. automodule:: mavsdk.winch 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc -------------------------------------------------------------------------------- /mavsdk/source/system.rst: -------------------------------------------------------------------------------- 1 | System 2 | ======= 3 | 4 | .. automodule:: mavsdk.system 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | -------------------------------------------------------------------------------- /mavsdk/tune_pb2.py: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # Generated by the protocol buffer compiler. DO NOT EDIT! 3 | # NO CHECKED-IN PROTOBUF GENCODE 4 | # source: tune/tune.proto 5 | # Protobuf Python Version: 5.29.0 6 | """Generated protocol buffer code.""" 7 | from google.protobuf import descriptor as _descriptor 8 | from google.protobuf import descriptor_pool as _descriptor_pool 9 | from google.protobuf import runtime_version as _runtime_version 10 | from google.protobuf import symbol_database as _symbol_database 11 | from google.protobuf.internal import builder as _builder 12 | _runtime_version.ValidateProtobufRuntimeVersion( 13 | _runtime_version.Domain.PUBLIC, 14 | 5, 15 | 29, 16 | 0, 17 | '', 18 | 'tune/tune.proto' 19 | ) 20 | # @@protoc_insertion_point(imports) 21 | 22 | _sym_db = _symbol_database.Default() 23 | 24 | 25 | 26 | 27 | DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x0ftune/tune.proto\x12\x0fmavsdk.rpc.tune\"M\n\x0fPlayTuneRequest\x12:\n\x10tune_description\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.tune.TuneDescription\"D\n\x10PlayTuneResponse\x12\x30\n\x0btune_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.tune.TuneResult\"U\n\x0fTuneDescription\x12\x33\n\rsong_elements\x18\x01 \x03(\x0e\x32\x1c.mavsdk.rpc.tune.SongElement\x12\r\n\x05tempo\x18\x02 \x01(\x05\"\xe3\x01\n\nTuneResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32\".mavsdk.rpc.tune.TuneResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x8c\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x18\n\x14RESULT_INVALID_TEMPO\x10\x02\x12\x18\n\x14RESULT_TUNE_TOO_LONG\x10\x03\x12\x10\n\x0cRESULT_ERROR\x10\x04\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x05*\xd1\x04\n\x0bSongElement\x12\x1d\n\x19SONG_ELEMENT_STYLE_LEGATO\x10\x00\x12\x1d\n\x19SONG_ELEMENT_STYLE_NORMAL\x10\x01\x12\x1f\n\x1bSONG_ELEMENT_STYLE_STACCATO\x10\x02\x12\x1b\n\x17SONG_ELEMENT_DURATION_1\x10\x03\x12\x1b\n\x17SONG_ELEMENT_DURATION_2\x10\x04\x12\x1b\n\x17SONG_ELEMENT_DURATION_4\x10\x05\x12\x1b\n\x17SONG_ELEMENT_DURATION_8\x10\x06\x12\x1c\n\x18SONG_ELEMENT_DURATION_16\x10\x07\x12\x1c\n\x18SONG_ELEMENT_DURATION_32\x10\x08\x12\x17\n\x13SONG_ELEMENT_NOTE_A\x10\t\x12\x17\n\x13SONG_ELEMENT_NOTE_B\x10\n\x12\x17\n\x13SONG_ELEMENT_NOTE_C\x10\x0b\x12\x17\n\x13SONG_ELEMENT_NOTE_D\x10\x0c\x12\x17\n\x13SONG_ELEMENT_NOTE_E\x10\r\x12\x17\n\x13SONG_ELEMENT_NOTE_F\x10\x0e\x12\x17\n\x13SONG_ELEMENT_NOTE_G\x10\x0f\x12\x1b\n\x17SONG_ELEMENT_NOTE_PAUSE\x10\x10\x12\x16\n\x12SONG_ELEMENT_SHARP\x10\x11\x12\x15\n\x11SONG_ELEMENT_FLAT\x10\x12\x12\x1a\n\x16SONG_ELEMENT_OCTAVE_UP\x10\x13\x12\x1c\n\x18SONG_ELEMENT_OCTAVE_DOWN\x10\x14\x32`\n\x0bTuneService\x12Q\n\x08PlayTune\x12 .mavsdk.rpc.tune.PlayTuneRequest\x1a!.mavsdk.rpc.tune.PlayTuneResponse\"\x00\x42\x1b\n\x0eio.mavsdk.tuneB\tTuneProtob\x06proto3') 28 | 29 | _globals = globals() 30 | _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) 31 | _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'tune.tune_pb2', _globals) 32 | if not _descriptor._USE_C_DESCRIPTORS: 33 | _globals['DESCRIPTOR']._loaded_options = None 34 | _globals['DESCRIPTOR']._serialized_options = b'\n\016io.mavsdk.tuneB\tTuneProto' 35 | _globals['_SONGELEMENT']._serialized_start=503 36 | _globals['_SONGELEMENT']._serialized_end=1096 37 | _globals['_PLAYTUNEREQUEST']._serialized_start=36 38 | _globals['_PLAYTUNEREQUEST']._serialized_end=113 39 | _globals['_PLAYTUNERESPONSE']._serialized_start=115 40 | _globals['_PLAYTUNERESPONSE']._serialized_end=183 41 | _globals['_TUNEDESCRIPTION']._serialized_start=185 42 | _globals['_TUNEDESCRIPTION']._serialized_end=270 43 | _globals['_TUNERESULT']._serialized_start=273 44 | _globals['_TUNERESULT']._serialized_end=500 45 | _globals['_TUNERESULT_RESULT']._serialized_start=360 46 | _globals['_TUNERESULT_RESULT']._serialized_end=500 47 | _globals['_TUNESERVICE']._serialized_start=1098 48 | _globals['_TUNESERVICE']._serialized_end=1194 49 | # @@protoc_insertion_point(module_scope) 50 | -------------------------------------------------------------------------------- /mavsdk/tune_pb2_grpc.py: -------------------------------------------------------------------------------- 1 | # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! 2 | """Client and server classes corresponding to protobuf-defined services.""" 3 | import grpc 4 | import warnings 5 | 6 | from . import tune_pb2 as tune_dot_tune__pb2 7 | 8 | GRPC_GENERATED_VERSION = '1.71.0' 9 | GRPC_VERSION = grpc.__version__ 10 | _version_not_supported = False 11 | 12 | try: 13 | from grpc._utilities import first_version_is_lower 14 | _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) 15 | except ImportError: 16 | _version_not_supported = True 17 | 18 | if _version_not_supported: 19 | raise RuntimeError( 20 | f'The grpc package installed is at version {GRPC_VERSION},' 21 | + f' but the generated code in tune/tune_pb2_grpc.py depends on' 22 | + f' grpcio>={GRPC_GENERATED_VERSION}.' 23 | + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' 24 | + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' 25 | ) 26 | 27 | 28 | class TuneServiceStub(object): 29 | """Enable creating and sending a tune to be played on the system. 30 | """ 31 | 32 | def __init__(self, channel): 33 | """Constructor. 34 | 35 | Args: 36 | channel: A grpc.Channel. 37 | """ 38 | self.PlayTune = channel.unary_unary( 39 | '/mavsdk.rpc.tune.TuneService/PlayTune', 40 | request_serializer=tune_dot_tune__pb2.PlayTuneRequest.SerializeToString, 41 | response_deserializer=tune_dot_tune__pb2.PlayTuneResponse.FromString, 42 | _registered_method=True) 43 | 44 | 45 | class TuneServiceServicer(object): 46 | """Enable creating and sending a tune to be played on the system. 47 | """ 48 | 49 | def PlayTune(self, request, context): 50 | """Send a tune to be played by the system. 51 | """ 52 | context.set_code(grpc.StatusCode.UNIMPLEMENTED) 53 | context.set_details('Method not implemented!') 54 | raise NotImplementedError('Method not implemented!') 55 | 56 | 57 | def add_TuneServiceServicer_to_server(servicer, server): 58 | rpc_method_handlers = { 59 | 'PlayTune': grpc.unary_unary_rpc_method_handler( 60 | servicer.PlayTune, 61 | request_deserializer=tune_dot_tune__pb2.PlayTuneRequest.FromString, 62 | response_serializer=tune_dot_tune__pb2.PlayTuneResponse.SerializeToString, 63 | ), 64 | } 65 | generic_handler = grpc.method_handlers_generic_handler( 66 | 'mavsdk.rpc.tune.TuneService', rpc_method_handlers) 67 | server.add_generic_rpc_handlers((generic_handler,)) 68 | server.add_registered_method_handlers('mavsdk.rpc.tune.TuneService', rpc_method_handlers) 69 | 70 | 71 | # This class is part of an EXPERIMENTAL API. 72 | class TuneService(object): 73 | """Enable creating and sending a tune to be played on the system. 74 | """ 75 | 76 | @staticmethod 77 | def PlayTune(request, 78 | target, 79 | options=(), 80 | channel_credentials=None, 81 | call_credentials=None, 82 | insecure=False, 83 | compression=None, 84 | wait_for_ready=None, 85 | timeout=None, 86 | metadata=None): 87 | return grpc.experimental.unary_unary( 88 | request, 89 | target, 90 | '/mavsdk.rpc.tune.TuneService/PlayTune', 91 | tune_dot_tune__pb2.PlayTuneRequest.SerializeToString, 92 | tune_dot_tune__pb2.PlayTuneResponse.FromString, 93 | options, 94 | channel_credentials, 95 | insecure, 96 | call_credentials, 97 | compression, 98 | wait_for_ready, 99 | timeout, 100 | metadata, 101 | _registered_method=True) 102 | -------------------------------------------------------------------------------- /other/docker/testing/Dockerfile: -------------------------------------------------------------------------------- 1 | FROM ubuntu:18.04 2 | 3 | # Prefere local python binaries over the distributed ones 4 | ENV PATH /usr/local/bin:$PATH 5 | 6 | # Needed for Python 3 7 | ENV LANG C.UTF-8 8 | 9 | RUN apt update \ 10 | && apt-get --yes install tzdata \ 11 | && ln -sf /usr/share/zoneinfo/Europe/Berlin /etc/localtime \ 12 | && apt install --yes python python-dev python-pip wget\ 13 | python3 python3-dev python3-pip \ 14 | build-essential checkinstall python3-setuptools\ 15 | libreadline-gplv2-dev libncursesw5-dev zlib1g-dev\ 16 | libssl-dev libsqlite3-dev tk-dev python-smbus\ 17 | libgdbm-dev libc6-dev libbz2-dev libffi-dev\ 18 | && rm -rf /var/lib/apt/lists/* 19 | 20 | # Copy build script 21 | COPY build_python.sh /build_python.sh 22 | 23 | # PYTHON VERSIONS 24 | ENV PYTHON_VERSIONS 3.7.0 25 | ENV PYTHON_PIP_VERSION 10.0.1 26 | 27 | # Build python versions using the script 28 | RUN bash -ex /build_python.sh 29 | 30 | # Installing tox for one python version is sufficient 31 | RUN pip3 install tox 32 | 33 | # Copy script for testing 34 | COPY test.sh /test.sh 35 | 36 | # Set ENTRYPOINT 37 | ENTRYPOINT ["sh", "-ex", "/test.sh"] 38 | -------------------------------------------------------------------------------- /other/docker/testing/build_python.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # 4 | # Helper for building python versions 5 | # 6 | # Based on https://github.com/xvzf/tox-docker/blob/master/build_python.sh 7 | # 8 | 9 | 10 | gnuArch="$(dpkg-architecture --query DEB_BUILD_GNU_TYPE)" \ 11 | 12 | 13 | function clean_pyc { 14 | find /usr/local -depth \ 15 | \( \ 16 | \( -type d -a \( -name test -o -name tests \) \) \ 17 | -o \ 18 | \( -type f -a \( -name '*.pyc' -o -name '*.pyo' \) \) \ 19 | \) -exec rm -rf '{}' + 20 | } 21 | 22 | 23 | # Install python 24 | for PYTHON_VERSION in $PYTHON_VERSIONS; do 25 | 26 | cd /tmp 27 | 28 | # Get source 29 | wget -O "python_${PYTHON_VERSION}.tar.xz" \ 30 | "https://www.python.org/ftp/python/${PYTHON_VERSION%%[a-z]*}/Python-${PYTHON_VERSION}.tar.xz" 31 | 32 | 33 | # Extract source 34 | mkdir -p "/usr/src/python_${PYTHON_VERSION}" 35 | tar xJC "/usr/src/python_${PYTHON_VERSION}" --strip-components=1 \ 36 | -f python_${PYTHON_VERSION}.tar.xz 37 | 38 | rm "python_${PYTHON_VERSION}.tar.xz" 39 | 40 | 41 | # Configure, build and install 42 | cd "/usr/src/python_${PYTHON_VERSION}" 43 | ./configure \ 44 | --build="$gnuArch" \ 45 | --enable-loadable-sqlite-extensions \ 46 | --enable-shared \ 47 | --with-system-expat \ 48 | --with-system-ffi \ 49 | --without-ensurepip \ 50 | --enable-unicode=ucs4 \ 51 | --prefix=/usr/local \ 52 | LDFLAGS="-Wl,--rpath=/usr/local/lib" 53 | 54 | make -j "$(nproc)" 55 | 56 | EXTRA_CFLAGS="-DTHREAD_STACK_SIZE=0x100000" make install 57 | 58 | # Cleanup 59 | rm -Rf "/usr/src/python_${PYTHON_VERSION}" 60 | clean_pyc 61 | 62 | 63 | done 64 | 65 | 66 | # Install pip 67 | cd /tmp 68 | wget -O get-pip.py "https://bootstrap.pypa.io/get-pip.py" 69 | for PYTHON_VERSION in $PYTHON_VERSIONS; do 70 | 71 | # Install pip 72 | 73 | python${PYTHON_VERSION%.*} get-pip.py \ 74 | --disable-pip-version-check \ 75 | --no-cache-dir \ 76 | "pip==$PYTHON_PIP_VERSION" 77 | 78 | # Cleanup 79 | clean_pyc 80 | done 81 | -------------------------------------------------------------------------------- /other/docker/testing/test.sh: -------------------------------------------------------------------------------- 1 | #!/bin/sh 2 | 3 | # We do NOT want to test in the actual mountpoint, therefore create a copy! 4 | cp -Rf /src /srccopy && cd /srccopy 5 | 6 | # Run tox for testing 7 | tox --skip-missing-interpreters 8 | -------------------------------------------------------------------------------- /other/templates/py/call.j2: -------------------------------------------------------------------------------- 1 | 2 | async def {{ name.lower_snake_case }}(self{% for param in params %}, {{ param.name.lower_snake_case }}{% endfor %}): 3 | """ 4 | {{ indent(method_description, 1) }} 5 | 6 | {% if params -%} 7 | Parameters 8 | ---------- 9 | {% for param in params -%} 10 | {{ param.name.lower_snake_case }} : {{ param.type_info.name }} 11 | {{ param.description }} 12 | {% endfor -%} 13 | {% endif -%} 14 | 15 | {% if has_result -%} 16 | Raises 17 | ------ 18 | {{ plugin_name.upper_camel_case }}Error 19 | If the request fails. The error contains the reason for the failure. 20 | {%- endif %} 21 | """ 22 | 23 | request = {{ plugin_name.lower_snake_case }}_pb2.{{ name.upper_camel_case }}Request() 24 | {% for param in params %} 25 | {%- if param.type_info.is_primitive -%} 26 | request.{{ param.name.lower_snake_case }} = {{ param.name.lower_snake_case }} 27 | {%- else -%} 28 | {% if param.type_info.is_repeated %} 29 | rpc_elems_list = [] 30 | for elem in {{ param.name.lower_snake_case }}: 31 | {% if param.type_info.is_enum %} 32 | rpc_elems_list.append(elem.translate_to_rpc()) 33 | {% else %} 34 | rpc_elem = {{ plugin_name.lower_snake_case }}_pb2.{{ param.type_info.inner_name }}() 35 | elem.translate_to_rpc(rpc_elem) 36 | rpc_elems_list.append(rpc_elem) 37 | {% endif %} 38 | request.{{ param.name.lower_snake_case }}.extend(rpc_elems_list) 39 | {% elif param.type_info.is_enum %} 40 | request.{{ param.name.lower_snake_case }} = {{ param.name.lower_snake_case }}.translate_to_rpc() 41 | {% else %} 42 | {{ param.name.lower_snake_case }}.translate_to_rpc(request.{{ param.name.lower_snake_case }}) 43 | {% endif %} 44 | {% endif %} 45 | {% endfor -%} 46 | response = await self._stub.{{ name.upper_camel_case }}(request) 47 | 48 | {% if has_result %} 49 | result = self._extract_result(response) 50 | 51 | if result.result != {{ plugin_name.upper_camel_case }}Result.Result.SUCCESS: 52 | raise {{ plugin_name.upper_camel_case }}Error(result, "{{ name.lower_snake_case }}()"{% for param in params %}, {{ param.name.lower_snake_case }}{% endfor %}) 53 | {% endif %} 54 | -------------------------------------------------------------------------------- /other/templates/py/enum.j2: -------------------------------------------------------------------------------- 1 | class {{ name.upper_camel_case }}(Enum): 2 | """ 3 | {{ indent(enum_description, 1) }} 4 | 5 | Values 6 | ------ 7 | {% for value in values -%} 8 | {{ value.name.uppercase }} 9 | {{ value.description }} 10 | {% endfor -%} 11 | """ 12 | 13 | {% for value in values %} 14 | {{ value.name.uppercase }} = {{ loop.index - 1 }} 15 | {%- endfor %} 16 | 17 | def translate_to_rpc(self): 18 | {%- for value in values %} 19 | if self == {% if parent_struct is not none %}{{ parent_struct.upper_camel_case }}.{% endif %}{{ name.upper_camel_case }}.{{ value.name.uppercase }}: 20 | return {{ plugin_name.lower_snake_case }}_pb2.{% if parent_struct is not none %}{{ parent_struct.upper_camel_case }}.{% endif %}{{ name.uppercase }}_{{ value.name.uppercase }} 21 | {%- endfor %} 22 | 23 | @staticmethod 24 | def translate_from_rpc(rpc_enum_value): 25 | """ Parses a gRPC response """ 26 | {%- for value in values %} 27 | if rpc_enum_value == {{ plugin_name.lower_snake_case }}_pb2.{% if parent_struct is not none %}{{ parent_struct.upper_camel_case }}.{% endif %}{{ name.uppercase }}_{{ value.name.uppercase }}: 28 | return {% if parent_struct is not none %}{{ parent_struct.upper_camel_case }}.{% endif %}{{ name.upper_camel_case }}.{{ value.name.uppercase }} 29 | {%- endfor %} 30 | 31 | def __str__(self): 32 | return self.name 33 | -------------------------------------------------------------------------------- /other/templates/py/file.j2: -------------------------------------------------------------------------------- 1 | # -*- coding: utf-8 -*- 2 | # DO NOT EDIT! This file is auto-generated from 3 | # https://github.com/mavlink/MAVSDK-Python/tree/main/other/templates/py 4 | from ._base import AsyncBase 5 | from . import {{ plugin_name.lower_snake_case }}_pb2, {{ plugin_name.lower_snake_case }}_pb2_grpc 6 | from enum import Enum 7 | 8 | {%- for enum in enums %} 9 | 10 | 11 | {{ enum }} 12 | {%- endfor %} 13 | 14 | 15 | {%- for struct in structs %} 16 | 17 | 18 | {{ struct }} 19 | {%- endfor %} 20 | 21 | 22 | {% if has_result %} 23 | class {{ plugin_name.upper_camel_case }}Error(Exception): 24 | """ Raised when a {{ plugin_name.upper_camel_case }}Result is a fail code """ 25 | 26 | def __init__(self, result, origin, *params): 27 | self._result = result 28 | self._origin = origin 29 | self._params = params 30 | 31 | def __str__(self): 32 | return f"{self._result.result}: '{self._result.result_str}'; origin: {self._origin}; params: {self._params}" 33 | {% endif %} 34 | 35 | class {{ plugin_name.upper_camel_case }}(AsyncBase): 36 | """ 37 | {{ indent(class_description, 1) }} 38 | 39 | Generated by dcsdkgen - MAVSDK {{ plugin_name.upper_camel_case }} API 40 | """ 41 | 42 | # Plugin name 43 | name = "{{ plugin_name.upper_camel_case }}" 44 | 45 | def _setup_stub(self, channel): 46 | """ Setups the api stub """ 47 | self._stub = {{ plugin_name.lower_snake_case }}_pb2_grpc.{{ plugin_name.upper_camel_case }}ServiceStub(channel) 48 | 49 | {% if has_result %} 50 | def _extract_result(self, response): 51 | """ Returns the response status and description """ 52 | return {{ plugin_name.upper_camel_case }}Result.translate_from_rpc(response.{{ plugin_name.lower_snake_case }}_result) 53 | {% endif %} 54 | 55 | {%- for method in methods -%} 56 | {{ '\n' + indent(method, 1) }} 57 | 58 | {%- endfor %} 59 | -------------------------------------------------------------------------------- /other/templates/py/request.j2: -------------------------------------------------------------------------------- 1 | 2 | async def {{ name.lower_snake_case }}(self{% for param in params %}, {{ param.name.lower_snake_case }}{% endfor %}): 3 | """ 4 | {{ indent(method_description, 1) }} 5 | 6 | {% if params -%} 7 | Parameters 8 | ---------- 9 | {% for param in params -%} 10 | {{ param.name.lower_snake_case }} : {{ param.type_info.name }} 11 | {{ param.description }} 12 | {% endfor -%} 13 | {% endif -%} 14 | 15 | Returns 16 | ------- 17 | {{ return_name.lower_snake_case }} : {{ return_type.name }} 18 | {{ return_description }} 19 | {% if has_result -%} 20 | Raises 21 | ------ 22 | {{ plugin_name.upper_camel_case }}Error 23 | If the request fails. The error contains the reason for the failure. 24 | {%- endif %} 25 | """ 26 | 27 | request = {{ plugin_name.lower_snake_case }}_pb2.{{ name.upper_camel_case }}Request() 28 | {% for param in params %} 29 | {% if param.type_info.is_primitive %} 30 | request.{{ param.name.lower_snake_case }} = {{ param.name.lower_snake_case }} 31 | {% else %} 32 | {% if param.type_info.is_repeated %} 33 | rpc_elems_list = [] 34 | for elem in {{ param.name.lower_snake_case }}: 35 | {% if param.type_info.is_enum %} 36 | rpc_elems_list.append(elem.translate_to_rpc()) 37 | {% else %} 38 | rpc_elem = {{ plugin_name.lower_snake_case }}_pb2.{{ param.type_info.inner_name }}() 39 | elem.translate_to_rpc(rpc_elem) 40 | rpc_elems_list.append(rpc_elem) 41 | {% endif %} 42 | request.{{ param.name.lower_snake_case }}.extend(rpc_elems_list) 43 | {% elif param.type_info.is_enum %} 44 | request.{{ param.name.lower_snake_case }} = {{ param.name.lower_snake_case }}.translate_to_rpc() 45 | {% else %} 46 | {{ param.name.lower_snake_case }}.translate_to_rpc(request.{{ param.name.lower_snake_case }}) 47 | {% endif %} 48 | {% endif %} 49 | {% endfor -%} 50 | response = await self._stub.{{ name.upper_camel_case }}(request) 51 | 52 | {% if has_result %} 53 | result = self._extract_result(response) 54 | 55 | if result.result != {{ plugin_name.upper_camel_case }}Result.Result.SUCCESS: 56 | raise {{ plugin_name.upper_camel_case }}Error(result, "{{ name.lower_snake_case }}()"{% for param in params %}, {{ param.name.lower_snake_case }}{% endfor %}) 57 | {% endif %} 58 | 59 | {% if return_type.is_primitive -%} 60 | return response.{{ return_name.lower_snake_case }} 61 | {% else -%} 62 | {% if return_type.is_repeated -%} 63 | {{ return_name.lower_snake_case }} = [] 64 | for {{ return_name.lower_snake_case }}_rpc in response.{{ return_name.lower_snake_case }}: 65 | {{ return_name.lower_snake_case }}.append({{ return_type.inner_name }}.translate_from_rpc({{ return_name.lower_snake_case }}_rpc)) 66 | 67 | return {{ return_name.lower_snake_case }} 68 | {% else -%} 69 | return {{ return_type.inner_name }}.translate_from_rpc(response.{{ return_name.lower_snake_case }}) 70 | {% endif -%} 71 | {% endif %} 72 | -------------------------------------------------------------------------------- /other/templates/py/stream.j2: -------------------------------------------------------------------------------- 1 | 2 | async def {{ name.lower_snake_case }}(self{% for param in params %}, {{ param.name.lower_snake_case }}{% endfor %}): 3 | """ 4 | {{ indent(method_description, 1) }} 5 | 6 | {% if params -%} 7 | Parameters 8 | ---------- 9 | {% for param in params -%} 10 | {{ param.name.lower_snake_case }} : {{ param.type_info.name }} 11 | {{ param.description }} 12 | {% endfor -%} 13 | {% endif -%} 14 | 15 | Yields 16 | ------- 17 | {{ return_name.lower_snake_case }} : {{ return_type.name }} 18 | {{ return_description }} 19 | {% if has_result -%} 20 | Raises 21 | ------ 22 | {{ plugin_name.upper_camel_case }}Error 23 | If the request fails. The error contains the reason for the failure. 24 | {%- endif %} 25 | """ 26 | 27 | request = {{ plugin_name.lower_snake_case }}_pb2.Subscribe{{ name.upper_camel_case }}Request() 28 | {% for param in params %} 29 | {%- if param.type_info.is_primitive -%} 30 | request.{{ param.name.lower_snake_case }} = {{ param.name.lower_snake_case }} 31 | {%- else -%} 32 | {% if param.type_info.is_repeated %} 33 | rpc_elems_list = [] 34 | for elem in {{ param.name.lower_snake_case }}: 35 | {% if param.type_info.is_enum %} 36 | rpc_elems_list.append(elem.translate_to_rpc()) 37 | {% else %} 38 | rpc_elem = {{ plugin_name.lower_snake_case }}_pb2.{{ param.type_info.inner_name }}() 39 | elem.translate_to_rpc(rpc_elem) 40 | rpc_elems_list.append(rpc_elem) 41 | {% endif %} 42 | request.{{ param.name.lower_snake_case }}.extend(rpc_elems_list) 43 | {% elif param.type_info.is_enum %} 44 | request.{{ param.name.lower_snake_case }} = {{ param.name.lower_snake_case }}.translate_to_rpc() 45 | {% else %} 46 | {{ param.name.lower_snake_case }}.translate_to_rpc(request.{{ param.name.lower_snake_case }}) 47 | {% endif %} 48 | {% endif %} 49 | {% endfor -%} 50 | {{ name.lower_snake_case }}_stream = self._stub.Subscribe{{ name.upper_camel_case }}(request) 51 | 52 | try: 53 | async for response in {{ name.lower_snake_case }}_stream: 54 | {% if has_result %} 55 | result = self._extract_result(response) 56 | 57 | success_codes = [{{ plugin_name.upper_camel_case }}Result.Result.SUCCESS] 58 | if 'NEXT' in [return_code.name for return_code in {{ plugin_name.upper_camel_case }}Result.Result]: 59 | success_codes.append({{ plugin_name.upper_camel_case }}Result.Result.NEXT) 60 | 61 | if result.result not in success_codes: 62 | raise {{ plugin_name.upper_camel_case }}Error(result, "{{ name.lower_snake_case }}()"{% for param in params %}, {{ param.name.lower_snake_case }}{% endfor %}) 63 | 64 | if result.result == {{ plugin_name.upper_camel_case }}Result.Result.SUCCESS: 65 | {{ name.lower_snake_case }}_stream.cancel(); 66 | return 67 | {% endif %} 68 | 69 | {% if not return_type %} 70 | yield None 71 | {%- elif return_type.is_primitive %} 72 | yield response.{{ return_name.lower_snake_case }} 73 | {%- elif not return_type.is_primitive and not return_type.is_repeated %} 74 | yield {{ return_type.name }}.translate_from_rpc(response.{{ return_name.lower_snake_case }}) 75 | {%- elif not return_type.is_primitive and return_type.is_repeated %} 76 | yield list(map(lambda x : {{ return_type.inner_name }}.translate_from_rpc(x), response.{{ return_name.lower_snake_case }})) 77 | {%- endif %} 78 | finally: 79 | {{ name.lower_snake_case }}_stream.cancel() 80 | -------------------------------------------------------------------------------- /other/templates/py/struct.j2: -------------------------------------------------------------------------------- 1 | class {{ name.upper_camel_case }}: 2 | """ 3 | {{ indent(struct_description, 1) }} 4 | 5 | Parameters 6 | ---------- 7 | {% for field in fields -%} 8 | {{ field.name.lower_snake_case }} : {{ field.type_info.name }} 9 | {{ field.description }} 10 | {% endfor -%} 11 | """ 12 | 13 | {% for nested_enum in nested_enums %} 14 | {{ '\n' + indent(nested_enums[nested_enum], 1) }} 15 | {% endfor %} 16 | 17 | def __init__( 18 | self, 19 | {%- for field in fields %} 20 | {{ field.name.lower_snake_case }}{{ "," if not loop.last }} 21 | {%- endfor %}): 22 | """ Initializes the {{ name.upper_camel_case }} object """ 23 | {%- for field in fields %} 24 | self.{{ field.name.lower_snake_case }} = {{ field.name.lower_snake_case }} 25 | {%- endfor %} 26 | 27 | def __eq__(self, to_compare): 28 | """ Checks if two {{ name.upper_camel_case }} are the same """ 29 | try: 30 | # Try to compare - this likely fails when it is compared to a non 31 | # {{ name.upper_camel_case }} object 32 | return \ 33 | {%- for field in fields %} 34 | (self.{{ field.name.lower_snake_case }} == to_compare.{{ field.name.lower_snake_case }}){{ " and \\" if not loop.last }} 35 | {%- endfor %} 36 | 37 | except AttributeError: 38 | return False 39 | 40 | def __str__(self): 41 | """ {{ name.upper_camel_case }} in string representation """ 42 | struct_repr = ", ".join([ 43 | {%- for field in fields %} 44 | "{{ field.name.lower_snake_case }}: " + str(self.{{ field.name.lower_snake_case }}){{ "," if not loop.last }} 45 | {%- endfor %} 46 | ]) 47 | 48 | return f"{{ name.upper_camel_case }}: [{struct_repr}]" 49 | 50 | @staticmethod 51 | def translate_from_rpc(rpc{{ name.upper_camel_case }}): 52 | """ Translates a gRPC struct to the SDK equivalent """ 53 | return {{ name.upper_camel_case }}( 54 | {%- for field in fields %} 55 | {% if field.type_info.is_primitive %} 56 | rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }}{{ "," if not loop.last }} 57 | {% else %} 58 | {%- if field.type_info.is_repeated %} 59 | list(map(lambda elem: {{ field.type_info.inner_name }}.translate_from_rpc(elem), rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }})){{ "," if not loop.last }} 60 | {%- else %} 61 | {% if field.type_info.parent_type is not none %}{{ field.type_info.parent_type }}.{% endif %}{{ field.type_info.inner_name }}.translate_from_rpc(rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }}){{ "," if not loop.last }} 62 | {%- endif %} 63 | {% endif %} 64 | {%- endfor %}) 65 | 66 | def translate_to_rpc(self, rpc{{ name.upper_camel_case }}): 67 | """ Translates this SDK object into its gRPC equivalent """ 68 | 69 | {% for field in fields %} 70 | {% if field.type_info.is_repeated %} 71 | {% if field.type_info.is_primitive %} 72 | for elem in self.{{ field.name.lower_snake_case}}: 73 | rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }}.append(elem) 74 | {% else %} 75 | rpc_elems_list = [] 76 | for elem in self.{{ field.name.lower_snake_case }}: 77 | {% if field.type_info.is_enum %} 78 | rpc_elems_list.append(elem.translate_to_rpc()) 79 | {% else %} 80 | rpc_elem = {{ plugin_name.lower_snake_case }}_pb2.{{ field.type_info.inner_name }}() 81 | elem.translate_to_rpc(rpc_elem) 82 | rpc_elems_list.append(rpc_elem) 83 | {% endif %} 84 | rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }}.extend(rpc_elems_list) 85 | {% endif %} 86 | {% else %} 87 | {% if field.type_info.is_primitive %} 88 | rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }} = self.{{ field.name.lower_snake_case }} 89 | {% elif field.type_info.is_enum %} 90 | rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }} = self.{{ field.name.lower_snake_case }}.translate_to_rpc() 91 | {% else %} 92 | self.{{ field.name.lower_snake_case}}.translate_to_rpc(rpc{{ name.upper_camel_case }}.{{ field.name.lower_snake_case }}) 93 | {% endif %} 94 | {% endif %} 95 | {% endfor %} 96 | -------------------------------------------------------------------------------- /other/templates/py/type_conversions: -------------------------------------------------------------------------------- 1 | { 2 | "repeated": { "prefix": "[", "suffix": "]" } 3 | } 4 | -------------------------------------------------------------------------------- /other/templates/rst/call.j2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/other/templates/rst/call.j2 -------------------------------------------------------------------------------- /other/templates/rst/enum.j2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/other/templates/rst/enum.j2 -------------------------------------------------------------------------------- /other/templates/rst/file.j2: -------------------------------------------------------------------------------- 1 | {{ plugin_name.upper_camel_case }} 2 | ==== 3 | 4 | .. automodule:: mavsdk.{{ plugin_name.lower_snake_case }} 5 | :members: 6 | :undoc-members: 7 | :show-inheritance: 8 | :exclude-members: translate_from_rpc, translate_to_rpc 9 | -------------------------------------------------------------------------------- /other/templates/rst/request.j2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/other/templates/rst/request.j2 -------------------------------------------------------------------------------- /other/templates/rst/stream.j2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/other/templates/rst/stream.j2 -------------------------------------------------------------------------------- /other/templates/rst/struct.j2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/other/templates/rst/struct.j2 -------------------------------------------------------------------------------- /other/templates/rst/type_conversions: -------------------------------------------------------------------------------- 1 | { 2 | "repeated": { "prefix": "[", "suffix": "]" } 3 | } 4 | -------------------------------------------------------------------------------- /other/tools/run_protoc.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | set -e 4 | 5 | SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" 6 | WORK_DIR="${SCRIPT_DIR%/*/*}" 7 | PROTO_DIR="${WORK_DIR}/proto" 8 | GENERATED_DIR="${WORK_DIR}/mavsdk" 9 | TEMPLATE_PATH="${WORK_DIR}/other/templates/py" 10 | 11 | TEMPLATE_PATH_RST="${WORK_DIR}/other/templates/rst" 12 | GENERATED_DIR_RST="${WORK_DIR}/mavsdk/source/plugins" 13 | 14 | PLUGIN_LIST=$(cd "${WORK_DIR}/proto/protos" && ls -d */ | sed 's:/*$::') 15 | 16 | command -v protoc-gen-mavsdk > /dev/null || { 17 | echo "-------------------------------" 18 | echo " Error" 19 | echo "-------------------------------" 20 | echo >&2 "'protoc-gen-mavsdk' not found in PATH" 21 | echo >&2 "" 22 | echo >&2 "Make sure 'protoc-gen-mavsdk' is installed and available" 23 | exit 1 24 | } 25 | 26 | function snake_case_to_camel_case { 27 | echo $1 | awk -v FS="_" -v OFS="" '{for (i=1;i<=NF;i++) $i=toupper(substr($i,1,1)) substr($i,2)} 1' 28 | } 29 | 30 | function generate { 31 | # Generate our extensions 32 | python3 -m grpc_tools.protoc -I${PROTO_DIR}/protos \ 33 | --python_out=${GENERATED_DIR} \ 34 | --grpc_python_out=${GENERATED_DIR} \ 35 | mavsdk_options.proto 36 | 37 | for plugin in ${PLUGIN_LIST}; do 38 | 39 | echo " -> [+] Generating bindings for ${plugin}" 40 | # Generate protobuf and gRPC files 41 | python3 -m grpc_tools.protoc -I${PROTO_DIR}/protos \ 42 | --python_out=${GENERATED_DIR} \ 43 | --grpc_python_out=${GENERATED_DIR} \ 44 | ${plugin}/${plugin}.proto 45 | 46 | # We need to create the .original backup files, otherwise we're not compatible with 47 | # BSD sed. 48 | sed -i'.sedoriginal' -e "s/import mavsdk_options_pb2/from . import mavsdk_options_pb2/" \ 49 | "${GENERATED_DIR}/${plugin}/${plugin}_pb2.py" 50 | sed -i'.sedoriginal' -e "s/from ${plugin} import ${plugin}_pb2/from . import ${plugin}_pb2/" \ 51 | "${GENERATED_DIR}/${plugin}/${plugin}_pb2_grpc.py" 52 | # Clean up the backup files. 53 | find ${GENERATED_DIR} -name '*.sedoriginal' -delete 54 | 55 | mv "${GENERATED_DIR}/${plugin}/${plugin}_pb2.py" "${GENERATED_DIR}/${plugin}_pb2.py" 56 | mv "${GENERATED_DIR}/${plugin}/${plugin}_pb2_grpc.py" "${GENERATED_DIR}/${plugin}_pb2_grpc.py" 57 | 58 | echo " -> [+] Generated protobuf and gRPC bindings for ${plugin}" 59 | 60 | # Generate plugin 61 | python3 -m grpc_tools.protoc -I${PROTO_DIR}/protos \ 62 | --plugin=protoc-gen-custom=$(which protoc-gen-mavsdk) \ 63 | --custom_out=${GENERATED_DIR} \ 64 | --custom_opt="file_ext=py,template_path=${TEMPLATE_PATH}" \ 65 | ${plugin}/${plugin}.proto 66 | 67 | # protoc-gen-mavsdk capitalizes filenames, and we don't want that with python 68 | mv -f ${GENERATED_DIR}/${plugin}/$(snake_case_to_camel_case ${plugin}).py ${GENERATED_DIR}/${plugin}.py 69 | 70 | echo " -> [+] Generated plugin for ${plugin}" 71 | 72 | # Generate plugin doc entry 73 | python3 -m grpc_tools.protoc -I${PROTO_DIR}/protos \ 74 | --proto_path=${PROTO_DIR}/protos/${plugin} \ 75 | --plugin=protoc-gen-custom=$(which protoc-gen-mavsdk) \ 76 | --custom_out=${GENERATED_DIR_RST} \ 77 | --custom_opt="file_ext=rst,template_path=${TEMPLATE_PATH_RST}" \ 78 | ${plugin}.proto 79 | 80 | # Again move generated file to its place. 81 | mv "${GENERATED_DIR_RST}/$(snake_case_to_camel_case ${plugin}).rst" "${GENERATED_DIR_RST}/temp.rst" 82 | mv "${GENERATED_DIR_RST}/temp.rst" "${GENERATED_DIR_RST}/${plugin}.rst" 83 | 84 | echo " -> [+] Generated doc entry for ${plugin}" 85 | 86 | # Add plugin entry to docs index if not already listed. 87 | if [[ ! $(grep ${plugin} ${GENERATED_DIR_RST}/index.rst) ]]; then 88 | echo " -> [+] Add doc entry for ${plugin} to index" 89 | echo " ${plugin}" >> ${GENERATED_DIR_RST}/index.rst 90 | fi 91 | 92 | rmdir ${GENERATED_DIR}/${plugin} 93 | 94 | done 95 | } 96 | 97 | echo "[+] Generating plugins from " 98 | generate 99 | echo "[+] Done" 100 | -------------------------------------------------------------------------------- /other/tools/run_tests.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" 3 | WORK_DIR="${SCRIPT_DIR}/../.." 4 | DOCKER_DIR="${WORK_DIR}/other/docker/testing/" 5 | DOCKER_IMAGE_NAME="tox-mavsdk-python" 6 | DOCKER_BUILD_LOG_PATH="/tmp/mavsdk-python-docker-build.log" 7 | 8 | function build_docker_image { 9 | cd $DOCKER_DIR 10 | echo "-> [+] Building the docker image used for testing multiple python versions (this can take some time)" 11 | docker build . -t $DOCKER_IMAGE_NAME &> $DOCKER_BUILD_LOG_PATH 12 | if [ $? -eq 0 ]; then 13 | echo "-> [+] Done!" 14 | else 15 | echo "-> [-] Failed to build the docker image, see ${DOCKER_BUILD_LOG_PATH}" 16 | exit 1 17 | fi 18 | cd $WORK_DIR 19 | } 20 | 21 | function run_tox { 22 | echo "-> [+] Running the test suite!" 23 | docker run --rm -v ${WORK_DIR}:/src $DOCKER_IMAGE_NAME 24 | } 25 | 26 | echo "[+] Building docker image" 27 | build_docker_image 28 | 29 | echo "[+] Running tests" 30 | run_tox 31 | -------------------------------------------------------------------------------- /other/tools/upload_docs.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | 3 | # Helper to upload artifact to s3 and set permissions and metadata correct. 4 | # http://mavsdk-python-docs.s3-website.eu-central-1.amazonaws.com/ 5 | 6 | # Sync everything 7 | s3cmd sync mavsdk/build/html/ s3://mavsdk-python-docs 8 | 9 | # Fix meta data 10 | s3cmd put -m text/html mavsdk/build/html/index.html s3://mavsdk-python-docs 11 | 12 | s3cmd put -m text/javascript mavsdk/build/html/searchindex.js s3://mavsdk-python-docs 13 | s3cmd put -m text/javascript mavsdk/build/html/_static/jquery.js s3://mavsdk-python-docs/_static/ 14 | s3cmd put -m text/javascript mavsdk/build/html/_static/doctools.js s3://mavsdk-python-docs/_static/ 15 | s3cmd put -m text/javascript mavsdk/build/html/_static/underscore.js s3://mavsdk-python-docs/_static/ 16 | s3cmd put -m text/javascript mavsdk/build/html/_static/documentation_options.js s3://mavsdk-python-docs/_static/ 17 | s3cmd put -m text/javascript mavsdk/build/html/_static/language_data.js s3://mavsdk-python-docs/_static/ 18 | s3cmd put -m text/css mavsdk/build/html/_static/nature.css s3://mavsdk-python-docs/_static/ 19 | s3cmd put -m text/css mavsdk/build/html/_static/basic.css s3://mavsdk-python-docs/_static/ 20 | 21 | s3cmd put -m image/x-icon mavsdk/build/html/_static/favicon.png s3://mavsdk-python-docs/ 22 | 23 | # Set it all to public 24 | s3cmd setacl -r s3://mavsdk-python-docs --acl-public 25 | -------------------------------------------------------------------------------- /requirements-dev.txt: -------------------------------------------------------------------------------- 1 | grpcio-tools>=1.40.0 2 | protoc-gen-mavsdk>=1.2.0 3 | -------------------------------------------------------------------------------- /requirements-docs.txt: -------------------------------------------------------------------------------- 1 | sphinx>=3.3.0 2 | numpydoc>=1.1.0 3 | s3cmd>=2.1.0 4 | -------------------------------------------------------------------------------- /requirements-test.txt: -------------------------------------------------------------------------------- 1 | pytest>=3.5.0 2 | -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- 1 | protobuf>=5.27.1 2 | grpcio>=1.64.1 3 | -------------------------------------------------------------------------------- /setup.cfg: -------------------------------------------------------------------------------- 1 | [metadata] 2 | license_file = LICENSE.txt 3 | 4 | [bdist_wheel] 5 | universal=0 6 | -------------------------------------------------------------------------------- /tests/.gitkeep: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/mavlink/MAVSDK-Python/483ed92234f91f647fa319ad7ccbbec02ca45a80/tests/.gitkeep -------------------------------------------------------------------------------- /tox.ini: -------------------------------------------------------------------------------- 1 | [tox] 2 | envlist = py{37, 36} 3 | 4 | [testenv] 5 | deps = 6 | -rrequirements.txt 7 | -rrequirements-test.txt 8 | commands = pytest 9 | --------------------------------------------------------------------------------