diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index a98befae..89df71a1 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -28,6 +28,12 @@ jobs: - name: Install pip run: sudo apt-get install -y python3-pip + - name: Check style + run: | + python3 -m pip install pycodestyle + export PATH=$PATH:$HOME/.local/bin + pycodestyle examples/* + - name: Install prerequisites run: | python3 -m pip install -r requirements.txt -r requirements-dev.txt -r requirements-docs.txt diff --git a/examples/all_params.py b/examples/all_params.py index 899b1bfd..353ae082 100755 --- a/examples/all_params.py +++ b/examples/all_params.py @@ -3,6 +3,7 @@ import asyncio from mavsdk import System + async def run(): # Connect to the drone drone = System() diff --git a/examples/camera_params.py b/examples/camera_params.py index 007a6420..5b3fc0e1 100755 --- a/examples/camera_params.py +++ b/examples/camera_params.py @@ -19,6 +19,7 @@ current_settings = [] possible_setting_options = [] + async def run(): drone = System() await drone.connect(system_address="udp://:14540") @@ -27,7 +28,7 @@ async def run(): asyncio.ensure_future(observe_camera_mode(drone)) asyncio.ensure_future(observe_possible_setting_options(drone)) - while(True): + while True: entered_input = await ainput(usage_str) if (entered_input == "p"): @@ -61,7 +62,8 @@ async def run(): print_possible_settings(possible_setting_options) try: - index_setting = await make_user_choose_setting(possible_setting_options) + index_setting = await \ + make_user_choose_setting(possible_setting_options) except ValueError: print("Invalid index") continue @@ -75,20 +77,32 @@ async def run(): print(f"Options:") try: print_possible_options(possible_options) - index_option = await make_user_choose_option(possible_options) + index_option = await \ + make_user_choose_option(possible_options) selected_option = possible_options[index_option - 1] - print(f"Setting {selected_setting.setting_id} to {selected_option.option_description}!") - setting = Setting(selected_setting.setting_id, "", selected_option, selected_setting.is_range) + print(f"Setting {selected_setting.setting_id} " + f"to {selected_option.option_description}!") + setting = Setting( + selected_setting.setting_id, + "", + selected_option, + selected_setting.is_range) except ValueError: print("Invalid index") continue else: try: - selected_value = await make_user_choose_option_range(possible_options) - - print(f"Setting {selected_setting.setting_id} to {selected_value}!") - setting = Setting(selected_setting.setting_id, "", Option(selected_value, ""), selected_setting.is_range) + selected_value = await \ + make_user_choose_option_range(possible_options) + + print(f"Setting {selected_setting.setting_id}" + f" to {selected_value}!") + setting = Setting( + selected_setting.setting_id, + "", + Option(selected_value, ""), + selected_setting.is_range) except ValueError: print("Invalid value") continue @@ -102,21 +116,25 @@ async def run(): print("Invalid input!") continue + async def observe_camera_mode(drone): global camera_mode async for mode in drone.camera.mode(): camera_mode = mode + async def observe_current_settings(drone): global current_settings async for settings in drone.camera.current_settings(): current_settings = settings + async def observe_possible_setting_options(drone): global possible_setting_options async for settings in drone.camera.possible_setting_options(): possible_setting_options = settings + def print_current_settings(): print(f"* CAM_MODE: {camera_mode}") for setting in current_settings: @@ -126,6 +144,7 @@ def print_current_settings(): else: print(f" -> {setting.option.option_description}") + async def make_user_choose_camera_mode(): index_mode_str = await ainput(f"\nWhich mode do you want? [1..2] >>> ") index_mode = int(index_mode_str) @@ -134,15 +153,19 @@ async def make_user_choose_camera_mode(): return index_mode + def print_possible_settings(possible_settings): i = 1 for setting in possible_settings: print(f"{i}. {setting.setting_id}: {setting.setting_description}") i += 1 + async def make_user_choose_setting(possible_settings): n_settings = len(possible_settings) - index_setting_str = await ainput(f"\nWhich setting do you want to change? [1..{n_settings}] >>> ") + index_setting_str = await \ + ainput(f"\nWhich setting do you want to change?" + f" [1..{n_settings}] >>> ") index_setting = int(index_setting_str) if (index_setting < 1 or index_setting > n_settings): @@ -150,15 +173,18 @@ async def make_user_choose_setting(possible_settings): return index_setting + def print_possible_options(possible_options): i = 1 for possible_option in possible_options: print(f"{i}. {possible_option.option_description}") i += 1 + async def make_user_choose_option(possible_options): n_options = len(possible_options) - index_option_str = await ainput(f"\nWhich option do you want? [1..{n_options}] >>> ") + index_option_str = await \ + ainput(f"\nWhich option do you want? [1..{n_options}] >>> ") index_option = int(index_option_str) if (index_option < 1 or index_option > n_options): @@ -166,6 +192,7 @@ async def make_user_choose_option(possible_options): return index_option + async def make_user_choose_option_range(possible_options): min_value = float(possible_options[0].option_id) max_value = float(possible_options[1].option_id) @@ -175,7 +202,9 @@ async def make_user_choose_option_range(possible_options): interval_value = float(possible_options[2].option_id) interval_text = f"interval: {interval_value}" - value_str = await ainput(f"\nWhat value do you want? [{min_value}, {max_value}] {interval_text} >>> ") + value_str = await \ + ainput(f"\nWhat value do you want?" + f" [{min_value}, {max_value}] {interval_text} >>> ") value = float(value_str) if (value < min_value or value > max_value): diff --git a/examples/failure_injection.py b/examples/failure_injection.py index 036f252c..2cb18a02 100755 --- a/examples/failure_injection.py +++ b/examples/failure_injection.py @@ -5,6 +5,7 @@ from mavsdk import System from mavsdk.failure import FailureType, FailureUnit + async def run(): drone = System() await drone.connect(system_address="udp://:14540") @@ -44,13 +45,14 @@ async def run(): break print("-- Flying up") - flying_alt = goto_alt + 20.0 # To fly drone 20m above the ground plane + flying_alt = goto_alt + 20.0 # To fly drone 20m above the ground plane await drone.action.goto_location(goto_lat, goto_lon, flying_alt, 0) await asyncio.sleep(5) print("-- Injecting GPS failure") - await drone.failure.inject(FailureUnit.SENSOR_GPS, FailureType.OFF, instance=0) + await drone.failure.inject( + FailureUnit.SENSOR_GPS, FailureType.OFF, instance=0) print("-- Waiting 20s before exiting script...") await asyncio.sleep(20) diff --git a/examples/follow_me_example.py b/examples/follow_me_example.py index 735ad732..3d99b0ba 100755 --- a/examples/follow_me_example.py +++ b/examples/follow_me_example.py @@ -1,20 +1,27 @@ #!/usr/bin/env python3 -#This example shows how to use the follow me plugin +# This example shows how to use the follow me plugin import asyncio from mavsdk import System from mavsdk.follow_me import (Config, FollowMeError, TargetLocation) -default_height = 8.0 #in Meters -follow_distance = 2.0 #in Meters, this is the distance that the drone will remain away from Target while following it -#Direction relative to the Target -#Options are NONE, FRONT, FRONT_LEFT, FRONT_RIGHT, BEHIND + +default_height = 8.0 # in meters +# distance between drone and target +follow_distance = 2.0 # in meters + +# Direction relative to the Target +# Options are NONE, FRONT, FRONT_LEFT, FRONT_RIGHT, BEHIND direction = Config.FollowDirection.BEHIND -responsiveness = 0.02 +responsiveness = 0.02 + +# This list contains fake location coordinates +# (These coordinates are obtained from mission.py example) +fake_location = [[47.398039859999997, 8.5455725400000002], + [47.398036222362471, 8.5450146439425509], + [47.397825620791885, 8.5450092830163271]] -#This list contains fake location coordinates (These coordinates are obtained from mission.py example) -fake_location = [[47.398039859999997,8.5455725400000002],[47.398036222362471,8.5450146439425509],[47.397825620791885,8.5450092830163271]] async def fly_drone(): drone = System() @@ -32,35 +39,37 @@ async def fly_drone(): print("-- Global position estimate OK") break - #Arming the drone - print ("-- Arming") + # Arming the drone + print("-- Arming") await drone.action.arm() - #Follow me Mode requires some configuration to be done before starting the mode + # Follow me Mode requires some configuration to be done before starting + # the mode conf = Config(default_height, follow_distance, direction, responsiveness) await drone.follow_me.set_config(conf) - print ("-- Taking Off") + print("-- Taking Off") await drone.action.takeoff() await asyncio.sleep(8) - print ("-- Starting Follow Me Mode") + print("-- Starting Follow Me Mode") await drone.follow_me.start() await asyncio.sleep(8) - #This for loop provides fake coordinates from the fake_location list for the follow me mode to work - #In a simulator it won't make much sense though - for latitude,longitude in fake_location: + # This for loop provides fake coordinates from the fake_location list for + # the follow me mode to work. + # In a simulator it won't make much sense though + for latitude, longitude in fake_location: target = TargetLocation(latitude, longitude, 0, 0, 0, 0) - print ("-- Following Target") + print("-- Following Target") await drone.follow_me.set_target_location(target) await asyncio.sleep(2) - #Stopping the follow me mode - print ("-- Stopping Follow Me Mode") + # Stopping the follow me mode + print("-- Stopping Follow Me Mode") await drone.follow_me.stop() await asyncio.sleep(5) - print ("-- Landing") + print("-- Landing") await drone.action.land() if __name__ == "__main__": diff --git a/examples/geofence.py b/examples/geofence.py index 96422fcb..4bcb8731 100755 --- a/examples/geofence.py +++ b/examples/geofence.py @@ -7,7 +7,8 @@ """ This example shows how to use the geofence plugin. -Note: The behavior when your vehicle hits the geofence is NOT configured in this example. +Note: The behavior when your vehicle hits the geofence is NOT configured +in this example. """ @@ -25,7 +26,8 @@ async def run(): print(f"-- Connected to drone!") break - # Fetch the home location coordinates, in order to set a boundary around the home location + # Fetch the home location coordinates, in order to set a boundary around + # the home location. print("Fetching home location coordinates...") async for terrain_info in drone.telemetry.home(): latitude = terrain_info.latitude_deg diff --git a/examples/gimbal.py b/examples/gimbal.py index f278dc0b..29ac0909 100755 --- a/examples/gimbal.py +++ b/examples/gimbal.py @@ -4,13 +4,15 @@ from mavsdk import System from mavsdk.gimbal import GimbalMode, ControlMode + async def run(): # Init the drone drone = System() await drone.connect(system_address="udp://:14540") # Start printing gimbal position updates - print_gimbal_position_task = asyncio.ensure_future(print_gimbal_position(drone)) + print_gimbal_position_task = \ + asyncio.ensure_future(print_gimbal_position(drone)) print("Taking control of gimbal") await drone.gimbal.take_control(ControlMode.PRIMARY) diff --git a/examples/manual_control.py b/examples/manual_control.py index a3d86766..d7220f4a 100755 --- a/examples/manual_control.py +++ b/examples/manual_control.py @@ -3,11 +3,13 @@ """ This example shows how to use the manual controls plugin. -Note: Manual inputs are taken from a test set in this example to decrease complexity. Manual inputs -can be received from devices such as a joystick using third-party python extensions +Note: Manual inputs are taken from a test set in this example to decrease +complexity. Manual inputs can be received from devices such as a joystick +using third-party python extensions. -Note: Taking off the drone is not necessary before enabling manual inputs. It is acceptable to send -positive throttle input to leave the ground. Takeoff is used in this example to decrease complexity +Note: Taking off the drone is not necessary before enabling manual inputs. +It is acceptable to send positive throttle input to leave the ground. +Takeoff is used in this example to decrease complexity """ import asyncio @@ -80,12 +82,14 @@ async def manual_controls(): roll = float(input_list[0]) # get current state of pitch axis (between -1 and 1) pitch = float(input_list[1]) - # get current state of throttle axis (between -1 and 1, but between 0 and 1 is expected) + # get current state of throttle axis + # (between -1 and 1, but between 0 and 1 is expected) throttle = float(input_list[2]) # get current state of yaw axis (between -1 and 1) yaw = float(input_list[3]) - await drone.manual_control.set_manual_control_input(roll, pitch, throttle, yaw) + await drone.manual_control.set_manual_control_input( + roll, pitch, throttle, yaw) await asyncio.sleep(0.1) diff --git a/examples/mission_import.py b/examples/mission_import.py index 225f6c6e..964c3d6e 100755 --- a/examples/mission_import.py +++ b/examples/mission_import.py @@ -16,13 +16,14 @@ async def run(): print(f"-- Connected to drone!") break - mission_import_data = await drone.mission_raw.import_qgroundcontrol_mission("example-mission.plan") + mission_import_data = await \ + drone.mission_raw.import_qgroundcontrol_mission( + "example-mission.plan") print(f"{len(mission_import_data.mission_items)} mission items imported") await drone.mission_raw.upload_mission(mission_import_data.mission_items) print("Mission uploaded") - if __name__ == "__main__": # Run the asyncio loop asyncio.run(run()) diff --git a/examples/mission_raw.py b/examples/mission_raw.py index a7c607cb..2b599560 100755 --- a/examples/mission_raw.py +++ b/examples/mission_raw.py @@ -4,6 +4,7 @@ from mavsdk import System from mavsdk import mission_raw + async def px4_connect_drone(): drone = System() await drone.connect(system_address="udp://:14540") @@ -14,19 +15,21 @@ async def px4_connect_drone(): print("-- Connected to drone!") return drone + async def run(): drone = await px4_connect_drone() await run_drone(drone) + async def run_drone(drone): mission_items = [] mission_items.append(mission_raw.MissionItem( - 0, # start seq at 0 + 0, # start seq at 0 6, 16, - 1, # first one is current + 1, # first one is current 1, 0, 10, 0, float('nan'), int(47.40271757 * 10**7), diff --git a/examples/offboard_position_ned.py b/examples/offboard_position_ned.py index eeb478f9..9e495c3e 100755 --- a/examples/offboard_position_ned.py +++ b/examples/offboard_position_ned.py @@ -42,32 +42,42 @@ async def run(): try: await drone.offboard.start() except OffboardError as error: - print(f"Starting offboard mode failed with error code: {error._result.result}") + print(f"Starting offboard mode failed \ + with error code: {error._result.result}") print("-- Disarming") await drone.action.disarm() return - print("-- Go 0m North, 0m East, -5m Down within local coordinate system") - await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, -5.0, 0.0)) + print("-- Go 0m North, 0m East, -5m Down \ + within local coordinate system") + await drone.offboard.set_position_ned( + PositionNedYaw(0.0, 0.0, -5.0, 0.0)) await asyncio.sleep(10) - print("-- Go 5m North, 0m East, -5m Down within local coordinate system, turn to face East") - await drone.offboard.set_position_ned(PositionNedYaw(5.0, 0.0, -5.0, 90.0)) + print("-- Go 5m North, 0m East, -5m Down \ + within local coordinate system, turn to face East") + await drone.offboard.set_position_ned( + PositionNedYaw(5.0, 0.0, -5.0, 90.0)) await asyncio.sleep(10) - print("-- Go 5m North, 10m East, -5m Down within local coordinate system") - await drone.offboard.set_position_ned(PositionNedYaw(5.0, 10.0, -5.0, 90.0)) + print("-- Go 5m North, 10m East, -5m Down \ + within local coordinate system") + await drone.offboard.set_position_ned( + PositionNedYaw(5.0, 10.0, -5.0, 90.0)) await asyncio.sleep(15) - print("-- Go 0m North, 10m East, 0m Down within local coordinate system, turn to face South") - await drone.offboard.set_position_ned(PositionNedYaw(0.0, 10.0, 0.0, 180.0)) + print("-- Go 0m North, 10m East, 0m Down \ + within local coordinate system, turn to face South") + await drone.offboard.set_position_ned( + PositionNedYaw(0.0, 10.0, 0.0, 180.0)) await asyncio.sleep(10) print("-- Stopping offboard") try: await drone.offboard.stop() except OffboardError as error: - print(f"Stopping offboard mode failed with error code: {error._result.result}") + print(f"Stopping offboard mode failed \ + with error code: {error._result.result}") if __name__ == "__main__": diff --git a/examples/offboard_position_velocity_ned.py b/examples/offboard_position_velocity_ned.py index f093c95e..f8f3b6ca 100755 --- a/examples/offboard_position_velocity_ned.py +++ b/examples/offboard_position_velocity_ned.py @@ -5,6 +5,7 @@ from mavsdk import System from mavsdk.offboard import (PositionNedYaw, VelocityNedYaw, OffboardError) + async def run(): drone = System() await drone.connect(system_address="udp://:14540") @@ -31,12 +32,12 @@ async def run(): try: await drone.offboard.start() except OffboardError as error: - print(f"Starting offboard mode failed with error code: {error._result.result}") + print(f"Starting offboard mode failed with \ + error code: {error._result.result}") print("-- Disarming") await drone.action.disarm() return - async def print_z_velocity(drone): async for odom in drone.telemetry.position_velocity_ned(): print(f"{odom.velocity.north_m_s} {odom.velocity.down_m_s}") @@ -44,23 +45,25 @@ async def print_z_velocity(drone): asyncio.ensure_future(print_z_velocity(drone)) print("-- Go 0m North, 0m East, -10m Down within local coordinate system") - #await drone.offboard.set_position_velocity_ned(PositionNedYaw(0.0, 0.0, -10.0, 0.0),VelocityNedYaw(0.0,0.0,-1.0,0.0)) - await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, -10.0, 0.0)) + await drone.offboard.set_position_velocity_ned( + PositionNedYaw(0.0, 0.0, -10.0, 0.0), + VelocityNedYaw(0.0, 0.0, -1.0, 0.0)) await asyncio.sleep(10) print("-- Go 10m North, 0m East, 0m Down within local coordinate system") - await drone.offboard.set_position_ned(PositionNedYaw(50.0, 0.0, -10.0, 0.0)) - #await drone.offboard.set_position_velocity_ned(PositionNedYaw(50.0, 0.0, -10.0, 0.0),VelocityNedYaw(1.0,0.0,0.0,0.0)) + await drone.offboard.set_position_velocity_ned( + PositionNedYaw(50.0, 0.0, -10.0, 0.0), + VelocityNedYaw(1.0, 0.0, 0.0, 0.0)) await asyncio.sleep(20) await drone.action.land() - print("-- Stopping offboard") try: await drone.offboard.stop() except OffboardError as error: - print(f"Stopping offboard mode failed with error code: {error._result.result}") + print(f"Stopping offboard mode failed with \ + error code: {error._result.result}") if __name__ == "__main__": diff --git a/examples/send_status_message.py b/examples/send_status_message.py index ddbca512..6a562447 100755 --- a/examples/send_status_message.py +++ b/examples/send_status_message.py @@ -25,7 +25,8 @@ async def run(): async for state in drone.core.connection_state(): if state.is_connected: print(f"-- Connected to drone!") - await drone.server_utility.send_status_text(StatusTextType.INFO, "Hello world!") + await drone.server_utility.send_status_text( + StatusTextType.INFO, "Hello world!") break if __name__ == "__main__": diff --git a/examples/shell.py b/examples/shell.py index 9a97ce9f..f9a1b35b 100755 --- a/examples/shell.py +++ b/examples/shell.py @@ -21,13 +21,16 @@ async def run(): asyncio.get_event_loop().add_reader(sys.stdin, got_stdin_data, drone) print("nsh> ", end='', flush=True) + async def observe_shell(drone): async for output in drone.shell.receive(): print(f"\n{output} ", end='', flush=True) + def got_stdin_data(drone): asyncio.ensure_future(send(drone, sys.stdin.readline())) + async def send(drone, command): await drone.shell.send(command) diff --git a/examples/takeoff_and_land.py b/examples/takeoff_and_land.py index 666897f5..2ad99aa5 100755 --- a/examples/takeoff_and_land.py +++ b/examples/takeoff_and_land.py @@ -37,7 +37,6 @@ async def run(): status_text_task.cancel() - async def print_status_text(drone): try: async for status_text in drone.telemetry.status_text(): diff --git a/examples/takeoff_and_land_keyboard_control.py b/examples/takeoff_and_land_keyboard_control.py deleted file mode 100755 index 6561222a..00000000 --- a/examples/takeoff_and_land_keyboard_control.py +++ /dev/null @@ -1,157 +0,0 @@ -#!/usr/bin/env python3 - -import asyncio -import pygame - -from mavsdk import System - -drone = System() - -pygame.init() -window = pygame.display.set_mode((300, 300)) - - -async def setup(): - """ - General configurations, setups, and connections are done here. - :return: - """ - - await drone.connect(system_address="udp://:14540") - - print("Waiting for drone to connect...") - async for state in drone.core.connection_state(): - if state.is_connected: - print(f"-- Connected to drone!") - break - - print("Waiting for drone to have a global position estimate...") - async for health in drone.telemetry.health(): - if health.is_global_position_ok and health.is_home_position_ok: - print("-- Global position estimate OK") - break - - -async def main(): - """ - Launching a specific pygame window retrieves and works according to the received commands. - :return: - """ - - running = True - - while running: - - for event in pygame.event.get(): - if event.type == pygame.QUIT: - running = False - - keys = pygame.key.get_pressed() - - # While being in air and landing mode the drone is not likely to takeoff again, so - # a condition check is required here to avoid such a condition. - - if keys[pygame.K_UP] and (await print_in_air(drone) != True): - await takeoff() - - elif keys[pygame.K_DOWN]: - await land() - - elif keys[pygame.K_RIGHT]: - await print_in_air(drone) - - elif keys[pygame.K_i]: - await info(drone) - - -async def takeoff(): - """ - Default takeoff command seperated and taken from takeoff_and_land.py - :return: - """ - - print("-- Arming") - await drone.action.arm() - - print("-- Taking off") - await drone.action.takeoff() - - -async def land(): - """ - Default land command seperated and taken from takeoff_and_land.py - :return: - """ - - await drone.action.land() - - -async def print_in_air(drone=drone): - async for in_air in drone.telemetry.in_air(): - print(f"In air: {in_air}") - return in_air - - -async def info(drone=drone): - """ - This is the combination of the print_battery, print_in_air, print_gps_info, and print_position functions aimed - to display all of the counted data/information at the same exact time. - :param drone: - :return: - """ - - await print_battery(drone) - await print_in_air(drone) - await print_gps_info(drone) - await print_position(drone) - - return True - - -async def print_battery(drone=drone): - """ - Default print_battery command seperated and taken from telemetry.py - :param drone: - :return: - """ - - async for battery in drone.telemetry.battery(): - print(f"Battery: {battery.remaining_percent}") - return battery.remaining_percent - - -async def print_gps_info(drone=drone): - """ - Default print_gps_info command seperated and taken from telemetry.py - :param drone: - :return: - """ - - async for gps_info in drone.telemetry.gps_info(): - print(f"GPS info: {gps_info}") - return gps_info - - -async def print_position(drone=drone): - """ - Default print_position command seperated and taken from telemetry.py - :param drone: - :return: - """ - - async for position in drone.telemetry.position(): - print(position) - return position - - -if __name__ == "__main__": - - # TODO: use new asyncio methods - loop = asyncio.get_event_loop() - loop.run_until_complete(setup()) - loop.run_until_complete(main()) - loop.run_until_complete(print_in_air(drone)) - loop.run_until_complete(info(drone)) - loop.run_until_complete(print_battery()) - loop.run_until_complete(print_gps_info()) - loop.run_until_complete(print_position()) diff --git a/examples/telemetry.py b/examples/telemetry.py index e85bd351..7fa831f7 100755 --- a/examples/telemetry.py +++ b/examples/telemetry.py @@ -15,6 +15,10 @@ async def run(): asyncio.ensure_future(print_in_air(drone)) asyncio.ensure_future(print_position(drone)) + while True: + await asyncio.sleep(1) + + async def print_battery(drone): async for battery in drone.telemetry.battery(): print(f"Battery: {battery.remaining_percent}") @@ -36,5 +40,5 @@ async def print_position(drone): if __name__ == "__main__": - # Run the asyncio loop + # Start the main function asyncio.run(run()) diff --git a/examples/telemetry_flight_mode.py b/examples/telemetry_flight_mode.py index 05732bab..611fff4d 100755 --- a/examples/telemetry_flight_mode.py +++ b/examples/telemetry_flight_mode.py @@ -19,5 +19,5 @@ async def print_flight_mode(): if __name__ == "__main__": - # Run the asyncio loop - asyncio.run(run()) + # Start the main function + asyncio.run(print_flight_mode()) diff --git a/examples/telemetry_is_armed_is_in_air.py b/examples/telemetry_is_armed_is_in_air.py index 283f941c..91dc2fdb 100755 --- a/examples/telemetry_is_armed_is_in_air.py +++ b/examples/telemetry_is_armed_is_in_air.py @@ -11,6 +11,9 @@ async def run(): asyncio.ensure_future(print_is_armed(drone)) asyncio.ensure_future(print_is_in_air(drone)) + while True: + await asyncio.sleep(1) + async def print_is_armed(drone): async for is_armed in drone.telemetry.armed(): @@ -23,5 +26,5 @@ async def print_is_in_air(drone): if __name__ == "__main__": - # Run the asyncio loop - asyncio.run(run()) + # Start the main function + asyncio.run(print_flight_mode()) diff --git a/examples/telemetry_takeoff_and_land.py b/examples/telemetry_takeoff_and_land.py index caf5015d..f22ee731 100755 --- a/examples/telemetry_takeoff_and_land.py +++ b/examples/telemetry_takeoff_and_land.py @@ -39,7 +39,8 @@ async def run(): print_flight_mode_task = asyncio.ensure_future(print_flight_mode(drone)) running_tasks = [print_altitude_task, print_flight_mode_task] - termination_task = asyncio.ensure_future(observe_is_in_air(drone, running_tasks)) + termination_task = asyncio.ensure_future( + observe_is_in_air(drone, running_tasks)) async for health in drone.telemetry.health(): if health.is_global_position_ok and health.is_home_position_ok: @@ -108,5 +109,5 @@ async def observe_is_in_air(drone, running_tasks): if __name__ == "__main__": - # Run the asyncio loop + # Start the main function asyncio.run(run()) diff --git a/examples/transponder.py b/examples/transponder.py old mode 100644 new mode 100755 index 1af8201b..a1d454f7 --- a/examples/transponder.py +++ b/examples/transponder.py @@ -7,17 +7,22 @@ async def run(): # Init the drone drone = System() - #await drone.connect(system_address="udp://:14540") await drone.connect() # Start the tasks asyncio.ensure_future(print_transponders(drone)) + # Runs the event loop until the program is canceled with e.g. CTRL-C + while True: + print("Waiting for transponder messages") + await asyncio.sleep(1) + + async def print_transponders(drone): async for transponder in drone.transponder.transponder(): print(transponder) if __name__ == "__main__": - # Run the asyncio loop + # Start the main function asyncio.run(run()) diff --git a/examples/tune.py b/examples/tune.py index 7dc3a984..217642b3 100755 --- a/examples/tune.py +++ b/examples/tune.py @@ -17,46 +17,46 @@ async def run(): break song_elements = [] - song_elements.append(SongElement.DURATION_4); - song_elements.append(SongElement.NOTE_G); - song_elements.append(SongElement.NOTE_A); - song_elements.append(SongElement.NOTE_B); - song_elements.append(SongElement.FLAT); - song_elements.append(SongElement.OCTAVE_UP); - song_elements.append(SongElement.DURATION_1); - song_elements.append(SongElement.NOTE_E); - song_elements.append(SongElement.FLAT); - song_elements.append(SongElement.OCTAVE_DOWN); - song_elements.append(SongElement.DURATION_4); - song_elements.append(SongElement.NOTE_PAUSE); - song_elements.append(SongElement.NOTE_F); - song_elements.append(SongElement.NOTE_G); - song_elements.append(SongElement.NOTE_A); - song_elements.append(SongElement.OCTAVE_UP); - song_elements.append(SongElement.DURATION_2); - song_elements.append(SongElement.NOTE_D); - song_elements.append(SongElement.NOTE_D); - song_elements.append(SongElement.OCTAVE_DOWN); - song_elements.append(SongElement.DURATION_4); - song_elements.append(SongElement.NOTE_PAUSE); - song_elements.append(SongElement.NOTE_E); - song_elements.append(SongElement.FLAT); - song_elements.append(SongElement.NOTE_F); - song_elements.append(SongElement.NOTE_G); - song_elements.append(SongElement.OCTAVE_UP); - song_elements.append(SongElement.DURATION_1); - song_elements.append(SongElement.NOTE_C); - song_elements.append(SongElement.OCTAVE_DOWN); - song_elements.append(SongElement.DURATION_4); - song_elements.append(SongElement.NOTE_PAUSE); - song_elements.append(SongElement.NOTE_A); - song_elements.append(SongElement.OCTAVE_UP); - song_elements.append(SongElement.NOTE_C); - song_elements.append(SongElement.OCTAVE_DOWN); - song_elements.append(SongElement.NOTE_B); - song_elements.append(SongElement.FLAT); - song_elements.append(SongElement.DURATION_2); - song_elements.append(SongElement.NOTE_G); + song_elements.append(SongElement.DURATION_4) + song_elements.append(SongElement.NOTE_G) + song_elements.append(SongElement.NOTE_A) + song_elements.append(SongElement.NOTE_B) + song_elements.append(SongElement.FLAT) + song_elements.append(SongElement.OCTAVE_UP) + song_elements.append(SongElement.DURATION_1) + song_elements.append(SongElement.NOTE_E) + song_elements.append(SongElement.FLAT) + song_elements.append(SongElement.OCTAVE_DOWN) + song_elements.append(SongElement.DURATION_4) + song_elements.append(SongElement.NOTE_PAUSE) + song_elements.append(SongElement.NOTE_F) + song_elements.append(SongElement.NOTE_G) + song_elements.append(SongElement.NOTE_A) + song_elements.append(SongElement.OCTAVE_UP) + song_elements.append(SongElement.DURATION_2) + song_elements.append(SongElement.NOTE_D) + song_elements.append(SongElement.NOTE_D) + song_elements.append(SongElement.OCTAVE_DOWN) + song_elements.append(SongElement.DURATION_4) + song_elements.append(SongElement.NOTE_PAUSE) + song_elements.append(SongElement.NOTE_E) + song_elements.append(SongElement.FLAT) + song_elements.append(SongElement.NOTE_F) + song_elements.append(SongElement.NOTE_G) + song_elements.append(SongElement.OCTAVE_UP) + song_elements.append(SongElement.DURATION_1) + song_elements.append(SongElement.NOTE_C) + song_elements.append(SongElement.OCTAVE_DOWN) + song_elements.append(SongElement.DURATION_4) + song_elements.append(SongElement.NOTE_PAUSE) + song_elements.append(SongElement.NOTE_A) + song_elements.append(SongElement.OCTAVE_UP) + song_elements.append(SongElement.NOTE_C) + song_elements.append(SongElement.OCTAVE_DOWN) + song_elements.append(SongElement.NOTE_B) + song_elements.append(SongElement.FLAT) + song_elements.append(SongElement.DURATION_2) + song_elements.append(SongElement.NOTE_G) tune_description = TuneDescription(song_elements, 200) await drone.tune.play_tune(tune_description)