diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 8e6f330b..fbfdb883 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -28,7 +28,7 @@ jobs: run: | python3 -m pip install pycodestyle export PATH=$PATH:$HOME/.local/bin - pycodestyle examples/* + pycodestyle --max-line-length=100 examples/* - name: Install prerequisites run: | diff --git a/examples/all_params.py b/examples/all_params.py index 9fd2b5fc..62aeeda0 100755 --- a/examples/all_params.py +++ b/examples/all_params.py @@ -19,5 +19,6 @@ async def run(): for param in all_params.float_params: print(f"{param.name}: {param.value}") + # Run the asyncio loop asyncio.run(run()) diff --git a/examples/calibration.py b/examples/calibration.py index 7db8c524..6b82737d 100755 --- a/examples/calibration.py +++ b/examples/calibration.py @@ -9,7 +9,6 @@ async def run(): - drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") diff --git a/examples/camera.py b/examples/camera.py index 774a6f15..a6b224b3 100755 --- a/examples/camera.py +++ b/examples/camera.py @@ -3,7 +3,7 @@ import asyncio import logging -from mavsdk.camera import (CameraError, Mode) +from mavsdk.camera import CameraError, Mode from mavsdk import System # Enable INFO level logging by default so that INFO messages are shown diff --git a/examples/camera_params.py b/examples/camera_params.py index c4e35bef..50b6ed88 100755 --- a/examples/camera_params.py +++ b/examples/camera_params.py @@ -4,7 +4,7 @@ from aioconsole import ainput from mavsdk import System -from mavsdk.camera import (CameraError, Mode, Option, Setting) +from mavsdk.camera import CameraError, Mode, Option, Setting usage_str = """ @@ -31,10 +31,10 @@ async def run(): while True: entered_input = await ainput(usage_str) - if (entered_input == "p"): + if entered_input == "p": print(f"\n=== Current settings ===\n") print_current_settings() - elif (entered_input == "m"): + elif entered_input == "m": print(f"\n=== Possible modes ===\n") print(f"1. PHOTO") print(f"2. VIDEO") @@ -45,7 +45,7 @@ async def run(): print("Invalid index") continue - if (index_mode == 1): + if index_mode == 1: chosen_mode = Mode.PHOTO else: chosen_mode = Mode.VIDEO @@ -57,13 +57,12 @@ async def run(): print(f" --> Succeeded") except CameraError as error: print(f" --> Failed with code: {error._result.result_str}") - elif (entered_input == "s"): + elif entered_input == "s": print(f"\n=== Possible settings ===\n") 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 @@ -73,36 +72,39 @@ async def run(): print(f"\n=== Available options ===") print(f"Setting: {selected_setting.setting_id}") - if (not selected_setting.is_range): + if not selected_setting.is_range: 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} " - f"to {selected_option.option_description}!") + 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) + 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) + selected_value = await make_user_choose_option_range( + possible_options + ) - print(f"Setting {selected_setting.setting_id}" - f" to {selected_value}!") + print(f"Setting {selected_setting.setting_id} to {selected_value}!") setting = Setting( - selected_setting.setting_id, - "", - Option(selected_value, ""), - selected_setting.is_range) + selected_setting.setting_id, + "", + Option(selected_value, ""), + selected_setting.is_range, + ) except ValueError: print("Invalid value") continue @@ -148,7 +150,7 @@ def print_current_settings(): 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) - if (index_mode < 1 or index_mode > 2): + if index_mode < 1 or index_mode > 2: raise ValueError() return index_mode @@ -163,12 +165,12 @@ def print_possible_settings(possible_settings): 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?" - f" [1..{n_settings}] >>> ") + index_setting_str = await ainput( + f"\nWhich setting do you want to change? [1..{n_settings}] >>> " + ) index_setting = int(index_setting_str) - if (index_setting < 1 or index_setting > n_settings): + if index_setting < 1 or index_setting > n_settings: raise ValueError() return index_setting @@ -183,11 +185,12 @@ def print_possible_options(possible_options): 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): + if index_option < 1 or index_option > n_options: raise ValueError() return index_option @@ -202,12 +205,12 @@ 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?" - f" [{min_value}, {max_value}] {interval_text} >>> ") + value_str = await ainput( + f"\nWhat value do you want? [{min_value}, {max_value}] {interval_text} >>> " + ) value = float(value_str) - if (value < min_value or value > max_value): + if value < min_value or value > max_value: raise ValueError() return str(value) diff --git a/examples/do_orbit.py b/examples/do_orbit.py index d918f894..fba44ade 100755 --- a/examples/do_orbit.py +++ b/examples/do_orbit.py @@ -20,7 +20,7 @@ async def run(): break position = await drone.telemetry.position().__aiter__().__anext__() - orbit_height = position.absolute_altitude_m+10 + orbit_height = position.absolute_altitude_m + 10 yaw_behavior = OrbitYawBehavior.HOLD_FRONT_TO_CIRCLE_CENTER print("-- Arming") @@ -30,17 +30,20 @@ async def run(): await drone.action.takeoff() await asyncio.sleep(10) - print('Do orbit at 10m height from the ground') - await drone.action.do_orbit(radius_m=10, - velocity_ms=2, - yaw_behavior=yaw_behavior, - latitude_deg=47.398036222362471, - longitude_deg=8.5450146439425509, - absolute_altitude_m=orbit_height) + print("Do orbit at 10m height from the ground") + await drone.action.do_orbit( + radius_m=10, + velocity_ms=2, + yaw_behavior=yaw_behavior, + latitude_deg=47.398036222362471, + longitude_deg=8.5450146439425509, + absolute_altitude_m=orbit_height, + ) await asyncio.sleep(60) await drone.action.return_to_launch() print("--- Landing") + if __name__ == "__main__": asyncio.run(run()) diff --git a/examples/failure_injection.py b/examples/failure_injection.py index 348b966c..8284e7c9 100755 --- a/examples/failure_injection.py +++ b/examples/failure_injection.py @@ -23,7 +23,7 @@ async def run(): break print("-- Enabling failure injection") - await drone.param.set_param_int('SYS_FAILURE_EN', 1) + await drone.param.set_param_int("SYS_FAILURE_EN", 1) print("-- Arming") await drone.action.arm() @@ -51,14 +51,14 @@ async def run(): 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) print("-- Disabling failure injection") - await drone.param.set_param_int('SYS_FAILURE_EN', 0) + await drone.param.set_param_int("SYS_FAILURE_EN", 0) + if __name__ == "__main__": # Run the asyncio loop diff --git a/examples/follow_me_example.py b/examples/follow_me_example.py index 7b9d7d43..048573a8 100755 --- a/examples/follow_me_example.py +++ b/examples/follow_me_example.py @@ -4,7 +4,7 @@ import asyncio from mavsdk import System -from mavsdk.follow_me import (Config, FollowMeError, TargetLocation) +from mavsdk.follow_me import Config, FollowMeError, TargetLocation follow_height = 8.0 # in meters @@ -18,9 +18,11 @@ # 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]] +fake_location = [ + [47.398039859999997, 8.5455725400000002], + [47.398036222362471, 8.5450146439425509], + [47.397825620791885, 8.5450092830163271], +] async def run(): @@ -45,8 +47,14 @@ async def run(): # Follow me Mode requires some configuration to be done before starting # the mode - conf = Config(follow_height, follow_distance, responsiveness, - altitude_mode, max_follow_vel, follow_angle_deg) + conf = Config( + follow_height, + follow_distance, + responsiveness, + altitude_mode, + max_follow_vel, + follow_angle_deg, + ) await drone.follow_me.set_config(conf) print("-- Taking Off") @@ -79,6 +87,7 @@ async def run(): print("-- Landing") await drone.action.land() + if __name__ == "__main__": # Run the asyncio loop asyncio.run(run()) diff --git a/examples/ftp_download_file.py b/examples/ftp_download_file.py index f20a6909..312af188 100755 --- a/examples/ftp_download_file.py +++ b/examples/ftp_download_file.py @@ -5,7 +5,6 @@ async def run(): - drone = System(mavsdk_server_address="localhost", port=50051) await drone.connect(system_address="serial:///dev/ttyACM0:57600") diff --git a/examples/ftp_list_dir.py b/examples/ftp_list_dir.py index 0c8a85a3..21fa1473 100755 --- a/examples/ftp_list_dir.py +++ b/examples/ftp_list_dir.py @@ -5,8 +5,7 @@ async def run(): - - drone = System(mavsdk_server_address='localhost', port=50051) + drone = System(mavsdk_server_address="localhost", port=50051) await drone.connect(system_address="serial:///dev/ttyACM0:57600") print("Waiting for drone to connect...") diff --git a/examples/geofence.py b/examples/geofence.py index 284815bb..557a4c77 100755 --- a/examples/geofence.py +++ b/examples/geofence.py @@ -18,7 +18,6 @@ async def run(): - # Connect to the Simulation drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") diff --git a/examples/gimbal.py b/examples/gimbal.py index a73c13e5..5680e4c3 100755 --- a/examples/gimbal.py +++ b/examples/gimbal.py @@ -42,7 +42,6 @@ async def run(): gimbals = await get_gimbals(drone) for gimbal in gimbals: - # Start printing gimbal position updates print_gimbal_position_task = asyncio.create_task( print_gimbal_attitude(gimbal.gimbal_id, drone) @@ -107,9 +106,7 @@ async def run(): # Set the gimbal to track a region of interest (lat, lon, altitude) # Units are degrees and meters MSL respectively - print( - "Look at a ROI (region of interest) with gimbal ID", - gimbal.gimbal_id) + print("Look at a ROI (region of interest) with gimbal ID", gimbal.gimbal_id) await drone.gimbal.set_roi_location( gimbal.gimbal_id, 47.39743832, 8.5463316, 488 ) @@ -133,7 +130,8 @@ async def print_gimbal_attitude(gimbal_id, drone): print( f"Gimbal ID {gimbal_id} " f"pitch: {attitude.euler_angle_forward.pitch_deg}, " - f"yaw: {attitude.euler_angle_forward.yaw_deg}") + f"yaw: {attitude.euler_angle_forward.yaw_deg}" + ) await asyncio.sleep(0.5) diff --git a/examples/highres_imu.py b/examples/highres_imu.py index 59c45dbf..dd129f6b 100644 --- a/examples/highres_imu.py +++ b/examples/highres_imu.py @@ -37,6 +37,7 @@ async def get_imu_data(): print(f"Temperature (°C): {imu.temperature_degc}") print("-----------------------------------------") + if __name__ == "__main__": loop = asyncio.get_event_loop() loop.run_until_complete(get_imu_data()) diff --git a/examples/logfile_download.py b/examples/logfile_download.py index 56935ca3..da67c013 100755 --- a/examples/logfile_download.py +++ b/examples/logfile_download.py @@ -26,7 +26,7 @@ async def download_log(drone, entry): print(f"Downloading: log {entry.id} from {entry.date} to {filename}") previous_progress = -1 async for progress in drone.log_files.download_log_file(entry, filename): - new_progress = round(progress.progress*100) + new_progress = round(progress.progress * 100) if new_progress != previous_progress: sys.stdout.write(f"\r{new_progress} %") sys.stdout.flush() diff --git a/examples/manual_control.py b/examples/manual_control.py index 2db6cc0e..4a1447c8 100755 --- a/examples/manual_control.py +++ b/examples/manual_control.py @@ -88,8 +88,7 @@ async def manual_controls(): # get current state of yaw axis (between -1 and 1) yaw = float(input_list[3]) - await drone.manual_control.set_manual_control_input( - pitch, roll, throttle, yaw) + await drone.manual_control.set_manual_control_input(pitch, roll, throttle, yaw) await asyncio.sleep(0.1) diff --git a/examples/mission.py b/examples/mission.py index 424235c3..68016340 100755 --- a/examples/mission.py +++ b/examples/mission.py @@ -4,7 +4,7 @@ import logging from mavsdk import System -from mavsdk.mission import (MissionItem, MissionPlan) +from mavsdk.mission import MissionItem, MissionPlan # Enable INFO level logging by default so that INFO messages are shown logging.basicConfig(level=logging.INFO) @@ -20,56 +20,66 @@ async def run(): print(f"-- Connected to drone!") break - print_mission_progress_task = asyncio.ensure_future( - print_mission_progress(drone)) + print_mission_progress_task = asyncio.ensure_future(print_mission_progress(drone)) running_tasks = [print_mission_progress_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)) mission_items = [] - mission_items.append(MissionItem(47.398039859999997, - 8.5455725400000002, - 25, - 10, - True, - float('nan'), - float('nan'), - MissionItem.CameraAction.NONE, - float('nan'), - float('nan'), - float('nan'), - float('nan'), - float('nan'), - MissionItem.VehicleAction.NONE)) - mission_items.append(MissionItem(47.398036222362471, - 8.5450146439425509, - 25, - 10, - True, - float('nan'), - float('nan'), - MissionItem.CameraAction.NONE, - float('nan'), - float('nan'), - float('nan'), - float('nan'), - float('nan'), - MissionItem.VehicleAction.NONE)) - mission_items.append(MissionItem(47.397825620791885, - 8.5450092830163271, - 25, - 10, - True, - float('nan'), - float('nan'), - MissionItem.CameraAction.NONE, - float('nan'), - float('nan'), - float('nan'), - float('nan'), - float('nan'), - MissionItem.VehicleAction.NONE)) + mission_items.append( + MissionItem( + 47.398039859999997, + 8.5455725400000002, + 25, + 10, + True, + float("nan"), + float("nan"), + MissionItem.CameraAction.NONE, + float("nan"), + float("nan"), + float("nan"), + float("nan"), + float("nan"), + MissionItem.VehicleAction.NONE, + ) + ) + mission_items.append( + MissionItem( + 47.398036222362471, + 8.5450146439425509, + 25, + 10, + True, + float("nan"), + float("nan"), + MissionItem.CameraAction.NONE, + float("nan"), + float("nan"), + float("nan"), + float("nan"), + float("nan"), + MissionItem.VehicleAction.NONE, + ) + ) + mission_items.append( + MissionItem( + 47.397825620791885, + 8.5450092830163271, + 25, + 10, + True, + float("nan"), + float("nan"), + MissionItem.CameraAction.NONE, + float("nan"), + float("nan"), + float("nan"), + float("nan"), + float("nan"), + MissionItem.VehicleAction.NONE, + ) + ) mission_plan = MissionPlan(mission_items) @@ -95,14 +105,12 @@ async def run(): async def print_mission_progress(drone): async for mission_progress in drone.mission.mission_progress(): - print(f"Mission progress: " - f"{mission_progress.current}/" - f"{mission_progress.total}") + print(f"Mission progress: {mission_progress.current}/{mission_progress.total}") async def observe_is_in_air(drone, running_tasks): - """ Monitors whether the drone is flying or not and - returns after landing """ + """Monitors whether the drone is flying or not and + returns after landing""" was_in_air = False diff --git a/examples/mission_import.py b/examples/mission_import.py index 9ea44578..b693ca1d 100755 --- a/examples/mission_import.py +++ b/examples/mission_import.py @@ -16,11 +16,12 @@ async def run(): print(f"-- Connected to drone!") break - out = await drone.mission_raw.import_qgroundcontrol_mission( - "example-mission.plan") + out = await drone.mission_raw.import_qgroundcontrol_mission("example-mission.plan") - print(f"{len(out.mission_items)} mission items and" - f"{len(out.rally_items)} rally items imported.") + print( + f"{len(out.mission_items)} mission items and" + f"{len(out.rally_items)} rally items imported." + ) await drone.mission_raw.upload_mission(out.mission_items) await drone.mission_raw.upload_rally_points(out.rally_items) diff --git a/examples/mission_raw.py b/examples/mission_raw.py index c0c60e22..989d5b73 100755 --- a/examples/mission_raw.py +++ b/examples/mission_raw.py @@ -24,50 +24,54 @@ async def run(): async def run_drone(drone): mission_items = [] - mission_items.append(mission_raw.MissionItem( - # start seq at 0 - 0, - # MAV_FRAME command. 3 is WGS84 + relative altitude - 3, - # command. 16 is a basic waypoint - 16, - # first one is current - 1, - # auto-continue. 1: True, 0: False - 1, - # param1 - 0, - # param2 - Acceptance radius - 10, - # param3 - 0 (pass through the waypoint normally) - 0, - # param4 - Desired yaw angle at waypoint - float('nan'), - # param5 - latitude - int(47.40271757 * 10**7), - # param6 - longitude - int(8.54285027 * 10**7), - # param7 - altitude - 30.0, - # mission_type. - 0 - )) + mission_items.append( + mission_raw.MissionItem( + # start seq at 0 + 0, + # MAV_FRAME command. 3 is WGS84 + relative altitude + 3, + # command. 16 is a basic waypoint + 16, + # first one is current + 1, + # auto-continue. 1: True, 0: False + 1, + # param1 + 0, + # param2 - Acceptance radius + 10, + # param3 - 0 (pass through the waypoint normally) + 0, + # param4 - Desired yaw angle at waypoint + float("nan"), + # param5 - latitude + int(47.40271757 * 10**7), + # param6 - longitude + int(8.54285027 * 10**7), + # param7 - altitude + 30.0, + # mission_type. + 0, + ) + ) - mission_items.append(mission_raw.MissionItem( - 1, - 3, - 16, - 0, - 1, - 0, - 10, - 0, - float('nan'), - int(47.40271757 * 10**7), - int(8.54361892 * 10**7), - 30.0, - 0 - )) + mission_items.append( + mission_raw.MissionItem( + 1, + 3, + 16, + 0, + 1, + 0, + 10, + 0, + float("nan"), + int(47.40271757 * 10**7), + int(8.54361892 * 10**7), + 30.0, + 0, + ) + ) print("-- Uploading mission") await drone.mission_raw.upload_mission(mission_items) diff --git a/examples/offboard_attitude.py b/examples/offboard_attitude.py index 49ee0674..9155a108 100755 --- a/examples/offboard_attitude.py +++ b/examples/offboard_attitude.py @@ -8,11 +8,11 @@ import asyncio from mavsdk import System -from mavsdk.offboard import (Attitude, OffboardError) +from mavsdk.offboard import Attitude, OffboardError async def run(): - """ Does Offboard control using attitude commands. """ + """Does Offboard control using attitude commands.""" drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") @@ -39,8 +39,10 @@ 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 @@ -65,8 +67,10 @@ async def run(): 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}" + ) await drone.action.land() diff --git a/examples/offboard_from_csv/offboard_from_csv.py b/examples/offboard_from_csv/offboard_from_csv.py index 83be885a..6510f3d1 100644 --- a/examples/offboard_from_csv/offboard_from_csv.py +++ b/examples/offboard_from_csv/offboard_from_csv.py @@ -76,7 +76,6 @@ If you need to input acceleration, you should build MAVSDK for yourself. """ - import asyncio import csv from mavsdk import System @@ -103,7 +102,7 @@ async def run(): 70: "Maneuvering (trajectory)", 80: "Holding at the end of the trajectory coordinate", 90: "Returning to home coordinate", - 100: "Landing" + 100: "Landing", } # Connect to the drone @@ -139,8 +138,7 @@ async def run(): try: await drone.offboard.start() except OffboardError as error: - print(f"Starting offboard mode failed with error code:" - f" {error._result.result}") + print(f"Starting offboard mode failed with error code: {error._result.result}") print("-- Disarming") await drone.action.disarm() return @@ -151,17 +149,21 @@ async def run(): with open("active.csv", newline="") as csvfile: reader = csv.DictReader(csvfile) for row in reader: - waypoints.append((float(row["t"]), - float(row["px"]), - float(row["py"]), - float(row["pz"]), - float(row["vx"]), - float(row["vy"]), - float(row["vz"]), - float(row["ax"]), - float(row["ay"]), - float(row["az"]), - int(row["mode"]))) + waypoints.append( + ( + float(row["t"]), + float(row["px"]), + float(row["py"]), + float(row["pz"]), + float(row["vx"]), + float(row["vy"]), + float(row["vz"]), + float(row["ax"]), + float(row["ay"]), + float(row["az"]), + int(row["mode"]), + ) + ) print("-- Performing trajectory") total_duration = waypoints[-1][0] @@ -180,8 +182,10 @@ async def run(): mode_code = current_waypoint[-1] if last_mode != mode_code: # Print the mode number and its description - print(" Mode number: " + f"{mode_code}, " - f"Description: {mode_descriptions[mode_code]}") + print( + " Mode number: " + f"{mode_code}, " + f"Description: {mode_descriptions[mode_code]}" + ) last_mode = mode_code # set_position_velocity_acceleration_ned is not yet available # in the default build for MAVSDK-Python Installation with pip3 @@ -189,7 +193,7 @@ async def run(): # you should build MAVSDK for yourself. await drone.offboard.set_position_velocity_ned( PositionNedYaw(*position, current_waypoint[10]), - VelocityNedYaw(*velocity, current_waypoint[10]) + VelocityNedYaw(*velocity, current_waypoint[10]), ) # await drone.offboard.set_position_velocity_acceleration_ned( # PositionNedYaw(*position, current_waypoint[10]), @@ -219,6 +223,7 @@ async def run(): print("-- Disarming") await drone.action.disarm() + if __name__ == "__main__": # Run the asyncio loop asyncio.run(run()) diff --git a/examples/offboard_position_ned.py b/examples/offboard_position_ned.py index d98b3104..8997dd8a 100755 --- a/examples/offboard_position_ned.py +++ b/examples/offboard_position_ned.py @@ -12,14 +12,14 @@ import logging from mavsdk import System -from mavsdk.offboard import (OffboardError, PositionNedYaw) +from mavsdk.offboard import OffboardError, PositionNedYaw # Enable INFO level logging by default so that INFO messages are shown logging.basicConfig(level=logging.INFO) async def run(): - """ Does Offboard control using position NED coordinates. """ + """Does Offboard control using position NED coordinates.""" drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") @@ -46,42 +46,50 @@ 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 a2eb7fff..f9a7ce8b 100755 --- a/examples/offboard_position_velocity_ned.py +++ b/examples/offboard_position_velocity_ned.py @@ -3,7 +3,7 @@ import asyncio from mavsdk import System -from mavsdk.offboard import (PositionNedYaw, VelocityNedYaw, OffboardError) +from mavsdk.offboard import PositionNedYaw, VelocityNedYaw, OffboardError async def run(): @@ -32,8 +32,10 @@ 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 @@ -46,14 +48,14 @@ async def 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)) + 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_velocity_ned( - PositionNedYaw(50.0, 0.0, -10.0, 0.0), - VelocityNedYaw(1.0, 0.0, 0.0, 0.0)) + 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() @@ -62,8 +64,10 @@ async def print_z_velocity(drone): 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_velocity_body.py b/examples/offboard_velocity_body.py index 4e154330..c3ef1ce9 100755 --- a/examples/offboard_velocity_body.py +++ b/examples/offboard_velocity_body.py @@ -4,11 +4,11 @@ import asyncio from mavsdk import System -from mavsdk.offboard import (OffboardError, VelocityBodyYawspeed) +from mavsdk.offboard import OffboardError, VelocityBodyYawspeed async def run(): - """ Does Offboard control using velocity body coordinates. """ + """Does Offboard control using velocity body coordinates.""" drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") @@ -29,60 +29,56 @@ async def run(): await drone.action.arm() print("-- Setting initial setpoint") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) print("-- Starting offboard") 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("-- Turn clock-wise and climb") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, 0.0, -1.0, 60.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, -1.0, 60.0)) await asyncio.sleep(5) print("-- Turn back anti-clockwise") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, 0.0, 0.0, -60.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, -60.0)) await asyncio.sleep(5) print("-- Wait for a bit") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) await asyncio.sleep(2) print("-- Fly a circle") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(5.0, 0.0, 0.0, 30.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(5.0, 0.0, 0.0, 30.0)) await asyncio.sleep(15) print("-- Wait for a bit") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) await asyncio.sleep(5) print("-- Fly a circle sideways") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, -5.0, 0.0, 30.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, -5.0, 0.0, 30.0)) await asyncio.sleep(15) print("-- Wait for a bit") - await drone.offboard.set_velocity_body( - VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) + await drone.offboard.set_velocity_body(VelocityBodyYawspeed(0.0, 0.0, 0.0, 0.0)) await asyncio.sleep(8) 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_velocity_ned.py b/examples/offboard_velocity_ned.py index bc729b0d..2196f976 100755 --- a/examples/offboard_velocity_ned.py +++ b/examples/offboard_velocity_ned.py @@ -4,11 +4,11 @@ import asyncio from mavsdk import System -from mavsdk.offboard import (OffboardError, VelocityNedYaw) +from mavsdk.offboard import OffboardError, VelocityNedYaw async def run(): - """ Does Offboard control using velocity NED coordinates. """ + """Does Offboard control using velocity NED coordinates.""" drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") @@ -35,8 +35,10 @@ 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 @@ -50,8 +52,7 @@ async def run(): await asyncio.sleep(4) print("-- Go South 2 m/s, turn to face West") - await drone.offboard.set_velocity_ned( - VelocityNedYaw(-2.0, 0.0, 0.0, 270.0)) + await drone.offboard.set_velocity_ned(VelocityNedYaw(-2.0, 0.0, 0.0, 270.0)) await asyncio.sleep(4) print("-- Go West 2 m/s, turn to face East") @@ -74,8 +75,10 @@ async def run(): 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/px4_ev_automation.py b/examples/px4_ev_automation.py index d1091d23..54468172 100644 --- a/examples/px4_ev_automation.py +++ b/examples/px4_ev_automation.py @@ -60,11 +60,7 @@ async def main(): print("-- Connected to drone!") break - params_preflight = [ - ("EKF2_HGT_REF", 0), - ("EKF2_EV_CTRL", 15), - ("EKF2_GPS_CTRL", 7) - ] + params_preflight = [("EKF2_HGT_REF", 0), ("EKF2_EV_CTRL", 15), ("EKF2_GPS_CTRL", 7)] await set_params(drone, params_preflight, "Setting preflight params...") # Wait for 5 seconds @@ -73,7 +69,7 @@ async def main(): params_gps_required = [ ("EKF2_HGT_REF", 1), ("EKF2_EV_CTRL", 0), - ("EKF2_GPS_CTRL", 7) + ("EKF2_GPS_CTRL", 7), ] await set_params(drone, params_gps_required, "Setting GPS params...") @@ -83,7 +79,7 @@ async def main(): params_ev_required = [ ("EKF2_HGT_REF", 3), ("EKF2_EV_CTRL", 15), - ("EKF2_GPS_CTRL", 0) + ("EKF2_GPS_CTRL", 0), ] await set_params(drone, params_ev_required, "Setting EV params...") diff --git a/examples/px4_ev_automation_keyboard.py b/examples/px4_ev_automation_keyboard.py index fbe3c77c..7d4dc827 100644 --- a/examples/px4_ev_automation_keyboard.py +++ b/examples/px4_ev_automation_keyboard.py @@ -40,11 +40,7 @@ async def main(): print("-- Connected to drone!") break - params_preflight = [ - ("EKF2_HGT_REF", 0), - ("EKF2_EV_CTRL", 15), - ("EKF2_GPS_CTRL", 7) - ] + params_preflight = [("EKF2_HGT_REF", 0), ("EKF2_EV_CTRL", 15), ("EKF2_GPS_CTRL", 7)] await set_params(drone, params_preflight, "Setting preflight params...") params_gps_required = [ @@ -73,21 +69,21 @@ async def main(): await set_params( drone, params_ev_required, - "Setting airborne (EV Required) parameters..." + "Setting airborne (EV Required) parameters...", ) break elif mode.lower() == "gps": await set_params( drone, params_gps_required, - "Setting airborne (GPS Required) parameters..." + "Setting airborne (GPS Required) parameters...", ) break elif mode.lower() == "multi-fusion": await set_params( drone, params_preflight, - "Setting airborne (Multi-fusion) parameters..." + "Setting airborne (Multi-fusion) parameters...", ) break else: diff --git a/examples/rtcm.py b/examples/rtcm.py index 01ae638e..02023391 100755 --- a/examples/rtcm.py +++ b/examples/rtcm.py @@ -12,8 +12,10 @@ async def send_data(data): await drone.rtk.send_rtcm_data(data) -if __name__ == '__main__': - 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 +if __name__ == "__main__": + 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 + ) # In MAVSDK 3.0.0 the data is expected to be base64 encoded string - base64_rtcm_data = base64.b64encode(rtcm_data).decode('utf-8') + base64_rtcm_data = base64.b64encode(rtcm_data).decode("utf-8") asyncio.run(send_data(RtcmData(base64_rtcm_data))) diff --git a/examples/rtk_base_ublox.py b/examples/rtk_base_ublox.py index 67567cb4..a2069238 100755 --- a/examples/rtk_base_ublox.py +++ b/examples/rtk_base_ublox.py @@ -32,9 +32,10 @@ def read_packet(self, dev, preamble): full_data += pkt + checksum if self.debug: - print("UBX class id {} and message id {}".format( - ord(ubx_class_id), - ord(ubx_message_id)) + print( + "UBX class id {} and message id {}".format( + ord(ubx_class_id), ord(ubx_message_id) + ) ) # The ubx message in full_data could be parsed with pyubx2.UBXReader @@ -44,7 +45,7 @@ def read_packet(self, dev, preamble): class RTCMParser: def __init__(self): self.debug = True - self.crc_init = 0x01864cfb + self.crc_init = 0x01864CFB self._init_crc_table() def _init_crc_table(self): @@ -109,7 +110,6 @@ async def print_gps_info(drone): async def send_rtcm(drone): - # Connect to a ublox RTK base station via USB. # Make sure that the baudrate matches the setting on the UBlox chip. # If you use UART instead, you should set the correct serial device. @@ -139,12 +139,12 @@ async def send_rtcm(drone): # Convert the rtcm data to a base64, # In MAVSDK v3 the rtcm data is expected # to be base64 encoded string . - base64_rtcm_data = base64.b64encode( - rtcm_correction_data).decode('utf-8') + base64_rtcm_data = base64.b64encode(rtcm_correction_data).decode( + "utf-8" + ) # Send RTCM - await drone.rtk.send_rtcm_data( - rtk.RtcmData(base64_rtcm_data)) + await drone.rtk.send_rtcm_data(rtk.RtcmData(base64_rtcm_data)) elif ord(preamble) == PREAMBLE_UBX: ubx = ubx_parser.read_packet(ublox, preamble) @@ -174,6 +174,7 @@ async def send_rtcm(drone): except Exception as e: print(f"Exception: {e}") + if __name__ == "__main__": # Start the main function asyncio.run(run()) diff --git a/examples/send_status_message.py b/examples/send_status_message.py index 7d073246..50e4e9ed 100755 --- a/examples/send_status_message.py +++ b/examples/send_status_message.py @@ -17,7 +17,6 @@ async def run(): - drone = System(sysid=1) await drone.connect(system_address="udpin://0.0.0.0:14540") @@ -26,9 +25,11 @@ async def run(): if state.is_connected: print(f"-- Connected to drone!") await drone.server_utility.send_status_text( - StatusTextType.INFO, "Hello world!") + StatusTextType.INFO, "Hello world!" + ) break + if __name__ == "__main__": # Run the asyncio loop asyncio.run(run()) diff --git a/examples/shell.py b/examples/shell.py index 296c0efd..15673bb0 100755 --- a/examples/shell.py +++ b/examples/shell.py @@ -19,12 +19,12 @@ async def run(): break asyncio.get_event_loop().add_reader(sys.stdin, got_stdin_data, drone) - print("nsh> ", end='', flush=True) + print("nsh> ", end="", flush=True) async def observe_shell(drone): async for output in drone.shell.receive(): - print(f"\n{output} ", end='', flush=True) + print(f"\n{output} ", end="", flush=True) def got_stdin_data(drone): diff --git a/examples/takeoff_and_land.py b/examples/takeoff_and_land.py index 25d4d831..712a9179 100755 --- a/examples/takeoff_and_land.py +++ b/examples/takeoff_and_land.py @@ -10,7 +10,6 @@ async def run(): - drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") diff --git a/examples/telemetry_takeoff_and_land.py b/examples/telemetry_takeoff_and_land.py index 4c9b8a0a..e68daeaf 100755 --- a/examples/telemetry_takeoff_and_land.py +++ b/examples/telemetry_takeoff_and_land.py @@ -39,8 +39,7 @@ 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: @@ -65,7 +64,7 @@ async def run(): async def print_altitude(drone): - """ Prints the altitude when it changes """ + """Prints the altitude when it changes""" previous_altitude = None @@ -77,7 +76,7 @@ async def print_altitude(drone): async def print_flight_mode(drone): - """ Prints the flight mode when it changes """ + """Prints the flight mode when it changes""" previous_flight_mode = None @@ -88,8 +87,8 @@ async def print_flight_mode(drone): async def observe_is_in_air(drone, running_tasks): - """ Monitors whether the drone is flying or not and - returns after landing """ + """Monitors whether the drone is flying or not and + returns after landing""" was_in_air = False diff --git a/examples/tune.py b/examples/tune.py index 5a7cd1b6..093dd886 100755 --- a/examples/tune.py +++ b/examples/tune.py @@ -2,11 +2,10 @@ import asyncio from mavsdk import System -from mavsdk.tune import (SongElement, TuneDescription, TuneError) +from mavsdk.tune import SongElement, TuneDescription, TuneError async def run(): - drone = System() await drone.connect(system_address="udpin://0.0.0.0:14540") @@ -63,6 +62,7 @@ async def run(): print("Tune played") + if __name__ == "__main__": # Run the asyncio loop asyncio.run(run()) diff --git a/examples/upload_params.py b/examples/upload_params.py index 9cc3bc06..eab79708 100755 --- a/examples/upload_params.py +++ b/examples/upload_params.py @@ -9,10 +9,11 @@ def main(): parser = argparse.ArgumentParser() parser.add_argument( - "connection", - help="Connection string (e.g. udpin://0.0.0.0:14540)") + "connection", help="Connection string (e.g. udpin://0.0.0.0:14540)" + ) parser.add_argument( - "param_file", help="Param file to be uploaded with .params format") + "param_file", help="Param file to be uploaded with .params format" + ) args = parser.parse_args() @@ -40,7 +41,7 @@ async def set_params(args): with open(args.param_file, "r") as param_file: print("Uploading Parameters... Please do not arm the vehicle!") - for line in tqdm(param_file, unit='lines'): + for line in tqdm(param_file, unit="lines"): if line.startswith("#"): continue diff --git a/mavsdk/__init__.py b/mavsdk/__init__.py index f5d463d7..726b17f4 100644 --- a/mavsdk/__init__.py +++ b/mavsdk/__init__.py @@ -17,6 +17,7 @@ # Try to import uvloop, provides _MUCH_ better performance compared to the # standart unix selector event loop import uvloop + asyncio.set_event_loop_policy(uvloop.EventLoopPolicy()) except ImportError: # No uvloop installed on the system; the default eventloop works as well! diff --git a/mavsdk/action.py b/mavsdk/action.py index 7d493ee4..bd5548d3 100644 --- a/mavsdk/action.py +++ b/mavsdk/action.py @@ -8,28 +8,27 @@ class OrbitYawBehavior(Enum): """ - Yaw behaviour during orbit flight. + Yaw behaviour during orbit flight. - Values - ------ - HOLD_FRONT_TO_CIRCLE_CENTER - Vehicle front points to the center (default) + Values + ------ + HOLD_FRONT_TO_CIRCLE_CENTER + Vehicle front points to the center (default) - HOLD_INITIAL_HEADING - Vehicle front holds heading when message received + HOLD_INITIAL_HEADING + Vehicle front holds heading when message received - UNCONTROLLED - Yaw uncontrolled + UNCONTROLLED + Yaw uncontrolled - HOLD_FRONT_TANGENT_TO_CIRCLE - Vehicle front follows flight path (tangential to circle) + HOLD_FRONT_TANGENT_TO_CIRCLE + Vehicle front follows flight path (tangential to circle) - RC_CONTROLLED - Yaw controlled by RC input + RC_CONTROLLED + Yaw controlled by RC input - """ + """ - HOLD_FRONT_TO_CIRCLE_CENTER = 0 HOLD_INITIAL_HEADING = 1 UNCONTROLLED = 2 @@ -50,7 +49,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == action_pb2.ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TO_CIRCLE_CENTER: return OrbitYawBehavior.HOLD_FRONT_TO_CIRCLE_CENTER if rpc_enum_value == action_pb2.ORBIT_YAW_BEHAVIOR_HOLD_INITIAL_HEADING: @@ -68,74 +67,71 @@ def __str__(self): class ActionResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request was successful + SUCCESS + Request was successful - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - COMMAND_DENIED_LANDED_STATE_UNKNOWN - Command refused because landed state is unknown + COMMAND_DENIED_LANDED_STATE_UNKNOWN + Command refused because landed state is unknown - COMMAND_DENIED_NOT_LANDED - Command refused because vehicle not landed + COMMAND_DENIED_NOT_LANDED + Command refused because vehicle not landed - TIMEOUT - Request timed out + TIMEOUT + Request timed out - VTOL_TRANSITION_SUPPORT_UNKNOWN - Hybrid/VTOL transition support is unknown + VTOL_TRANSITION_SUPPORT_UNKNOWN + Hybrid/VTOL transition support is unknown - NO_VTOL_TRANSITION_SUPPORT - Vehicle does not support hybrid/VTOL transitions + NO_VTOL_TRANSITION_SUPPORT + Vehicle does not support hybrid/VTOL transitions - PARAMETER_ERROR - Error getting or setting parameter + PARAMETER_ERROR + Error getting or setting parameter - UNSUPPORTED - Action not supported + UNSUPPORTED + Action not supported - FAILED - Action failed + FAILED + Action failed - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -166,7 +162,9 @@ def translate_to_rpc(self): if self == ActionResult.Result.COMMAND_DENIED: return action_pb2.ActionResult.RESULT_COMMAND_DENIED if self == ActionResult.Result.COMMAND_DENIED_LANDED_STATE_UNKNOWN: - return action_pb2.ActionResult.RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN + return ( + action_pb2.ActionResult.RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN + ) if self == ActionResult.Result.COMMAND_DENIED_NOT_LANDED: return action_pb2.ActionResult.RESULT_COMMAND_DENIED_NOT_LANDED if self == ActionResult.Result.TIMEOUT: @@ -186,7 +184,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == action_pb2.ActionResult.RESULT_UNKNOWN: return ActionResult.Result.UNKNOWN if rpc_enum_value == action_pb2.ActionResult.RESULT_SUCCESS: @@ -199,15 +197,27 @@ def translate_from_rpc(rpc_enum_value): return ActionResult.Result.BUSY if rpc_enum_value == action_pb2.ActionResult.RESULT_COMMAND_DENIED: return ActionResult.Result.COMMAND_DENIED - if rpc_enum_value == action_pb2.ActionResult.RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN: + if ( + rpc_enum_value + == action_pb2.ActionResult.RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN + ): return ActionResult.Result.COMMAND_DENIED_LANDED_STATE_UNKNOWN - if rpc_enum_value == action_pb2.ActionResult.RESULT_COMMAND_DENIED_NOT_LANDED: + if ( + rpc_enum_value + == action_pb2.ActionResult.RESULT_COMMAND_DENIED_NOT_LANDED + ): return ActionResult.Result.COMMAND_DENIED_NOT_LANDED if rpc_enum_value == action_pb2.ActionResult.RESULT_TIMEOUT: return ActionResult.Result.TIMEOUT - if rpc_enum_value == action_pb2.ActionResult.RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN: + if ( + rpc_enum_value + == action_pb2.ActionResult.RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN + ): return ActionResult.Result.VTOL_TRANSITION_SUPPORT_UNKNOWN - if rpc_enum_value == action_pb2.ActionResult.RESULT_NO_VTOL_TRANSITION_SUPPORT: + if ( + rpc_enum_value + == action_pb2.ActionResult.RESULT_NO_VTOL_TRANSITION_SUPPORT + ): return ActionResult.Result.NO_VTOL_TRANSITION_SUPPORT if rpc_enum_value == action_pb2.ActionResult.RESULT_PARAMETER_ERROR: return ActionResult.Result.PARAMETER_ERROR @@ -220,69 +230,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ActionResult object """ + def __init__(self, result, result_str): + """Initializes the ActionResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ActionResult are the same """ + """Checks if two ActionResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActionResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ActionResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ActionResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ActionResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActionResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActionResult( - - ActionResult.Result.translate_from_rpc(rpcActionResult.result), - - - rpcActionResult.result_str - ) + ActionResult.Result.translate_from_rpc(rpcActionResult.result), + rpcActionResult.result_str, + ) def translate_to_rpc(self, rpcActionResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcActionResult.result = self.result.translate_to_rpc() - - - - - - rpcActionResult.result_str = self.result_str - - - + rpcActionResult.result_str = self.result_str class ActionError(Exception): - """ Raised when a ActionResult is a fail code """ + """Raised when a ActionResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -295,284 +286,264 @@ def __str__(self): class Action(AsyncBase): """ - Enable simple actions such as arming, taking off, and landing. + Enable simple actions such as arming, taking off, and landing. - Generated by dcsdkgen - MAVSDK Action API + Generated by dcsdkgen - MAVSDK Action API """ # Plugin name name = "Action" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = action_pb2_grpc.ActionServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ActionResult.translate_from_rpc(response.action_result) - async def arm(self): """ - Send command to arm the drone. + Send command to arm the drone. - Arming a drone normally causes motors to spin at idle. - Before arming take all safety precautions and stand clear of the drone! + Arming a drone normally causes motors to spin at idle. + Before arming take all safety precautions and stand clear of the drone! - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.ArmRequest() response = await self._stub.Arm(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "arm()") - async def arm_force(self): """ - Send command to force-arm the drone without any checks. + Send command to force-arm the drone without any checks. - Attention: this is not to be used for normal flying but only bench tests! + Attention: this is not to be used for normal flying but only bench tests! - Arming a drone normally causes motors to spin at idle. - Before arming take all safety precautions and stand clear of the drone! + Arming a drone normally causes motors to spin at idle. + Before arming take all safety precautions and stand clear of the drone! - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.ArmForceRequest() response = await self._stub.ArmForce(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "arm_force()") - async def disarm(self): """ - Send command to disarm the drone. + Send command to disarm the drone. - This will disarm a drone that considers itself landed. If flying, the drone should - reject the disarm command. Disarming means that all motors will stop. + This will disarm a drone that considers itself landed. If flying, the drone should + reject the disarm command. Disarming means that all motors will stop. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.DisarmRequest() response = await self._stub.Disarm(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "disarm()") - async def takeoff(self): """ - Send command to take off and hover. + Send command to take off and hover. - This switches the drone into position control mode and commands - it to take off and hover at the takeoff altitude. + This switches the drone into position control mode and commands + it to take off and hover at the takeoff altitude. - Note that the vehicle must be armed before it can take off. + Note that the vehicle must be armed before it can take off. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.TakeoffRequest() response = await self._stub.Takeoff(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "takeoff()") - async def land(self): """ - Send command to land at the current position. + Send command to land at the current position. - This switches the drone to 'Land' flight mode. + This switches the drone to 'Land' flight mode. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.LandRequest() response = await self._stub.Land(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "land()") - async def reboot(self): """ - Send command to reboot the drone components. + Send command to reboot the drone components. - This will reboot the autopilot, companion computer, camera and gimbal. + This will reboot the autopilot, companion computer, camera and gimbal. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.RebootRequest() response = await self._stub.Reboot(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "reboot()") - async def shutdown(self): """ - Send command to shut down the drone components. + Send command to shut down the drone components. - This will shut down the autopilot, onboard computer, camera and gimbal. - This command should only be used when the autopilot is disarmed and autopilots commonly - reject it if they are not already ready to shut down. + This will shut down the autopilot, onboard computer, camera and gimbal. + This command should only be used when the autopilot is disarmed and autopilots commonly + reject it if they are not already ready to shut down. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.ShutdownRequest() response = await self._stub.Shutdown(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "shutdown()") - async def terminate(self): """ - Send command to terminate the drone. + Send command to terminate the drone. - This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute). + This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute). - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.TerminateRequest() response = await self._stub.Terminate(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "terminate()") - async def kill(self): """ - Send command to kill the drone. + Send command to kill the drone. - This will disarm a drone irrespective of whether it is landed or flying. - Note that the drone will fall out of the sky if this command is used while flying. + This will disarm a drone irrespective of whether it is landed or flying. + Note that the drone will fall out of the sky if this command is used while flying. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.KillRequest() response = await self._stub.Kill(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "kill()") - async def return_to_launch(self): """ - Send command to return to the launch (takeoff) position and land. + Send command to return to the launch (takeoff) position and land. - This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) which - generally means it will rise up to a certain altitude to clear any obstacles before heading - back to the launch (takeoff) position and land there. + This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) which + generally means it will rise up to a certain altitude to clear any obstacles before heading + back to the launch (takeoff) position and land there. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.ReturnToLaunchRequest() response = await self._stub.ReturnToLaunch(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "return_to_launch()") - - async def goto_location(self, latitude_deg, longitude_deg, absolute_altitude_m, yaw_deg): + async def goto_location( + self, latitude_deg, longitude_deg, absolute_altitude_m, yaw_deg + ): """ - Send command to move the vehicle to a specific global position. + Send command to move the vehicle to a specific global position. - The latitude and longitude are given in degrees (WGS84 frame) and the altitude - in meters AMSL (above mean sea level). + The latitude and longitude are given in degrees (WGS84 frame) and the altitude + in meters AMSL (above mean sea level). - The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise). + The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise). - Parameters - ---------- - latitude_deg : double - Latitude (in degrees) + Parameters + ---------- + latitude_deg : double + Latitude (in degrees) - longitude_deg : double - Longitude (in degrees) + longitude_deg : double + Longitude (in degrees) - absolute_altitude_m : float - Altitude AMSL (in meters) + absolute_altitude_m : float + Altitude AMSL (in meters) - yaw_deg : float - Yaw angle (in degrees, frame is NED, 0 is North, positive is clockwise) + yaw_deg : float + Yaw angle (in degrees, frame is NED, 0 is North, positive is clockwise) - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.GotoLocationRequest() @@ -582,108 +553,125 @@ async def goto_location(self, latitude_deg, longitude_deg, absolute_altitude_m, request.yaw_deg = yaw_deg response = await self._stub.GotoLocation(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: - raise ActionError(result, "goto_location()", latitude_deg, longitude_deg, absolute_altitude_m, yaw_deg) - + raise ActionError( + result, + "goto_location()", + latitude_deg, + longitude_deg, + absolute_altitude_m, + yaw_deg, + ) - async def do_orbit(self, radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m): + async def do_orbit( + self, + radius_m, + velocity_ms, + yaw_behavior, + latitude_deg, + longitude_deg, + absolute_altitude_m, + ): """ - Send command do orbit to the drone. + Send command do orbit to the drone. - This will run the orbit routine with the given parameters. + This will run the orbit routine with the given parameters. - Parameters - ---------- - radius_m : float - Radius of circle (in meters) + Parameters + ---------- + radius_m : float + Radius of circle (in meters) - velocity_ms : float - Tangential velocity (in m/s) + velocity_ms : float + Tangential velocity (in m/s) - yaw_behavior : OrbitYawBehavior - Yaw behavior of vehicle (ORBIT_YAW_BEHAVIOUR) + yaw_behavior : OrbitYawBehavior + Yaw behavior of vehicle (ORBIT_YAW_BEHAVIOUR) - latitude_deg : double - Center point latitude in degrees. NAN: use current latitude for center + latitude_deg : double + Center point latitude in degrees. NAN: use current latitude for center - longitude_deg : double - Center point longitude in degrees. NAN: use current longitude for center + longitude_deg : double + Center point longitude in degrees. NAN: use current longitude for center - absolute_altitude_m : double - Center point altitude in meters. NAN: use current altitude for center + absolute_altitude_m : double + Center point altitude in meters. NAN: use current altitude for center - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.DoOrbitRequest() request.radius_m = radius_m request.velocity_ms = velocity_ms - + request.yaw_behavior = yaw_behavior.translate_to_rpc() - - + request.latitude_deg = latitude_deg request.longitude_deg = longitude_deg request.absolute_altitude_m = absolute_altitude_m response = await self._stub.DoOrbit(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: - raise ActionError(result, "do_orbit()", radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m) - + raise ActionError( + result, + "do_orbit()", + radius_m, + velocity_ms, + yaw_behavior, + latitude_deg, + longitude_deg, + absolute_altitude_m, + ) async def hold(self): """ - Send command to hold position (a.k.a. "Loiter"). + Send command to hold position (a.k.a. "Loiter"). - Sends a command to drone to change to Hold flight mode, causing the - vehicle to stop and maintain its current GPS position and altitude. + Sends a command to drone to change to Hold flight mode, causing the + vehicle to stop and maintain its current GPS position and altitude. - Note: this command is specific to the PX4 Autopilot flight stack as - it implies a change to a PX4-specific mode. + Note: this command is specific to the PX4 Autopilot flight stack as + it implies a change to a PX4-specific mode. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.HoldRequest() response = await self._stub.Hold(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "hold()") - async def set_actuator(self, index, value): """ - Send command to set the value of an actuator. + Send command to set the value of an actuator. - Note that the index of the actuator starts at 1 and that the value goes from -1 to 1. + Note that the index of the actuator starts at 1 and that the value goes from -1 to 1. - Parameters - ---------- - index : int32_t - Index of actuator (starting with 1) + Parameters + ---------- + index : int32_t + Index of actuator (starting with 1) - value : float - Value to set the actuator to (normalized from [-1..1]) + value : float + Value to set the actuator to (normalized from [-1..1]) - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.SetActuatorRequest() @@ -691,194 +679,178 @@ async def set_actuator(self, index, value): request.value = value response = await self._stub.SetActuator(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_actuator()", index, value) - async def transition_to_fixedwing(self): """ - Send command to transition the drone to fixedwing. + Send command to transition the drone to fixedwing. - The associated action will only be executed for VTOL vehicles (on other vehicle types the - command will fail). The command will succeed if called when the vehicle - is already in fixedwing mode. + The associated action will only be executed for VTOL vehicles (on other vehicle types the + command will fail). The command will succeed if called when the vehicle + is already in fixedwing mode. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.TransitionToFixedwingRequest() response = await self._stub.TransitionToFixedwing(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "transition_to_fixedwing()") - async def transition_to_multicopter(self): """ - Send command to transition the drone to multicopter. + Send command to transition the drone to multicopter. - The associated action will only be executed for VTOL vehicles (on other vehicle types the - command will fail). The command will succeed if called when the vehicle - is already in multicopter mode. + The associated action will only be executed for VTOL vehicles (on other vehicle types the + command will fail). The command will succeed if called when the vehicle + is already in multicopter mode. - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.TransitionToMulticopterRequest() response = await self._stub.TransitionToMulticopter(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "transition_to_multicopter()") - async def get_takeoff_altitude(self): """ - Get the takeoff altitude (in meters above ground). + Get the takeoff altitude (in meters above ground). - Returns - ------- - altitude : float - Takeoff altitude relative to ground/takeoff location (in meters) + Returns + ------- + altitude : float + Takeoff altitude relative to ground/takeoff location (in meters) - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.GetTakeoffAltitudeRequest() response = await self._stub.GetTakeoffAltitude(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "get_takeoff_altitude()") - return response.altitude - async def set_takeoff_altitude(self, altitude): """ - Set takeoff altitude (in meters above ground). + Set takeoff altitude (in meters above ground). - Parameters - ---------- - altitude : float - Takeoff altitude relative to ground/takeoff location (in meters) + Parameters + ---------- + altitude : float + Takeoff altitude relative to ground/takeoff location (in meters) - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.SetTakeoffAltitudeRequest() request.altitude = altitude response = await self._stub.SetTakeoffAltitude(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_takeoff_altitude()", altitude) - async def get_return_to_launch_altitude(self): """ - Get the return to launch minimum return altitude (in meters). + Get the return to launch minimum return altitude (in meters). - Returns - ------- - relative_altitude_m : float - Return altitude relative to takeoff location (in meters) + Returns + ------- + relative_altitude_m : float + Return altitude relative to takeoff location (in meters) - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.GetReturnToLaunchAltitudeRequest() response = await self._stub.GetReturnToLaunchAltitude(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "get_return_to_launch_altitude()") - return response.relative_altitude_m - async def set_return_to_launch_altitude(self, relative_altitude_m): """ - Set the return to launch minimum return altitude (in meters). + Set the return to launch minimum return altitude (in meters). - Parameters - ---------- - relative_altitude_m : float - Return altitude relative to takeoff location (in meters) + Parameters + ---------- + relative_altitude_m : float + Return altitude relative to takeoff location (in meters) - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.SetReturnToLaunchAltitudeRequest() request.relative_altitude_m = relative_altitude_m response = await self._stub.SetReturnToLaunchAltitude(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: - raise ActionError(result, "set_return_to_launch_altitude()", relative_altitude_m) - + raise ActionError( + result, "set_return_to_launch_altitude()", relative_altitude_m + ) async def set_current_speed(self, speed_m_s): """ - Set current speed. + Set current speed. - This will set the speed during a mission, reposition, and similar. - It is ephemeral, so not stored on the drone and does not survive a reboot. + This will set the speed during a mission, reposition, and similar. + It is ephemeral, so not stored on the drone and does not survive a reboot. - Parameters - ---------- - speed_m_s : float - Speed in meters/second + Parameters + ---------- + speed_m_s : float + Speed in meters/second - Raises - ------ - ActionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionError + If the request fails. The error contains the reason for the failure. """ request = action_pb2.SetCurrentSpeedRequest() request.speed_m_s = speed_m_s response = await self._stub.SetCurrentSpeed(request) - result = self._extract_result(response) if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_current_speed()", speed_m_s) - \ No newline at end of file diff --git a/mavsdk/action_pb2.py b/mavsdk/action_pb2.py index d8ca2e70..c694529b 100644 --- a/mavsdk/action_pb2.py +++ b/mavsdk/action_pb2.py @@ -4,18 +4,15 @@ # source: action/action.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'action/action.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "action/action.proto" ) # @@protoc_insertion_point(imports) @@ -25,110 +22,122 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13\x61\x63tion/action.proto\x12\x11mavsdk.rpc.action\x1a\x14mavsdk_options.proto\"\x0c\n\nArmRequest\"E\n\x0b\x41rmResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x11\n\x0f\x41rmForceRequest\"J\n\x10\x41rmForceResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x0f\n\rDisarmRequest\"H\n\x0e\x44isarmResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x10\n\x0eTakeoffRequest\"I\n\x0fTakeoffResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\r\n\x0bLandRequest\"F\n\x0cLandResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x0f\n\rRebootRequest\"H\n\x0eRebootResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x11\n\x0fShutdownRequest\"J\n\x10ShutdownResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x12\n\x10TerminateRequest\"K\n\x11TerminateResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\r\n\x0bKillRequest\"F\n\x0cKillResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x17\n\x15ReturnToLaunchRequest\"P\n\x16ReturnToLaunchResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"p\n\x13GotoLocationRequest\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\"N\n\x14GotoLocationResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\xd7\x01\n\x0e\x44oOrbitRequest\x12\x10\n\x08radius_m\x18\x01 \x01(\x02\x12\x13\n\x0bvelocity_ms\x18\x02 \x01(\x02\x12\x39\n\x0cyaw_behavior\x18\x03 \x01(\x0e\x32#.mavsdk.rpc.action.OrbitYawBehavior\x12\x1d\n\x0clatitude_deg\x18\x05 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x06 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x07 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\"I\n\x0f\x44oOrbitResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\r\n\x0bHoldRequest\"F\n\x0cHoldResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"2\n\x12SetActuatorRequest\x12\r\n\x05index\x18\x01 \x01(\x05\x12\r\n\x05value\x18\x02 \x01(\x02\"M\n\x13SetActuatorResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x1e\n\x1cTransitionToFixedwingRequest\"W\n\x1dTransitionToFixedwingResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\" \n\x1eTransitionToMulticopterRequest\"Y\n\x1fTransitionToMulticopterResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x1b\n\x19GetTakeoffAltitudeRequest\"f\n\x1aGetTakeoffAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\x12\x10\n\x08\x61ltitude\x18\x02 \x01(\x02\"-\n\x19SetTakeoffAltitudeRequest\x12\x10\n\x08\x61ltitude\x18\x01 \x01(\x02\"T\n\x1aSetTakeoffAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\"\n GetReturnToLaunchAltitudeRequest\"x\n!GetReturnToLaunchAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\x12\x1b\n\x13relative_altitude_m\x18\x02 \x01(\x02\"?\n SetReturnToLaunchAltitudeRequest\x12\x1b\n\x13relative_altitude_m\x18\x01 \x01(\x02\"[\n!SetReturnToLaunchAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"+\n\x16SetCurrentSpeedRequest\x12\x11\n\tspeed_m_s\x18\x01 \x01(\x02\"Q\n\x17SetCurrentSpeedResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\"\x8d\x04\n\x0c\x41\x63tionResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.action.ActionResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xb0\x03\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.\n*RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN\x10\x06\x12$\n RESULT_COMMAND_DENIED_NOT_LANDED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12*\n&RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN\x10\t\x12%\n!RESULT_NO_VTOL_TRANSITION_SUPPORT\x10\n\x12\x1a\n\x16RESULT_PARAMETER_ERROR\x10\x0b\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x0c\x12\x11\n\rRESULT_FAILED\x10\r\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x0e*\xf3\x01\n\x10OrbitYawBehavior\x12\x32\n.ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TO_CIRCLE_CENTER\x10\x00\x12+\n\'ORBIT_YAW_BEHAVIOR_HOLD_INITIAL_HEADING\x10\x01\x12#\n\x1fORBIT_YAW_BEHAVIOR_UNCONTROLLED\x10\x02\x12\x33\n/ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TANGENT_TO_CIRCLE\x10\x03\x12$\n ORBIT_YAW_BEHAVIOR_RC_CONTROLLED\x10\x04\x32\xa5\x10\n\rActionService\x12\x46\n\x03\x41rm\x12\x1d.mavsdk.rpc.action.ArmRequest\x1a\x1e.mavsdk.rpc.action.ArmResponse\"\x00\x12U\n\x08\x41rmForce\x12\".mavsdk.rpc.action.ArmForceRequest\x1a#.mavsdk.rpc.action.ArmForceResponse\"\x00\x12O\n\x06\x44isarm\x12 .mavsdk.rpc.action.DisarmRequest\x1a!.mavsdk.rpc.action.DisarmResponse\"\x00\x12R\n\x07Takeoff\x12!.mavsdk.rpc.action.TakeoffRequest\x1a\".mavsdk.rpc.action.TakeoffResponse\"\x00\x12I\n\x04Land\x12\x1e.mavsdk.rpc.action.LandRequest\x1a\x1f.mavsdk.rpc.action.LandResponse\"\x00\x12O\n\x06Reboot\x12 .mavsdk.rpc.action.RebootRequest\x1a!.mavsdk.rpc.action.RebootResponse\"\x00\x12U\n\x08Shutdown\x12\".mavsdk.rpc.action.ShutdownRequest\x1a#.mavsdk.rpc.action.ShutdownResponse\"\x00\x12X\n\tTerminate\x12#.mavsdk.rpc.action.TerminateRequest\x1a$.mavsdk.rpc.action.TerminateResponse\"\x00\x12I\n\x04Kill\x12\x1e.mavsdk.rpc.action.KillRequest\x1a\x1f.mavsdk.rpc.action.KillResponse\"\x00\x12g\n\x0eReturnToLaunch\x12(.mavsdk.rpc.action.ReturnToLaunchRequest\x1a).mavsdk.rpc.action.ReturnToLaunchResponse\"\x00\x12\x61\n\x0cGotoLocation\x12&.mavsdk.rpc.action.GotoLocationRequest\x1a\'.mavsdk.rpc.action.GotoLocationResponse\"\x00\x12R\n\x07\x44oOrbit\x12!.mavsdk.rpc.action.DoOrbitRequest\x1a\".mavsdk.rpc.action.DoOrbitResponse\"\x00\x12I\n\x04Hold\x12\x1e.mavsdk.rpc.action.HoldRequest\x1a\x1f.mavsdk.rpc.action.HoldResponse\"\x00\x12^\n\x0bSetActuator\x12%.mavsdk.rpc.action.SetActuatorRequest\x1a&.mavsdk.rpc.action.SetActuatorResponse\"\x00\x12|\n\x15TransitionToFixedwing\x12/.mavsdk.rpc.action.TransitionToFixedwingRequest\x1a\x30.mavsdk.rpc.action.TransitionToFixedwingResponse\"\x00\x12\x82\x01\n\x17TransitionToMulticopter\x12\x31.mavsdk.rpc.action.TransitionToMulticopterRequest\x1a\x32.mavsdk.rpc.action.TransitionToMulticopterResponse\"\x00\x12s\n\x12GetTakeoffAltitude\x12,.mavsdk.rpc.action.GetTakeoffAltitudeRequest\x1a-.mavsdk.rpc.action.GetTakeoffAltitudeResponse\"\x00\x12s\n\x12SetTakeoffAltitude\x12,.mavsdk.rpc.action.SetTakeoffAltitudeRequest\x1a-.mavsdk.rpc.action.SetTakeoffAltitudeResponse\"\x00\x12\x88\x01\n\x19GetReturnToLaunchAltitude\x12\x33.mavsdk.rpc.action.GetReturnToLaunchAltitudeRequest\x1a\x34.mavsdk.rpc.action.GetReturnToLaunchAltitudeResponse\"\x00\x12\x88\x01\n\x19SetReturnToLaunchAltitude\x12\x33.mavsdk.rpc.action.SetReturnToLaunchAltitudeRequest\x1a\x34.mavsdk.rpc.action.SetReturnToLaunchAltitudeResponse\"\x00\x12j\n\x0fSetCurrentSpeed\x12).mavsdk.rpc.action.SetCurrentSpeedRequest\x1a*.mavsdk.rpc.action.SetCurrentSpeedResponse\"\x00\x42\x1f\n\x10io.mavsdk.actionB\x0b\x41\x63tionProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x13\x61\x63tion/action.proto\x12\x11mavsdk.rpc.action\x1a\x14mavsdk_options.proto"\x0c\n\nArmRequest"E\n\x0b\x41rmResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x11\n\x0f\x41rmForceRequest"J\n\x10\x41rmForceResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x0f\n\rDisarmRequest"H\n\x0e\x44isarmResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x10\n\x0eTakeoffRequest"I\n\x0fTakeoffResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\r\n\x0bLandRequest"F\n\x0cLandResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x0f\n\rRebootRequest"H\n\x0eRebootResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x11\n\x0fShutdownRequest"J\n\x10ShutdownResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x12\n\x10TerminateRequest"K\n\x11TerminateResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\r\n\x0bKillRequest"F\n\x0cKillResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x17\n\x15ReturnToLaunchRequest"P\n\x16ReturnToLaunchResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"p\n\x13GotoLocationRequest\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02"N\n\x14GotoLocationResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\xd7\x01\n\x0e\x44oOrbitRequest\x12\x10\n\x08radius_m\x18\x01 \x01(\x02\x12\x13\n\x0bvelocity_ms\x18\x02 \x01(\x02\x12\x39\n\x0cyaw_behavior\x18\x03 \x01(\x0e\x32#.mavsdk.rpc.action.OrbitYawBehavior\x12\x1d\n\x0clatitude_deg\x18\x05 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x06 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x07 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN"I\n\x0f\x44oOrbitResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\r\n\x0bHoldRequest"F\n\x0cHoldResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"2\n\x12SetActuatorRequest\x12\r\n\x05index\x18\x01 \x01(\x05\x12\r\n\x05value\x18\x02 \x01(\x02"M\n\x13SetActuatorResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x1e\n\x1cTransitionToFixedwingRequest"W\n\x1dTransitionToFixedwingResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult" \n\x1eTransitionToMulticopterRequest"Y\n\x1fTransitionToMulticopterResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x1b\n\x19GetTakeoffAltitudeRequest"f\n\x1aGetTakeoffAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\x12\x10\n\x08\x61ltitude\x18\x02 \x01(\x02"-\n\x19SetTakeoffAltitudeRequest\x12\x10\n\x08\x61ltitude\x18\x01 \x01(\x02"T\n\x1aSetTakeoffAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult""\n GetReturnToLaunchAltitudeRequest"x\n!GetReturnToLaunchAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult\x12\x1b\n\x13relative_altitude_m\x18\x02 \x01(\x02"?\n SetReturnToLaunchAltitudeRequest\x12\x1b\n\x13relative_altitude_m\x18\x01 \x01(\x02"[\n!SetReturnToLaunchAltitudeResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"+\n\x16SetCurrentSpeedRequest\x12\x11\n\tspeed_m_s\x18\x01 \x01(\x02"Q\n\x17SetCurrentSpeedResponse\x12\x36\n\raction_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.action.ActionResult"\x8d\x04\n\x0c\x41\x63tionResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.action.ActionResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xb0\x03\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.\n*RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN\x10\x06\x12$\n RESULT_COMMAND_DENIED_NOT_LANDED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12*\n&RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN\x10\t\x12%\n!RESULT_NO_VTOL_TRANSITION_SUPPORT\x10\n\x12\x1a\n\x16RESULT_PARAMETER_ERROR\x10\x0b\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x0c\x12\x11\n\rRESULT_FAILED\x10\r\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x0e*\xf3\x01\n\x10OrbitYawBehavior\x12\x32\n.ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TO_CIRCLE_CENTER\x10\x00\x12+\n\'ORBIT_YAW_BEHAVIOR_HOLD_INITIAL_HEADING\x10\x01\x12#\n\x1fORBIT_YAW_BEHAVIOR_UNCONTROLLED\x10\x02\x12\x33\n/ORBIT_YAW_BEHAVIOR_HOLD_FRONT_TANGENT_TO_CIRCLE\x10\x03\x12$\n ORBIT_YAW_BEHAVIOR_RC_CONTROLLED\x10\x04\x32\xa5\x10\n\rActionService\x12\x46\n\x03\x41rm\x12\x1d.mavsdk.rpc.action.ArmRequest\x1a\x1e.mavsdk.rpc.action.ArmResponse"\x00\x12U\n\x08\x41rmForce\x12".mavsdk.rpc.action.ArmForceRequest\x1a#.mavsdk.rpc.action.ArmForceResponse"\x00\x12O\n\x06\x44isarm\x12 .mavsdk.rpc.action.DisarmRequest\x1a!.mavsdk.rpc.action.DisarmResponse"\x00\x12R\n\x07Takeoff\x12!.mavsdk.rpc.action.TakeoffRequest\x1a".mavsdk.rpc.action.TakeoffResponse"\x00\x12I\n\x04Land\x12\x1e.mavsdk.rpc.action.LandRequest\x1a\x1f.mavsdk.rpc.action.LandResponse"\x00\x12O\n\x06Reboot\x12 .mavsdk.rpc.action.RebootRequest\x1a!.mavsdk.rpc.action.RebootResponse"\x00\x12U\n\x08Shutdown\x12".mavsdk.rpc.action.ShutdownRequest\x1a#.mavsdk.rpc.action.ShutdownResponse"\x00\x12X\n\tTerminate\x12#.mavsdk.rpc.action.TerminateRequest\x1a$.mavsdk.rpc.action.TerminateResponse"\x00\x12I\n\x04Kill\x12\x1e.mavsdk.rpc.action.KillRequest\x1a\x1f.mavsdk.rpc.action.KillResponse"\x00\x12g\n\x0eReturnToLaunch\x12(.mavsdk.rpc.action.ReturnToLaunchRequest\x1a).mavsdk.rpc.action.ReturnToLaunchResponse"\x00\x12\x61\n\x0cGotoLocation\x12&.mavsdk.rpc.action.GotoLocationRequest\x1a\'.mavsdk.rpc.action.GotoLocationResponse"\x00\x12R\n\x07\x44oOrbit\x12!.mavsdk.rpc.action.DoOrbitRequest\x1a".mavsdk.rpc.action.DoOrbitResponse"\x00\x12I\n\x04Hold\x12\x1e.mavsdk.rpc.action.HoldRequest\x1a\x1f.mavsdk.rpc.action.HoldResponse"\x00\x12^\n\x0bSetActuator\x12%.mavsdk.rpc.action.SetActuatorRequest\x1a&.mavsdk.rpc.action.SetActuatorResponse"\x00\x12|\n\x15TransitionToFixedwing\x12/.mavsdk.rpc.action.TransitionToFixedwingRequest\x1a\x30.mavsdk.rpc.action.TransitionToFixedwingResponse"\x00\x12\x82\x01\n\x17TransitionToMulticopter\x12\x31.mavsdk.rpc.action.TransitionToMulticopterRequest\x1a\x32.mavsdk.rpc.action.TransitionToMulticopterResponse"\x00\x12s\n\x12GetTakeoffAltitude\x12,.mavsdk.rpc.action.GetTakeoffAltitudeRequest\x1a-.mavsdk.rpc.action.GetTakeoffAltitudeResponse"\x00\x12s\n\x12SetTakeoffAltitude\x12,.mavsdk.rpc.action.SetTakeoffAltitudeRequest\x1a-.mavsdk.rpc.action.SetTakeoffAltitudeResponse"\x00\x12\x88\x01\n\x19GetReturnToLaunchAltitude\x12\x33.mavsdk.rpc.action.GetReturnToLaunchAltitudeRequest\x1a\x34.mavsdk.rpc.action.GetReturnToLaunchAltitudeResponse"\x00\x12\x88\x01\n\x19SetReturnToLaunchAltitude\x12\x33.mavsdk.rpc.action.SetReturnToLaunchAltitudeRequest\x1a\x34.mavsdk.rpc.action.SetReturnToLaunchAltitudeResponse"\x00\x12j\n\x0fSetCurrentSpeed\x12).mavsdk.rpc.action.SetCurrentSpeedRequest\x1a*.mavsdk.rpc.action.SetCurrentSpeedResponse"\x00\x42\x1f\n\x10io.mavsdk.actionB\x0b\x41\x63tionProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'action.action_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "action.action_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\020io.mavsdk.actionB\013ActionProto' - _globals['_DOORBITREQUEST'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_DOORBITREQUEST'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_DOORBITREQUEST'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_DOORBITREQUEST'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_DOORBITREQUEST'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_DOORBITREQUEST'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ORBITYAWBEHAVIOR']._serialized_start=3182 - _globals['_ORBITYAWBEHAVIOR']._serialized_end=3425 - _globals['_ARMREQUEST']._serialized_start=64 - _globals['_ARMREQUEST']._serialized_end=76 - _globals['_ARMRESPONSE']._serialized_start=78 - _globals['_ARMRESPONSE']._serialized_end=147 - _globals['_ARMFORCEREQUEST']._serialized_start=149 - _globals['_ARMFORCEREQUEST']._serialized_end=166 - _globals['_ARMFORCERESPONSE']._serialized_start=168 - _globals['_ARMFORCERESPONSE']._serialized_end=242 - _globals['_DISARMREQUEST']._serialized_start=244 - _globals['_DISARMREQUEST']._serialized_end=259 - _globals['_DISARMRESPONSE']._serialized_start=261 - _globals['_DISARMRESPONSE']._serialized_end=333 - _globals['_TAKEOFFREQUEST']._serialized_start=335 - _globals['_TAKEOFFREQUEST']._serialized_end=351 - _globals['_TAKEOFFRESPONSE']._serialized_start=353 - _globals['_TAKEOFFRESPONSE']._serialized_end=426 - _globals['_LANDREQUEST']._serialized_start=428 - _globals['_LANDREQUEST']._serialized_end=441 - _globals['_LANDRESPONSE']._serialized_start=443 - _globals['_LANDRESPONSE']._serialized_end=513 - _globals['_REBOOTREQUEST']._serialized_start=515 - _globals['_REBOOTREQUEST']._serialized_end=530 - _globals['_REBOOTRESPONSE']._serialized_start=532 - _globals['_REBOOTRESPONSE']._serialized_end=604 - _globals['_SHUTDOWNREQUEST']._serialized_start=606 - _globals['_SHUTDOWNREQUEST']._serialized_end=623 - _globals['_SHUTDOWNRESPONSE']._serialized_start=625 - _globals['_SHUTDOWNRESPONSE']._serialized_end=699 - _globals['_TERMINATEREQUEST']._serialized_start=701 - _globals['_TERMINATEREQUEST']._serialized_end=719 - _globals['_TERMINATERESPONSE']._serialized_start=721 - _globals['_TERMINATERESPONSE']._serialized_end=796 - _globals['_KILLREQUEST']._serialized_start=798 - _globals['_KILLREQUEST']._serialized_end=811 - _globals['_KILLRESPONSE']._serialized_start=813 - _globals['_KILLRESPONSE']._serialized_end=883 - _globals['_RETURNTOLAUNCHREQUEST']._serialized_start=885 - _globals['_RETURNTOLAUNCHREQUEST']._serialized_end=908 - _globals['_RETURNTOLAUNCHRESPONSE']._serialized_start=910 - _globals['_RETURNTOLAUNCHRESPONSE']._serialized_end=990 - _globals['_GOTOLOCATIONREQUEST']._serialized_start=992 - _globals['_GOTOLOCATIONREQUEST']._serialized_end=1104 - _globals['_GOTOLOCATIONRESPONSE']._serialized_start=1106 - _globals['_GOTOLOCATIONRESPONSE']._serialized_end=1184 - _globals['_DOORBITREQUEST']._serialized_start=1187 - _globals['_DOORBITREQUEST']._serialized_end=1402 - _globals['_DOORBITRESPONSE']._serialized_start=1404 - _globals['_DOORBITRESPONSE']._serialized_end=1477 - _globals['_HOLDREQUEST']._serialized_start=1479 - _globals['_HOLDREQUEST']._serialized_end=1492 - _globals['_HOLDRESPONSE']._serialized_start=1494 - _globals['_HOLDRESPONSE']._serialized_end=1564 - _globals['_SETACTUATORREQUEST']._serialized_start=1566 - _globals['_SETACTUATORREQUEST']._serialized_end=1616 - _globals['_SETACTUATORRESPONSE']._serialized_start=1618 - _globals['_SETACTUATORRESPONSE']._serialized_end=1695 - _globals['_TRANSITIONTOFIXEDWINGREQUEST']._serialized_start=1697 - _globals['_TRANSITIONTOFIXEDWINGREQUEST']._serialized_end=1727 - _globals['_TRANSITIONTOFIXEDWINGRESPONSE']._serialized_start=1729 - _globals['_TRANSITIONTOFIXEDWINGRESPONSE']._serialized_end=1816 - _globals['_TRANSITIONTOMULTICOPTERREQUEST']._serialized_start=1818 - _globals['_TRANSITIONTOMULTICOPTERREQUEST']._serialized_end=1850 - _globals['_TRANSITIONTOMULTICOPTERRESPONSE']._serialized_start=1852 - _globals['_TRANSITIONTOMULTICOPTERRESPONSE']._serialized_end=1941 - _globals['_GETTAKEOFFALTITUDEREQUEST']._serialized_start=1943 - _globals['_GETTAKEOFFALTITUDEREQUEST']._serialized_end=1970 - _globals['_GETTAKEOFFALTITUDERESPONSE']._serialized_start=1972 - _globals['_GETTAKEOFFALTITUDERESPONSE']._serialized_end=2074 - _globals['_SETTAKEOFFALTITUDEREQUEST']._serialized_start=2076 - _globals['_SETTAKEOFFALTITUDEREQUEST']._serialized_end=2121 - _globals['_SETTAKEOFFALTITUDERESPONSE']._serialized_start=2123 - _globals['_SETTAKEOFFALTITUDERESPONSE']._serialized_end=2207 - _globals['_GETRETURNTOLAUNCHALTITUDEREQUEST']._serialized_start=2209 - _globals['_GETRETURNTOLAUNCHALTITUDEREQUEST']._serialized_end=2243 - _globals['_GETRETURNTOLAUNCHALTITUDERESPONSE']._serialized_start=2245 - _globals['_GETRETURNTOLAUNCHALTITUDERESPONSE']._serialized_end=2365 - _globals['_SETRETURNTOLAUNCHALTITUDEREQUEST']._serialized_start=2367 - _globals['_SETRETURNTOLAUNCHALTITUDEREQUEST']._serialized_end=2430 - _globals['_SETRETURNTOLAUNCHALTITUDERESPONSE']._serialized_start=2432 - _globals['_SETRETURNTOLAUNCHALTITUDERESPONSE']._serialized_end=2523 - _globals['_SETCURRENTSPEEDREQUEST']._serialized_start=2525 - _globals['_SETCURRENTSPEEDREQUEST']._serialized_end=2568 - _globals['_SETCURRENTSPEEDRESPONSE']._serialized_start=2570 - _globals['_SETCURRENTSPEEDRESPONSE']._serialized_end=2651 - _globals['_ACTIONRESULT']._serialized_start=2654 - _globals['_ACTIONRESULT']._serialized_end=3179 - _globals['_ACTIONRESULT_RESULT']._serialized_start=2747 - _globals['_ACTIONRESULT_RESULT']._serialized_end=3179 - _globals['_ACTIONSERVICE']._serialized_start=3428 - _globals['_ACTIONSERVICE']._serialized_end=5513 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\020io.mavsdk.actionB\013ActionProto" + _globals["_DOORBITREQUEST"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_DOORBITREQUEST"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_DOORBITREQUEST"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_DOORBITREQUEST"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_DOORBITREQUEST"].fields_by_name[ + "absolute_altitude_m" + ]._loaded_options = None + _globals["_DOORBITREQUEST"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ORBITYAWBEHAVIOR"]._serialized_start = 3182 + _globals["_ORBITYAWBEHAVIOR"]._serialized_end = 3425 + _globals["_ARMREQUEST"]._serialized_start = 64 + _globals["_ARMREQUEST"]._serialized_end = 76 + _globals["_ARMRESPONSE"]._serialized_start = 78 + _globals["_ARMRESPONSE"]._serialized_end = 147 + _globals["_ARMFORCEREQUEST"]._serialized_start = 149 + _globals["_ARMFORCEREQUEST"]._serialized_end = 166 + _globals["_ARMFORCERESPONSE"]._serialized_start = 168 + _globals["_ARMFORCERESPONSE"]._serialized_end = 242 + _globals["_DISARMREQUEST"]._serialized_start = 244 + _globals["_DISARMREQUEST"]._serialized_end = 259 + _globals["_DISARMRESPONSE"]._serialized_start = 261 + _globals["_DISARMRESPONSE"]._serialized_end = 333 + _globals["_TAKEOFFREQUEST"]._serialized_start = 335 + _globals["_TAKEOFFREQUEST"]._serialized_end = 351 + _globals["_TAKEOFFRESPONSE"]._serialized_start = 353 + _globals["_TAKEOFFRESPONSE"]._serialized_end = 426 + _globals["_LANDREQUEST"]._serialized_start = 428 + _globals["_LANDREQUEST"]._serialized_end = 441 + _globals["_LANDRESPONSE"]._serialized_start = 443 + _globals["_LANDRESPONSE"]._serialized_end = 513 + _globals["_REBOOTREQUEST"]._serialized_start = 515 + _globals["_REBOOTREQUEST"]._serialized_end = 530 + _globals["_REBOOTRESPONSE"]._serialized_start = 532 + _globals["_REBOOTRESPONSE"]._serialized_end = 604 + _globals["_SHUTDOWNREQUEST"]._serialized_start = 606 + _globals["_SHUTDOWNREQUEST"]._serialized_end = 623 + _globals["_SHUTDOWNRESPONSE"]._serialized_start = 625 + _globals["_SHUTDOWNRESPONSE"]._serialized_end = 699 + _globals["_TERMINATEREQUEST"]._serialized_start = 701 + _globals["_TERMINATEREQUEST"]._serialized_end = 719 + _globals["_TERMINATERESPONSE"]._serialized_start = 721 + _globals["_TERMINATERESPONSE"]._serialized_end = 796 + _globals["_KILLREQUEST"]._serialized_start = 798 + _globals["_KILLREQUEST"]._serialized_end = 811 + _globals["_KILLRESPONSE"]._serialized_start = 813 + _globals["_KILLRESPONSE"]._serialized_end = 883 + _globals["_RETURNTOLAUNCHREQUEST"]._serialized_start = 885 + _globals["_RETURNTOLAUNCHREQUEST"]._serialized_end = 908 + _globals["_RETURNTOLAUNCHRESPONSE"]._serialized_start = 910 + _globals["_RETURNTOLAUNCHRESPONSE"]._serialized_end = 990 + _globals["_GOTOLOCATIONREQUEST"]._serialized_start = 992 + _globals["_GOTOLOCATIONREQUEST"]._serialized_end = 1104 + _globals["_GOTOLOCATIONRESPONSE"]._serialized_start = 1106 + _globals["_GOTOLOCATIONRESPONSE"]._serialized_end = 1184 + _globals["_DOORBITREQUEST"]._serialized_start = 1187 + _globals["_DOORBITREQUEST"]._serialized_end = 1402 + _globals["_DOORBITRESPONSE"]._serialized_start = 1404 + _globals["_DOORBITRESPONSE"]._serialized_end = 1477 + _globals["_HOLDREQUEST"]._serialized_start = 1479 + _globals["_HOLDREQUEST"]._serialized_end = 1492 + _globals["_HOLDRESPONSE"]._serialized_start = 1494 + _globals["_HOLDRESPONSE"]._serialized_end = 1564 + _globals["_SETACTUATORREQUEST"]._serialized_start = 1566 + _globals["_SETACTUATORREQUEST"]._serialized_end = 1616 + _globals["_SETACTUATORRESPONSE"]._serialized_start = 1618 + _globals["_SETACTUATORRESPONSE"]._serialized_end = 1695 + _globals["_TRANSITIONTOFIXEDWINGREQUEST"]._serialized_start = 1697 + _globals["_TRANSITIONTOFIXEDWINGREQUEST"]._serialized_end = 1727 + _globals["_TRANSITIONTOFIXEDWINGRESPONSE"]._serialized_start = 1729 + _globals["_TRANSITIONTOFIXEDWINGRESPONSE"]._serialized_end = 1816 + _globals["_TRANSITIONTOMULTICOPTERREQUEST"]._serialized_start = 1818 + _globals["_TRANSITIONTOMULTICOPTERREQUEST"]._serialized_end = 1850 + _globals["_TRANSITIONTOMULTICOPTERRESPONSE"]._serialized_start = 1852 + _globals["_TRANSITIONTOMULTICOPTERRESPONSE"]._serialized_end = 1941 + _globals["_GETTAKEOFFALTITUDEREQUEST"]._serialized_start = 1943 + _globals["_GETTAKEOFFALTITUDEREQUEST"]._serialized_end = 1970 + _globals["_GETTAKEOFFALTITUDERESPONSE"]._serialized_start = 1972 + _globals["_GETTAKEOFFALTITUDERESPONSE"]._serialized_end = 2074 + _globals["_SETTAKEOFFALTITUDEREQUEST"]._serialized_start = 2076 + _globals["_SETTAKEOFFALTITUDEREQUEST"]._serialized_end = 2121 + _globals["_SETTAKEOFFALTITUDERESPONSE"]._serialized_start = 2123 + _globals["_SETTAKEOFFALTITUDERESPONSE"]._serialized_end = 2207 + _globals["_GETRETURNTOLAUNCHALTITUDEREQUEST"]._serialized_start = 2209 + _globals["_GETRETURNTOLAUNCHALTITUDEREQUEST"]._serialized_end = 2243 + _globals["_GETRETURNTOLAUNCHALTITUDERESPONSE"]._serialized_start = 2245 + _globals["_GETRETURNTOLAUNCHALTITUDERESPONSE"]._serialized_end = 2365 + _globals["_SETRETURNTOLAUNCHALTITUDEREQUEST"]._serialized_start = 2367 + _globals["_SETRETURNTOLAUNCHALTITUDEREQUEST"]._serialized_end = 2430 + _globals["_SETRETURNTOLAUNCHALTITUDERESPONSE"]._serialized_start = 2432 + _globals["_SETRETURNTOLAUNCHALTITUDERESPONSE"]._serialized_end = 2523 + _globals["_SETCURRENTSPEEDREQUEST"]._serialized_start = 2525 + _globals["_SETCURRENTSPEEDREQUEST"]._serialized_end = 2568 + _globals["_SETCURRENTSPEEDRESPONSE"]._serialized_start = 2570 + _globals["_SETCURRENTSPEEDRESPONSE"]._serialized_end = 2651 + _globals["_ACTIONRESULT"]._serialized_start = 2654 + _globals["_ACTIONRESULT"]._serialized_end = 3179 + _globals["_ACTIONRESULT_RESULT"]._serialized_start = 2747 + _globals["_ACTIONRESULT_RESULT"]._serialized_end = 3179 + _globals["_ACTIONSERVICE"]._serialized_start = 3428 + _globals["_ACTIONSERVICE"]._serialized_end = 5513 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/action_pb2_grpc.py b/mavsdk/action_pb2_grpc.py index 555ca3be..9e372728 100644 --- a/mavsdk/action_pb2_grpc.py +++ b/mavsdk/action_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import action_pb2 as action_dot_action__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in action/action_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in action/action_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ActionServiceStub(object): - """Enable simple actions such as arming, taking off, and landing. - """ + """Enable simple actions such as arming, taking off, and landing.""" def __init__(self, channel): """Constructor. @@ -36,115 +39,135 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.Arm = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Arm', - request_serializer=action_dot_action__pb2.ArmRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.ArmResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Arm", + request_serializer=action_dot_action__pb2.ArmRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.ArmResponse.FromString, + _registered_method=True, + ) self.ArmForce = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/ArmForce', - request_serializer=action_dot_action__pb2.ArmForceRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.ArmForceResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/ArmForce", + request_serializer=action_dot_action__pb2.ArmForceRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.ArmForceResponse.FromString, + _registered_method=True, + ) self.Disarm = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Disarm', - request_serializer=action_dot_action__pb2.DisarmRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.DisarmResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Disarm", + request_serializer=action_dot_action__pb2.DisarmRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.DisarmResponse.FromString, + _registered_method=True, + ) self.Takeoff = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Takeoff', - request_serializer=action_dot_action__pb2.TakeoffRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.TakeoffResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Takeoff", + request_serializer=action_dot_action__pb2.TakeoffRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.TakeoffResponse.FromString, + _registered_method=True, + ) self.Land = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Land', - request_serializer=action_dot_action__pb2.LandRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.LandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Land", + request_serializer=action_dot_action__pb2.LandRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.LandResponse.FromString, + _registered_method=True, + ) self.Reboot = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Reboot', - request_serializer=action_dot_action__pb2.RebootRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.RebootResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Reboot", + request_serializer=action_dot_action__pb2.RebootRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.RebootResponse.FromString, + _registered_method=True, + ) self.Shutdown = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Shutdown', - request_serializer=action_dot_action__pb2.ShutdownRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.ShutdownResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Shutdown", + request_serializer=action_dot_action__pb2.ShutdownRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.ShutdownResponse.FromString, + _registered_method=True, + ) self.Terminate = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Terminate', - request_serializer=action_dot_action__pb2.TerminateRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.TerminateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Terminate", + request_serializer=action_dot_action__pb2.TerminateRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.TerminateResponse.FromString, + _registered_method=True, + ) self.Kill = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Kill', - request_serializer=action_dot_action__pb2.KillRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.KillResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Kill", + request_serializer=action_dot_action__pb2.KillRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.KillResponse.FromString, + _registered_method=True, + ) self.ReturnToLaunch = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/ReturnToLaunch', - request_serializer=action_dot_action__pb2.ReturnToLaunchRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.ReturnToLaunchResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/ReturnToLaunch", + request_serializer=action_dot_action__pb2.ReturnToLaunchRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.ReturnToLaunchResponse.FromString, + _registered_method=True, + ) self.GotoLocation = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/GotoLocation', - request_serializer=action_dot_action__pb2.GotoLocationRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.GotoLocationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/GotoLocation", + request_serializer=action_dot_action__pb2.GotoLocationRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.GotoLocationResponse.FromString, + _registered_method=True, + ) self.DoOrbit = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/DoOrbit', - request_serializer=action_dot_action__pb2.DoOrbitRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.DoOrbitResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/DoOrbit", + request_serializer=action_dot_action__pb2.DoOrbitRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.DoOrbitResponse.FromString, + _registered_method=True, + ) self.Hold = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/Hold', - request_serializer=action_dot_action__pb2.HoldRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.HoldResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/Hold", + request_serializer=action_dot_action__pb2.HoldRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.HoldResponse.FromString, + _registered_method=True, + ) self.SetActuator = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/SetActuator', - request_serializer=action_dot_action__pb2.SetActuatorRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.SetActuatorResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/SetActuator", + request_serializer=action_dot_action__pb2.SetActuatorRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.SetActuatorResponse.FromString, + _registered_method=True, + ) self.TransitionToFixedwing = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/TransitionToFixedwing', - request_serializer=action_dot_action__pb2.TransitionToFixedwingRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.TransitionToFixedwingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/TransitionToFixedwing", + request_serializer=action_dot_action__pb2.TransitionToFixedwingRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.TransitionToFixedwingResponse.FromString, + _registered_method=True, + ) self.TransitionToMulticopter = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/TransitionToMulticopter', - request_serializer=action_dot_action__pb2.TransitionToMulticopterRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.TransitionToMulticopterResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/TransitionToMulticopter", + request_serializer=action_dot_action__pb2.TransitionToMulticopterRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.TransitionToMulticopterResponse.FromString, + _registered_method=True, + ) self.GetTakeoffAltitude = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/GetTakeoffAltitude', - request_serializer=action_dot_action__pb2.GetTakeoffAltitudeRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.GetTakeoffAltitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/GetTakeoffAltitude", + request_serializer=action_dot_action__pb2.GetTakeoffAltitudeRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.GetTakeoffAltitudeResponse.FromString, + _registered_method=True, + ) self.SetTakeoffAltitude = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/SetTakeoffAltitude', - request_serializer=action_dot_action__pb2.SetTakeoffAltitudeRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.SetTakeoffAltitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/SetTakeoffAltitude", + request_serializer=action_dot_action__pb2.SetTakeoffAltitudeRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.SetTakeoffAltitudeResponse.FromString, + _registered_method=True, + ) self.GetReturnToLaunchAltitude = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude', - request_serializer=action_dot_action__pb2.GetReturnToLaunchAltitudeRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.GetReturnToLaunchAltitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude", + request_serializer=action_dot_action__pb2.GetReturnToLaunchAltitudeRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.GetReturnToLaunchAltitudeResponse.FromString, + _registered_method=True, + ) self.SetReturnToLaunchAltitude = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude', - request_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude", + request_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString, + _registered_method=True, + ) self.SetCurrentSpeed = channel.unary_unary( - '/mavsdk.rpc.action.ActionService/SetCurrentSpeed', - request_serializer=action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString, - response_deserializer=action_dot_action__pb2.SetCurrentSpeedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action.ActionService/SetCurrentSpeed", + request_serializer=action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString, + response_deserializer=action_dot_action__pb2.SetCurrentSpeedResponse.FromString, + _registered_method=True, + ) class ActionServiceServicer(object): - """Enable simple actions such as arming, taking off, and landing. - """ + """Enable simple actions such as arming, taking off, and landing.""" def Arm(self, request, context): """ @@ -154,8 +177,8 @@ def Arm(self, request, context): Before arming take all safety precautions and stand clear of the drone! """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ArmForce(self, request, context): """ @@ -167,8 +190,8 @@ def ArmForce(self, request, context): Before arming take all safety precautions and stand clear of the drone! """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Disarm(self, request, context): """ @@ -178,8 +201,8 @@ def Disarm(self, request, context): reject the disarm command. Disarming means that all motors will stop. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Takeoff(self, request, context): """ @@ -191,8 +214,8 @@ def Takeoff(self, request, context): Note that the vehicle must be armed before it can take off. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Land(self, request, context): """ @@ -201,8 +224,8 @@ def Land(self, request, context): This switches the drone to 'Land' flight mode. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Reboot(self, request, context): """ @@ -211,8 +234,8 @@ def Reboot(self, request, context): This will reboot the autopilot, companion computer, camera and gimbal. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Shutdown(self, request, context): """ @@ -223,8 +246,8 @@ def Shutdown(self, request, context): reject it if they are not already ready to shut down. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Terminate(self, request, context): """ @@ -233,8 +256,8 @@ def Terminate(self, request, context): This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Kill(self, request, context): """ @@ -244,8 +267,8 @@ def Kill(self, request, context): Note that the drone will fall out of the sky if this command is used while flying. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ReturnToLaunch(self, request, context): """ @@ -256,8 +279,8 @@ def ReturnToLaunch(self, request, context): back to the launch (takeoff) position and land there. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GotoLocation(self, request, context): """ @@ -269,8 +292,8 @@ def GotoLocation(self, request, context): The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def DoOrbit(self, request, context): """ @@ -279,8 +302,8 @@ def DoOrbit(self, request, context): This will run the orbit routine with the given parameters. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Hold(self, request, context): """ @@ -293,8 +316,8 @@ def Hold(self, request, context): it implies a change to a PX4-specific mode. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetActuator(self, request, context): """ @@ -303,8 +326,8 @@ def SetActuator(self, request, context): Note that the index of the actuator starts at 1 and that the value goes from -1 to 1. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def TransitionToFixedwing(self, request, context): """ @@ -315,8 +338,8 @@ def TransitionToFixedwing(self, request, context): is already in fixedwing mode. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def TransitionToMulticopter(self, request, context): """ @@ -327,40 +350,40 @@ def TransitionToMulticopter(self, request, context): is already in multicopter mode. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetTakeoffAltitude(self, request, context): """ Get the takeoff altitude (in meters above ground). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTakeoffAltitude(self, request, context): """ Set takeoff altitude (in meters above ground). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetReturnToLaunchAltitude(self, request, context): """ Get the return to launch minimum return altitude (in meters). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetReturnToLaunchAltitude(self, request, context): """ Set the return to launch minimum return altitude (in meters). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetCurrentSpeed(self, request, context): """ @@ -370,144 +393,148 @@ def SetCurrentSpeed(self, request, context): It is ephemeral, so not stored on the drone and does not survive a reboot. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ActionServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'Arm': grpc.unary_unary_rpc_method_handler( - servicer.Arm, - request_deserializer=action_dot_action__pb2.ArmRequest.FromString, - response_serializer=action_dot_action__pb2.ArmResponse.SerializeToString, - ), - 'ArmForce': grpc.unary_unary_rpc_method_handler( - servicer.ArmForce, - request_deserializer=action_dot_action__pb2.ArmForceRequest.FromString, - response_serializer=action_dot_action__pb2.ArmForceResponse.SerializeToString, - ), - 'Disarm': grpc.unary_unary_rpc_method_handler( - servicer.Disarm, - request_deserializer=action_dot_action__pb2.DisarmRequest.FromString, - response_serializer=action_dot_action__pb2.DisarmResponse.SerializeToString, - ), - 'Takeoff': grpc.unary_unary_rpc_method_handler( - servicer.Takeoff, - request_deserializer=action_dot_action__pb2.TakeoffRequest.FromString, - response_serializer=action_dot_action__pb2.TakeoffResponse.SerializeToString, - ), - 'Land': grpc.unary_unary_rpc_method_handler( - servicer.Land, - request_deserializer=action_dot_action__pb2.LandRequest.FromString, - response_serializer=action_dot_action__pb2.LandResponse.SerializeToString, - ), - 'Reboot': grpc.unary_unary_rpc_method_handler( - servicer.Reboot, - request_deserializer=action_dot_action__pb2.RebootRequest.FromString, - response_serializer=action_dot_action__pb2.RebootResponse.SerializeToString, - ), - 'Shutdown': grpc.unary_unary_rpc_method_handler( - servicer.Shutdown, - request_deserializer=action_dot_action__pb2.ShutdownRequest.FromString, - response_serializer=action_dot_action__pb2.ShutdownResponse.SerializeToString, - ), - 'Terminate': grpc.unary_unary_rpc_method_handler( - servicer.Terminate, - request_deserializer=action_dot_action__pb2.TerminateRequest.FromString, - response_serializer=action_dot_action__pb2.TerminateResponse.SerializeToString, - ), - 'Kill': grpc.unary_unary_rpc_method_handler( - servicer.Kill, - request_deserializer=action_dot_action__pb2.KillRequest.FromString, - response_serializer=action_dot_action__pb2.KillResponse.SerializeToString, - ), - 'ReturnToLaunch': grpc.unary_unary_rpc_method_handler( - servicer.ReturnToLaunch, - request_deserializer=action_dot_action__pb2.ReturnToLaunchRequest.FromString, - response_serializer=action_dot_action__pb2.ReturnToLaunchResponse.SerializeToString, - ), - 'GotoLocation': grpc.unary_unary_rpc_method_handler( - servicer.GotoLocation, - request_deserializer=action_dot_action__pb2.GotoLocationRequest.FromString, - response_serializer=action_dot_action__pb2.GotoLocationResponse.SerializeToString, - ), - 'DoOrbit': grpc.unary_unary_rpc_method_handler( - servicer.DoOrbit, - request_deserializer=action_dot_action__pb2.DoOrbitRequest.FromString, - response_serializer=action_dot_action__pb2.DoOrbitResponse.SerializeToString, - ), - 'Hold': grpc.unary_unary_rpc_method_handler( - servicer.Hold, - request_deserializer=action_dot_action__pb2.HoldRequest.FromString, - response_serializer=action_dot_action__pb2.HoldResponse.SerializeToString, - ), - 'SetActuator': grpc.unary_unary_rpc_method_handler( - servicer.SetActuator, - request_deserializer=action_dot_action__pb2.SetActuatorRequest.FromString, - response_serializer=action_dot_action__pb2.SetActuatorResponse.SerializeToString, - ), - 'TransitionToFixedwing': grpc.unary_unary_rpc_method_handler( - servicer.TransitionToFixedwing, - request_deserializer=action_dot_action__pb2.TransitionToFixedwingRequest.FromString, - response_serializer=action_dot_action__pb2.TransitionToFixedwingResponse.SerializeToString, - ), - 'TransitionToMulticopter': grpc.unary_unary_rpc_method_handler( - servicer.TransitionToMulticopter, - request_deserializer=action_dot_action__pb2.TransitionToMulticopterRequest.FromString, - response_serializer=action_dot_action__pb2.TransitionToMulticopterResponse.SerializeToString, - ), - 'GetTakeoffAltitude': grpc.unary_unary_rpc_method_handler( - servicer.GetTakeoffAltitude, - request_deserializer=action_dot_action__pb2.GetTakeoffAltitudeRequest.FromString, - response_serializer=action_dot_action__pb2.GetTakeoffAltitudeResponse.SerializeToString, - ), - 'SetTakeoffAltitude': grpc.unary_unary_rpc_method_handler( - servicer.SetTakeoffAltitude, - request_deserializer=action_dot_action__pb2.SetTakeoffAltitudeRequest.FromString, - response_serializer=action_dot_action__pb2.SetTakeoffAltitudeResponse.SerializeToString, - ), - 'GetReturnToLaunchAltitude': grpc.unary_unary_rpc_method_handler( - servicer.GetReturnToLaunchAltitude, - request_deserializer=action_dot_action__pb2.GetReturnToLaunchAltitudeRequest.FromString, - response_serializer=action_dot_action__pb2.GetReturnToLaunchAltitudeResponse.SerializeToString, - ), - 'SetReturnToLaunchAltitude': grpc.unary_unary_rpc_method_handler( - servicer.SetReturnToLaunchAltitude, - request_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.FromString, - response_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.SerializeToString, - ), - 'SetCurrentSpeed': grpc.unary_unary_rpc_method_handler( - servicer.SetCurrentSpeed, - request_deserializer=action_dot_action__pb2.SetCurrentSpeedRequest.FromString, - response_serializer=action_dot_action__pb2.SetCurrentSpeedResponse.SerializeToString, - ), + "Arm": grpc.unary_unary_rpc_method_handler( + servicer.Arm, + request_deserializer=action_dot_action__pb2.ArmRequest.FromString, + response_serializer=action_dot_action__pb2.ArmResponse.SerializeToString, + ), + "ArmForce": grpc.unary_unary_rpc_method_handler( + servicer.ArmForce, + request_deserializer=action_dot_action__pb2.ArmForceRequest.FromString, + response_serializer=action_dot_action__pb2.ArmForceResponse.SerializeToString, + ), + "Disarm": grpc.unary_unary_rpc_method_handler( + servicer.Disarm, + request_deserializer=action_dot_action__pb2.DisarmRequest.FromString, + response_serializer=action_dot_action__pb2.DisarmResponse.SerializeToString, + ), + "Takeoff": grpc.unary_unary_rpc_method_handler( + servicer.Takeoff, + request_deserializer=action_dot_action__pb2.TakeoffRequest.FromString, + response_serializer=action_dot_action__pb2.TakeoffResponse.SerializeToString, + ), + "Land": grpc.unary_unary_rpc_method_handler( + servicer.Land, + request_deserializer=action_dot_action__pb2.LandRequest.FromString, + response_serializer=action_dot_action__pb2.LandResponse.SerializeToString, + ), + "Reboot": grpc.unary_unary_rpc_method_handler( + servicer.Reboot, + request_deserializer=action_dot_action__pb2.RebootRequest.FromString, + response_serializer=action_dot_action__pb2.RebootResponse.SerializeToString, + ), + "Shutdown": grpc.unary_unary_rpc_method_handler( + servicer.Shutdown, + request_deserializer=action_dot_action__pb2.ShutdownRequest.FromString, + response_serializer=action_dot_action__pb2.ShutdownResponse.SerializeToString, + ), + "Terminate": grpc.unary_unary_rpc_method_handler( + servicer.Terminate, + request_deserializer=action_dot_action__pb2.TerminateRequest.FromString, + response_serializer=action_dot_action__pb2.TerminateResponse.SerializeToString, + ), + "Kill": grpc.unary_unary_rpc_method_handler( + servicer.Kill, + request_deserializer=action_dot_action__pb2.KillRequest.FromString, + response_serializer=action_dot_action__pb2.KillResponse.SerializeToString, + ), + "ReturnToLaunch": grpc.unary_unary_rpc_method_handler( + servicer.ReturnToLaunch, + request_deserializer=action_dot_action__pb2.ReturnToLaunchRequest.FromString, + response_serializer=action_dot_action__pb2.ReturnToLaunchResponse.SerializeToString, + ), + "GotoLocation": grpc.unary_unary_rpc_method_handler( + servicer.GotoLocation, + request_deserializer=action_dot_action__pb2.GotoLocationRequest.FromString, + response_serializer=action_dot_action__pb2.GotoLocationResponse.SerializeToString, + ), + "DoOrbit": grpc.unary_unary_rpc_method_handler( + servicer.DoOrbit, + request_deserializer=action_dot_action__pb2.DoOrbitRequest.FromString, + response_serializer=action_dot_action__pb2.DoOrbitResponse.SerializeToString, + ), + "Hold": grpc.unary_unary_rpc_method_handler( + servicer.Hold, + request_deserializer=action_dot_action__pb2.HoldRequest.FromString, + response_serializer=action_dot_action__pb2.HoldResponse.SerializeToString, + ), + "SetActuator": grpc.unary_unary_rpc_method_handler( + servicer.SetActuator, + request_deserializer=action_dot_action__pb2.SetActuatorRequest.FromString, + response_serializer=action_dot_action__pb2.SetActuatorResponse.SerializeToString, + ), + "TransitionToFixedwing": grpc.unary_unary_rpc_method_handler( + servicer.TransitionToFixedwing, + request_deserializer=action_dot_action__pb2.TransitionToFixedwingRequest.FromString, + response_serializer=action_dot_action__pb2.TransitionToFixedwingResponse.SerializeToString, + ), + "TransitionToMulticopter": grpc.unary_unary_rpc_method_handler( + servicer.TransitionToMulticopter, + request_deserializer=action_dot_action__pb2.TransitionToMulticopterRequest.FromString, + response_serializer=action_dot_action__pb2.TransitionToMulticopterResponse.SerializeToString, + ), + "GetTakeoffAltitude": grpc.unary_unary_rpc_method_handler( + servicer.GetTakeoffAltitude, + request_deserializer=action_dot_action__pb2.GetTakeoffAltitudeRequest.FromString, + response_serializer=action_dot_action__pb2.GetTakeoffAltitudeResponse.SerializeToString, + ), + "SetTakeoffAltitude": grpc.unary_unary_rpc_method_handler( + servicer.SetTakeoffAltitude, + request_deserializer=action_dot_action__pb2.SetTakeoffAltitudeRequest.FromString, + response_serializer=action_dot_action__pb2.SetTakeoffAltitudeResponse.SerializeToString, + ), + "GetReturnToLaunchAltitude": grpc.unary_unary_rpc_method_handler( + servicer.GetReturnToLaunchAltitude, + request_deserializer=action_dot_action__pb2.GetReturnToLaunchAltitudeRequest.FromString, + response_serializer=action_dot_action__pb2.GetReturnToLaunchAltitudeResponse.SerializeToString, + ), + "SetReturnToLaunchAltitude": grpc.unary_unary_rpc_method_handler( + servicer.SetReturnToLaunchAltitude, + request_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.FromString, + response_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.SerializeToString, + ), + "SetCurrentSpeed": grpc.unary_unary_rpc_method_handler( + servicer.SetCurrentSpeed, + request_deserializer=action_dot_action__pb2.SetCurrentSpeedRequest.FromString, + response_serializer=action_dot_action__pb2.SetCurrentSpeedResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.action.ActionService', rpc_method_handlers) + "mavsdk.rpc.action.ActionService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.action.ActionService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.action.ActionService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ActionService(object): - """Enable simple actions such as arming, taking off, and landing. - """ + """Enable simple actions such as arming, taking off, and landing.""" @staticmethod - def Arm(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Arm( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Arm', + "/mavsdk.rpc.action.ActionService/Arm", action_dot_action__pb2.ArmRequest.SerializeToString, action_dot_action__pb2.ArmResponse.FromString, options, @@ -518,23 +545,26 @@ def Arm(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ArmForce(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ArmForce( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/ArmForce', + "/mavsdk.rpc.action.ActionService/ArmForce", action_dot_action__pb2.ArmForceRequest.SerializeToString, action_dot_action__pb2.ArmForceResponse.FromString, options, @@ -545,23 +575,26 @@ def ArmForce(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Disarm(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Disarm( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Disarm', + "/mavsdk.rpc.action.ActionService/Disarm", action_dot_action__pb2.DisarmRequest.SerializeToString, action_dot_action__pb2.DisarmResponse.FromString, options, @@ -572,23 +605,26 @@ def Disarm(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Takeoff(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Takeoff( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Takeoff', + "/mavsdk.rpc.action.ActionService/Takeoff", action_dot_action__pb2.TakeoffRequest.SerializeToString, action_dot_action__pb2.TakeoffResponse.FromString, options, @@ -599,23 +635,26 @@ def Takeoff(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Land(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Land( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Land', + "/mavsdk.rpc.action.ActionService/Land", action_dot_action__pb2.LandRequest.SerializeToString, action_dot_action__pb2.LandResponse.FromString, options, @@ -626,23 +665,26 @@ def Land(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Reboot(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Reboot( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Reboot', + "/mavsdk.rpc.action.ActionService/Reboot", action_dot_action__pb2.RebootRequest.SerializeToString, action_dot_action__pb2.RebootResponse.FromString, options, @@ -653,23 +695,26 @@ def Reboot(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Shutdown(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Shutdown( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Shutdown', + "/mavsdk.rpc.action.ActionService/Shutdown", action_dot_action__pb2.ShutdownRequest.SerializeToString, action_dot_action__pb2.ShutdownResponse.FromString, options, @@ -680,23 +725,26 @@ def Shutdown(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Terminate(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Terminate( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Terminate', + "/mavsdk.rpc.action.ActionService/Terminate", action_dot_action__pb2.TerminateRequest.SerializeToString, action_dot_action__pb2.TerminateResponse.FromString, options, @@ -707,23 +755,26 @@ def Terminate(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Kill(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Kill( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Kill', + "/mavsdk.rpc.action.ActionService/Kill", action_dot_action__pb2.KillRequest.SerializeToString, action_dot_action__pb2.KillResponse.FromString, options, @@ -734,23 +785,26 @@ def Kill(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ReturnToLaunch(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ReturnToLaunch( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/ReturnToLaunch', + "/mavsdk.rpc.action.ActionService/ReturnToLaunch", action_dot_action__pb2.ReturnToLaunchRequest.SerializeToString, action_dot_action__pb2.ReturnToLaunchResponse.FromString, options, @@ -761,23 +815,26 @@ def ReturnToLaunch(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GotoLocation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GotoLocation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/GotoLocation', + "/mavsdk.rpc.action.ActionService/GotoLocation", action_dot_action__pb2.GotoLocationRequest.SerializeToString, action_dot_action__pb2.GotoLocationResponse.FromString, options, @@ -788,23 +845,26 @@ def GotoLocation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def DoOrbit(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def DoOrbit( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/DoOrbit', + "/mavsdk.rpc.action.ActionService/DoOrbit", action_dot_action__pb2.DoOrbitRequest.SerializeToString, action_dot_action__pb2.DoOrbitResponse.FromString, options, @@ -815,23 +875,26 @@ def DoOrbit(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Hold(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Hold( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/Hold', + "/mavsdk.rpc.action.ActionService/Hold", action_dot_action__pb2.HoldRequest.SerializeToString, action_dot_action__pb2.HoldResponse.FromString, options, @@ -842,23 +905,26 @@ def Hold(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetActuator(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetActuator( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/SetActuator', + "/mavsdk.rpc.action.ActionService/SetActuator", action_dot_action__pb2.SetActuatorRequest.SerializeToString, action_dot_action__pb2.SetActuatorResponse.FromString, options, @@ -869,23 +935,26 @@ def SetActuator(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def TransitionToFixedwing(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TransitionToFixedwing( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/TransitionToFixedwing', + "/mavsdk.rpc.action.ActionService/TransitionToFixedwing", action_dot_action__pb2.TransitionToFixedwingRequest.SerializeToString, action_dot_action__pb2.TransitionToFixedwingResponse.FromString, options, @@ -896,23 +965,26 @@ def TransitionToFixedwing(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def TransitionToMulticopter(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TransitionToMulticopter( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/TransitionToMulticopter', + "/mavsdk.rpc.action.ActionService/TransitionToMulticopter", action_dot_action__pb2.TransitionToMulticopterRequest.SerializeToString, action_dot_action__pb2.TransitionToMulticopterResponse.FromString, options, @@ -923,23 +995,26 @@ def TransitionToMulticopter(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetTakeoffAltitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetTakeoffAltitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/GetTakeoffAltitude', + "/mavsdk.rpc.action.ActionService/GetTakeoffAltitude", action_dot_action__pb2.GetTakeoffAltitudeRequest.SerializeToString, action_dot_action__pb2.GetTakeoffAltitudeResponse.FromString, options, @@ -950,23 +1025,26 @@ def GetTakeoffAltitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetTakeoffAltitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetTakeoffAltitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/SetTakeoffAltitude', + "/mavsdk.rpc.action.ActionService/SetTakeoffAltitude", action_dot_action__pb2.SetTakeoffAltitudeRequest.SerializeToString, action_dot_action__pb2.SetTakeoffAltitudeResponse.FromString, options, @@ -977,23 +1055,26 @@ def SetTakeoffAltitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetReturnToLaunchAltitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetReturnToLaunchAltitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude', + "/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude", action_dot_action__pb2.GetReturnToLaunchAltitudeRequest.SerializeToString, action_dot_action__pb2.GetReturnToLaunchAltitudeResponse.FromString, options, @@ -1004,23 +1085,26 @@ def GetReturnToLaunchAltitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetReturnToLaunchAltitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetReturnToLaunchAltitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude', + "/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude", action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.SerializeToString, action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString, options, @@ -1031,23 +1115,26 @@ def SetReturnToLaunchAltitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetCurrentSpeed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetCurrentSpeed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action.ActionService/SetCurrentSpeed', + "/mavsdk.rpc.action.ActionService/SetCurrentSpeed", action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString, action_dot_action__pb2.SetCurrentSpeedResponse.FromString, options, @@ -1058,4 +1145,5 @@ def SetCurrentSpeed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/action_server.py b/mavsdk/action_server.py index bdcf46a5..3b09c946 100644 --- a/mavsdk/action_server.py +++ b/mavsdk/action_server.py @@ -8,58 +8,57 @@ class FlightMode(Enum): """ - Flight modes. + Flight modes. - For more information about flight modes, check out - https://docs.px4.io/master/en/config/flight_mode.html. + For more information about flight modes, check out + https://docs.px4.io/master/en/config/flight_mode.html. - Values - ------ - UNKNOWN - Mode not known + Values + ------ + UNKNOWN + Mode not known - READY - Armed and ready to take off + READY + Armed and ready to take off - TAKEOFF - Taking off + TAKEOFF + Taking off - HOLD - Holding (hovering in place (or circling for fixed-wing vehicles) + HOLD + Holding (hovering in place (or circling for fixed-wing vehicles) - MISSION - In mission + MISSION + In mission - RETURN_TO_LAUNCH - Returning to launch position (then landing) + RETURN_TO_LAUNCH + Returning to launch position (then landing) - LAND - Landing + LAND + Landing - OFFBOARD - In 'offboard' mode + OFFBOARD + In 'offboard' mode - FOLLOW_ME - In 'follow-me' mode + FOLLOW_ME + In 'follow-me' mode - MANUAL - In 'Manual' mode + MANUAL + In 'Manual' mode - ALTCTL - In 'Altitude Control' mode + ALTCTL + In 'Altitude Control' mode - POSCTL - In 'Position Control' mode + POSCTL + In 'Position Control' mode - ACRO - In 'Acro' mode + ACRO + In 'Acro' mode - STABILIZED - In 'Stabilize' mode + STABILIZED + In 'Stabilize' mode - """ + """ - UNKNOWN = 0 READY = 1 TAKEOFF = 2 @@ -107,7 +106,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == action_server_pb2.FLIGHT_MODE_UNKNOWN: return FlightMode.UNKNOWN if rpc_enum_value == action_server_pb2.FLIGHT_MODE_READY: @@ -143,233 +142,182 @@ def __str__(self): class AllowableFlightModes: """ - State to check if the vehicle can transition to - respective flightmodes - - Parameters - ---------- - can_auto_mode : bool - Auto/mission mode + State to check if the vehicle can transition to + respective flightmodes - can_guided_mode : bool - Guided mode + Parameters + ---------- + can_auto_mode : bool + Auto/mission mode - can_stabilize_mode : bool - Stabilize mode + can_guided_mode : bool + Guided mode - """ + can_stabilize_mode : bool + Stabilize mode - + """ - def __init__( - self, - can_auto_mode, - can_guided_mode, - can_stabilize_mode): - """ Initializes the AllowableFlightModes object """ + def __init__(self, can_auto_mode, can_guided_mode, can_stabilize_mode): + """Initializes the AllowableFlightModes object""" self.can_auto_mode = can_auto_mode self.can_guided_mode = can_guided_mode self.can_stabilize_mode = can_stabilize_mode def __eq__(self, to_compare): - """ Checks if two AllowableFlightModes are the same """ + """Checks if two AllowableFlightModes are the same""" try: # Try to compare - this likely fails when it is compared to a non # AllowableFlightModes object - return \ - (self.can_auto_mode == to_compare.can_auto_mode) and \ - (self.can_guided_mode == to_compare.can_guided_mode) and \ - (self.can_stabilize_mode == to_compare.can_stabilize_mode) + return ( + (self.can_auto_mode == to_compare.can_auto_mode) + and (self.can_guided_mode == to_compare.can_guided_mode) + and (self.can_stabilize_mode == to_compare.can_stabilize_mode) + ) except AttributeError: return False def __str__(self): - """ AllowableFlightModes in string representation """ - struct_repr = ", ".join([ + """AllowableFlightModes in string representation""" + struct_repr = ", ".join( + [ "can_auto_mode: " + str(self.can_auto_mode), "can_guided_mode: " + str(self.can_guided_mode), - "can_stabilize_mode: " + str(self.can_stabilize_mode) - ]) + "can_stabilize_mode: " + str(self.can_stabilize_mode), + ] + ) return f"AllowableFlightModes: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAllowableFlightModes): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AllowableFlightModes( - - rpcAllowableFlightModes.can_auto_mode, - - - rpcAllowableFlightModes.can_guided_mode, - - - rpcAllowableFlightModes.can_stabilize_mode - ) + rpcAllowableFlightModes.can_auto_mode, + rpcAllowableFlightModes.can_guided_mode, + rpcAllowableFlightModes.can_stabilize_mode, + ) def translate_to_rpc(self, rpcAllowableFlightModes): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAllowableFlightModes.can_auto_mode = self.can_auto_mode - - - - - + rpcAllowableFlightModes.can_guided_mode = self.can_guided_mode - - - - - + rpcAllowableFlightModes.can_stabilize_mode = self.can_stabilize_mode - - - class ArmDisarm: """ - Arming message type + Arming message type - Parameters - ---------- - arm : bool - Should vehicle arm + Parameters + ---------- + arm : bool + Should vehicle arm - force : bool - Should arm override pre-flight checks + force : bool + Should arm override pre-flight checks - """ - - + """ - def __init__( - self, - arm, - force): - """ Initializes the ArmDisarm object """ + def __init__(self, arm, force): + """Initializes the ArmDisarm object""" self.arm = arm self.force = force def __eq__(self, to_compare): - """ Checks if two ArmDisarm are the same """ + """Checks if two ArmDisarm are the same""" try: # Try to compare - this likely fails when it is compared to a non # ArmDisarm object - return \ - (self.arm == to_compare.arm) and \ - (self.force == to_compare.force) + return (self.arm == to_compare.arm) and (self.force == to_compare.force) except AttributeError: return False def __str__(self): - """ ArmDisarm in string representation """ - struct_repr = ", ".join([ - "arm: " + str(self.arm), - "force: " + str(self.force) - ]) + """ArmDisarm in string representation""" + struct_repr = ", ".join(["arm: " + str(self.arm), "force: " + str(self.force)]) return f"ArmDisarm: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcArmDisarm): - """ Translates a gRPC struct to the SDK equivalent """ - return ArmDisarm( - - rpcArmDisarm.arm, - - - rpcArmDisarm.force - ) + """Translates a gRPC struct to the SDK equivalent""" + return ArmDisarm(rpcArmDisarm.arm, rpcArmDisarm.force) def translate_to_rpc(self, rpcArmDisarm): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcArmDisarm.arm = self.arm - - - - - + rpcArmDisarm.force = self.force - - - class ActionServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request was successful + SUCCESS + Request was successful - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - COMMAND_DENIED_LANDED_STATE_UNKNOWN - Command refused because landed state is unknown + COMMAND_DENIED_LANDED_STATE_UNKNOWN + Command refused because landed state is unknown - COMMAND_DENIED_NOT_LANDED - Command refused because vehicle not landed + COMMAND_DENIED_NOT_LANDED + Command refused because vehicle not landed - TIMEOUT - Request timed out + TIMEOUT + Request timed out - VTOL_TRANSITION_SUPPORT_UNKNOWN - Hybrid/VTOL transition support is unknown + VTOL_TRANSITION_SUPPORT_UNKNOWN + Hybrid/VTOL transition support is unknown - NO_VTOL_TRANSITION_SUPPORT - Vehicle does not support hybrid/VTOL transitions + NO_VTOL_TRANSITION_SUPPORT + Vehicle does not support hybrid/VTOL transitions - PARAMETER_ERROR - Error getting or setting parameter + PARAMETER_ERROR + Error getting or setting parameter - NEXT - Intermediate message showing progress or instructions on the next steps + NEXT + Intermediate message showing progress or instructions on the next steps - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -414,99 +362,101 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_UNKNOWN: return ActionServerResult.Result.UNKNOWN if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_SUCCESS: return ActionServerResult.Result.SUCCESS if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_NO_SYSTEM: return ActionServerResult.Result.NO_SYSTEM - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_CONNECTION_ERROR + ): return ActionServerResult.Result.CONNECTION_ERROR if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_BUSY: return ActionServerResult.Result.BUSY - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_COMMAND_DENIED: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_COMMAND_DENIED + ): return ActionServerResult.Result.COMMAND_DENIED - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN + ): return ActionServerResult.Result.COMMAND_DENIED_LANDED_STATE_UNKNOWN - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_COMMAND_DENIED_NOT_LANDED: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_COMMAND_DENIED_NOT_LANDED + ): return ActionServerResult.Result.COMMAND_DENIED_NOT_LANDED if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_TIMEOUT: return ActionServerResult.Result.TIMEOUT - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN + ): return ActionServerResult.Result.VTOL_TRANSITION_SUPPORT_UNKNOWN - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_NO_VTOL_TRANSITION_SUPPORT: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_NO_VTOL_TRANSITION_SUPPORT + ): return ActionServerResult.Result.NO_VTOL_TRANSITION_SUPPORT - if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_PARAMETER_ERROR: + if ( + rpc_enum_value + == action_server_pb2.ActionServerResult.RESULT_PARAMETER_ERROR + ): return ActionServerResult.Result.PARAMETER_ERROR if rpc_enum_value == action_server_pb2.ActionServerResult.RESULT_NEXT: return ActionServerResult.Result.NEXT def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ActionServerResult object """ + def __init__(self, result, result_str): + """Initializes the ActionServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ActionServerResult are the same """ + """Checks if two ActionServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActionServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ActionServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ActionServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ActionServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActionServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActionServerResult( - - ActionServerResult.Result.translate_from_rpc(rpcActionServerResult.result), - - - rpcActionServerResult.result_str - ) + ActionServerResult.Result.translate_from_rpc(rpcActionServerResult.result), + rpcActionServerResult.result_str, + ) def translate_to_rpc(self, rpcActionServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcActionServerResult.result = self.result.translate_to_rpc() - - - - - - rpcActionServerResult.result_str = self.result_str - - - + rpcActionServerResult.result_str = self.result_str class ActionServerError(Exception): - """ Raised when a ActionServerResult is a fail code """ + """Raised when a ActionServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -519,36 +469,34 @@ def __str__(self): class ActionServer(AsyncBase): """ - Provide vehicle actions (as a server) such as arming, taking off, and landing. + Provide vehicle actions (as a server) such as arming, taking off, and landing. - Generated by dcsdkgen - MAVSDK ActionServer API + Generated by dcsdkgen - MAVSDK ActionServer API """ # Plugin name name = "ActionServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = action_server_pb2_grpc.ActionServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ActionServerResult.translate_from_rpc(response.action_server_result) - async def arm_disarm(self): """ - Subscribe to ARM/DISARM commands - - Yields - ------- - arm : ArmDisarm - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to ARM/DISARM commands + + Yields + ------- + arm : ArmDisarm + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeArmDisarmRequest() @@ -556,38 +504,37 @@ async def arm_disarm(self): try: async for response in arm_disarm_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "arm_disarm()") if result.result == ActionServerResult.Result.SUCCESS: - arm_disarm_stream.cancel(); + arm_disarm_stream.cancel() return - - yield ArmDisarm.translate_from_rpc(response.arm) finally: arm_disarm_stream.cancel() async def flight_mode_change(self): """ - Subscribe to DO_SET_MODE - - Yields - ------- - flight_mode : FlightMode - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to DO_SET_MODE + + Yields + ------- + flight_mode : FlightMode + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeFlightModeChangeRequest() @@ -595,38 +542,37 @@ async def flight_mode_change(self): try: async for response in flight_mode_change_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "flight_mode_change()") if result.result == ActionServerResult.Result.SUCCESS: - flight_mode_change_stream.cancel(); + flight_mode_change_stream.cancel() return - - yield FlightMode.translate_from_rpc(response.flight_mode) finally: flight_mode_change_stream.cancel() async def takeoff(self): """ - Subscribe to takeoff command - - Yields - ------- - takeoff : bool - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to takeoff command + + Yields + ------- + takeoff : bool + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeTakeoffRequest() @@ -634,38 +580,37 @@ async def takeoff(self): try: async for response in takeoff_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "takeoff()") if result.result == ActionServerResult.Result.SUCCESS: - takeoff_stream.cancel(); + takeoff_stream.cancel() return - - yield response.takeoff finally: takeoff_stream.cancel() async def land(self): """ - Subscribe to land command - - Yields - ------- - land : bool - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to land command + + Yields + ------- + land : bool + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeLandRequest() @@ -673,38 +618,37 @@ async def land(self): try: async for response in land_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "land()") if result.result == ActionServerResult.Result.SUCCESS: - land_stream.cancel(); + land_stream.cancel() return - - yield response.land finally: land_stream.cancel() async def reboot(self): """ - Subscribe to reboot command - - Yields - ------- - reboot : bool - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to reboot command + + Yields + ------- + reboot : bool + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeRebootRequest() @@ -712,38 +656,37 @@ async def reboot(self): try: async for response in reboot_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "reboot()") if result.result == ActionServerResult.Result.SUCCESS: - reboot_stream.cancel(); + reboot_stream.cancel() return - - yield response.reboot finally: reboot_stream.cancel() async def shutdown(self): """ - Subscribe to shutdown command - - Yields - ------- - shutdown : bool - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to shutdown command + + Yields + ------- + shutdown : bool + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeShutdownRequest() @@ -751,38 +694,37 @@ async def shutdown(self): try: async for response in shutdown_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "shutdown()") if result.result == ActionServerResult.Result.SUCCESS: - shutdown_stream.cancel(); + shutdown_stream.cancel() return - - yield response.shutdown finally: shutdown_stream.cancel() async def terminate(self): """ - Subscribe to terminate command - - Yields - ------- - terminate : bool - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Subscribe to terminate command + + Yields + ------- + terminate : bool + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SubscribeTerminateRequest() @@ -790,68 +732,65 @@ async def terminate(self): try: async for response in terminate_stream: - result = self._extract_result(response) success_codes = [ActionServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in ActionServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in ActionServerResult.Result + ]: success_codes.append(ActionServerResult.Result.NEXT) if result.result not in success_codes: raise ActionServerError(result, "terminate()") if result.result == ActionServerResult.Result.SUCCESS: - terminate_stream.cancel(); + terminate_stream.cancel() return - - yield response.terminate finally: terminate_stream.cancel() async def set_allow_takeoff(self, allow_takeoff): """ - Can the vehicle takeoff + Can the vehicle takeoff - Parameters - ---------- - allow_takeoff : bool - Is takeoff allowed? + Parameters + ---------- + allow_takeoff : bool + Is takeoff allowed? - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SetAllowTakeoffRequest() request.allow_takeoff = allow_takeoff response = await self._stub.SetAllowTakeoff(request) - result = self._extract_result(response) if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_allow_takeoff()", allow_takeoff) - async def set_armable(self, armable, force_armable): """ - Can the vehicle arm when requested + Can the vehicle arm when requested - Parameters - ---------- - armable : bool - Is Armable now? + Parameters + ---------- + armable : bool + Is Armable now? - force_armable : bool - Is armable with force? + force_armable : bool + Is armable with force? - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SetArmableRequest() @@ -859,29 +798,27 @@ async def set_armable(self, armable, force_armable): request.force_armable = force_armable response = await self._stub.SetArmable(request) - result = self._extract_result(response) if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_armable()", armable, force_armable) - async def set_disarmable(self, disarmable, force_disarmable): """ - Can the vehicle disarm when requested + Can the vehicle disarm when requested - Parameters - ---------- - disarmable : bool - Is disarmable now? + Parameters + ---------- + disarmable : bool + Is disarmable now? - force_disarmable : bool - Is disarmable with force? (Kill) + force_disarmable : bool + Is disarmable with force? (Kill) - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SetDisarmableRequest() @@ -889,111 +826,102 @@ async def set_disarmable(self, disarmable, force_disarmable): request.force_disarmable = force_disarmable response = await self._stub.SetDisarmable(request) - result = self._extract_result(response) if result.result != ActionServerResult.Result.SUCCESS: - raise ActionServerError(result, "set_disarmable()", disarmable, force_disarmable) - + raise ActionServerError( + result, "set_disarmable()", disarmable, force_disarmable + ) async def set_allowable_flight_modes(self, flight_modes): """ - Set which modes the vehicle can transition to (Manual always allowed) - - Parameters - ---------- - flight_modes : AllowableFlightModes - - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Set which modes the vehicle can transition to (Manual always allowed) + + Parameters + ---------- + flight_modes : AllowableFlightModes + + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SetAllowableFlightModesRequest() - + flight_modes.translate_to_rpc(request.flight_modes) - - + response = await self._stub.SetAllowableFlightModes(request) - result = self._extract_result(response) if result.result != ActionServerResult.Result.SUCCESS: - raise ActionServerError(result, "set_allowable_flight_modes()", flight_modes) - + raise ActionServerError( + result, "set_allowable_flight_modes()", flight_modes + ) async def get_allowable_flight_modes(self): """ - Get which modes the vehicle can transition to (Manual always allowed) + Get which modes the vehicle can transition to (Manual always allowed) + + Returns + ------- + flight_modes : AllowableFlightModes + - Returns - ------- - flight_modes : AllowableFlightModes - - """ request = action_server_pb2.GetAllowableFlightModesRequest() response = await self._stub.GetAllowableFlightModes(request) - - return AllowableFlightModes.translate_from_rpc(response.flight_modes) - async def set_armed_state(self, is_armed): """ - Set/override the armed/disarmed state of the vehicle directly, and notify subscribers + Set/override the armed/disarmed state of the vehicle directly, and notify subscribers - Parameters - ---------- - is_armed : bool - Is armed now? + Parameters + ---------- + is_armed : bool + Is armed now? - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SetArmedStateRequest() request.is_armed = is_armed response = await self._stub.SetArmedState(request) - result = self._extract_result(response) if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_armed_state()", is_armed) - async def set_flight_mode(self, flight_mode): """ - Set/override the flight mode of the vehicle directly, and notify subscribers + Set/override the flight mode of the vehicle directly, and notify subscribers - Parameters - ---------- - flight_mode : FlightMode - Current vehicle flight mode, e.g. Takeoff/Mission/Land/etc. + Parameters + ---------- + flight_mode : FlightMode + Current vehicle flight mode, e.g. Takeoff/Mission/Land/etc. - Raises - ------ - ActionServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ActionServerError + If the request fails. The error contains the reason for the failure. """ request = action_server_pb2.SetFlightModeRequest() - + request.flight_mode = flight_mode.translate_to_rpc() - - + response = await self._stub.SetFlightMode(request) - result = self._extract_result(response) if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_flight_mode()", flight_mode) - \ No newline at end of file diff --git a/mavsdk/action_server_pb2.py b/mavsdk/action_server_pb2.py index 62d06415..c40f935d 100644 --- a/mavsdk/action_server_pb2.py +++ b/mavsdk/action_server_pb2.py @@ -4,18 +4,15 @@ # source: action_server/action_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'action_server/action_server.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "action_server/action_server.proto" ) # @@protoc_insertion_point(imports) @@ -25,108 +22,170 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n!action_server/action_server.proto\x12\x18mavsdk.rpc.action_server\x1a\x14mavsdk_options.proto\"/\n\x16SetAllowTakeoffRequest\x12\x15\n\rallow_takeoff\x18\x01 \x01(\x08\";\n\x11SetArmableRequest\x12\x0f\n\x07\x61rmable\x18\x01 \x01(\x08\x12\x15\n\rforce_armable\x18\x02 \x01(\x08\"D\n\x14SetDisarmableRequest\x12\x12\n\ndisarmable\x18\x01 \x01(\x08\x12\x18\n\x10\x66orce_disarmable\x18\x02 \x01(\x08\"f\n\x1eSetAllowableFlightModesRequest\x12\x44\n\x0c\x66light_modes\x18\x01 \x01(\x0b\x32..mavsdk.rpc.action_server.AllowableFlightModes\"(\n\x14SetArmedStateRequest\x12\x10\n\x08is_armed\x18\x01 \x01(\x08\"Q\n\x14SetFlightModeRequest\x12\x39\n\x0b\x66light_mode\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.action_server.FlightMode\" \n\x1eGetAllowableFlightModesRequest\"\x1b\n\x19SubscribeArmDisarmRequest\"\"\n SubscribeFlightModeChangeRequest\"\x19\n\x17SubscribeTakeoffRequest\"\x16\n\x14SubscribeLandRequest\"\x18\n\x16SubscribeRebootRequest\"\x1a\n\x18SubscribeShutdownRequest\"\x1b\n\x19SubscribeTerminateRequest\"\x91\x01\n\x11\x41rmDisarmResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x30\n\x03\x61rm\x18\x02 \x01(\x0b\x32#.mavsdk.rpc.action_server.ArmDisarm\"\xa1\x01\n\x18\x46lightModeChangeResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x39\n\x0b\x66light_mode\x18\x02 \x01(\x0e\x32$.mavsdk.rpc.action_server.FlightMode\"n\n\x0fTakeoffResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x0f\n\x07takeoff\x18\x02 \x01(\x08\"h\n\x0cLandResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x0c\n\x04land\x18\x02 \x01(\x08\"l\n\x0eRebootResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x0e\n\x06reboot\x18\x02 \x01(\x08\"p\n\x10ShutdownResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x10\n\x08shutdown\x18\x02 \x01(\x08\"r\n\x11TerminateResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x11\n\tterminate\x18\x02 \x01(\x08\"`\n\x12SetArmableResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\"c\n\x15SetDisarmableResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\"m\n\x1fSetAllowableFlightModesResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\"e\n\x17SetAllowTakeoffResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\"g\n\x1fGetAllowableFlightModesResponse\x12\x44\n\x0c\x66light_modes\x18\x01 \x01(\x0b\x32..mavsdk.rpc.action_server.AllowableFlightModes\"c\n\x15SetArmedStateResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\"c\n\x15SetFlightModeResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\"b\n\x14\x41llowableFlightModes\x12\x15\n\rcan_auto_mode\x18\x01 \x01(\x08\x12\x17\n\x0f\x63\x61n_guided_mode\x18\x02 \x01(\x08\x12\x1a\n\x12\x63\x61n_stabilize_mode\x18\x03 \x01(\x08\"\'\n\tArmDisarm\x12\x0b\n\x03\x61rm\x18\x01 \x01(\x08\x12\r\n\x05\x66orce\x18\x02 \x01(\x08\"\xe9\x03\n\x12\x41\x63tionServerResult\x12\x43\n\x06result\x18\x01 \x01(\x0e\x32\x33.mavsdk.rpc.action_server.ActionServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xf9\x02\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.\n*RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN\x10\x06\x12$\n RESULT_COMMAND_DENIED_NOT_LANDED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12*\n&RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN\x10\t\x12%\n!RESULT_NO_VTOL_TRANSITION_SUPPORT\x10\n\x12\x1a\n\x16RESULT_PARAMETER_ERROR\x10\x0b\x12\x0f\n\x0bRESULT_NEXT\x10\x0c*\xeb\x02\n\nFlightMode\x12\x17\n\x13\x46LIGHT_MODE_UNKNOWN\x10\x00\x12\x15\n\x11\x46LIGHT_MODE_READY\x10\x01\x12\x17\n\x13\x46LIGHT_MODE_TAKEOFF\x10\x02\x12\x14\n\x10\x46LIGHT_MODE_HOLD\x10\x03\x12\x17\n\x13\x46LIGHT_MODE_MISSION\x10\x04\x12 \n\x1c\x46LIGHT_MODE_RETURN_TO_LAUNCH\x10\x05\x12\x14\n\x10\x46LIGHT_MODE_LAND\x10\x06\x12\x18\n\x14\x46LIGHT_MODE_OFFBOARD\x10\x07\x12\x19\n\x15\x46LIGHT_MODE_FOLLOW_ME\x10\x08\x12\x16\n\x12\x46LIGHT_MODE_MANUAL\x10\t\x12\x16\n\x12\x46LIGHT_MODE_ALTCTL\x10\n\x12\x16\n\x12\x46LIGHT_MODE_POSCTL\x10\x0b\x12\x14\n\x10\x46LIGHT_MODE_ACRO\x10\x0c\x12\x1a\n\x16\x46LIGHT_MODE_STABILIZED\x10\r2\x8d\x0e\n\x13\x41\x63tionServerService\x12~\n\x12SubscribeArmDisarm\x12\x33.mavsdk.rpc.action_server.SubscribeArmDisarmRequest\x1a+.mavsdk.rpc.action_server.ArmDisarmResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x93\x01\n\x19SubscribeFlightModeChange\x12:.mavsdk.rpc.action_server.SubscribeFlightModeChangeRequest\x1a\x32.mavsdk.rpc.action_server.FlightModeChangeResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12x\n\x10SubscribeTakeoff\x12\x31.mavsdk.rpc.action_server.SubscribeTakeoffRequest\x1a).mavsdk.rpc.action_server.TakeoffResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12o\n\rSubscribeLand\x12..mavsdk.rpc.action_server.SubscribeLandRequest\x1a&.mavsdk.rpc.action_server.LandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12u\n\x0fSubscribeReboot\x12\x30.mavsdk.rpc.action_server.SubscribeRebootRequest\x1a(.mavsdk.rpc.action_server.RebootResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12{\n\x11SubscribeShutdown\x12\x32.mavsdk.rpc.action_server.SubscribeShutdownRequest\x1a*.mavsdk.rpc.action_server.ShutdownResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12~\n\x12SubscribeTerminate\x12\x33.mavsdk.rpc.action_server.SubscribeTerminateRequest\x1a+.mavsdk.rpc.action_server.TerminateResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12|\n\x0fSetAllowTakeoff\x12\x30.mavsdk.rpc.action_server.SetAllowTakeoffRequest\x1a\x31.mavsdk.rpc.action_server.SetAllowTakeoffResponse\"\x04\x80\xb5\x18\x01\x12m\n\nSetArmable\x12+.mavsdk.rpc.action_server.SetArmableRequest\x1a,.mavsdk.rpc.action_server.SetArmableResponse\"\x04\x80\xb5\x18\x01\x12v\n\rSetDisarmable\x12..mavsdk.rpc.action_server.SetDisarmableRequest\x1a/.mavsdk.rpc.action_server.SetDisarmableResponse\"\x04\x80\xb5\x18\x01\x12\x94\x01\n\x17SetAllowableFlightModes\x12\x38.mavsdk.rpc.action_server.SetAllowableFlightModesRequest\x1a\x39.mavsdk.rpc.action_server.SetAllowableFlightModesResponse\"\x04\x80\xb5\x18\x01\x12\x94\x01\n\x17GetAllowableFlightModes\x12\x38.mavsdk.rpc.action_server.GetAllowableFlightModesRequest\x1a\x39.mavsdk.rpc.action_server.GetAllowableFlightModesResponse\"\x04\x80\xb5\x18\x01\x12v\n\rSetArmedState\x12..mavsdk.rpc.action_server.SetArmedStateRequest\x1a/.mavsdk.rpc.action_server.SetArmedStateResponse\"\x04\x80\xb5\x18\x01\x12v\n\rSetFlightMode\x12..mavsdk.rpc.action_server.SetFlightModeRequest\x1a/.mavsdk.rpc.action_server.SetFlightModeResponse\"\x04\x80\xb5\x18\x01\x42,\n\x17io.mavsdk.action_serverB\x11\x41\x63tionServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n!action_server/action_server.proto\x12\x18mavsdk.rpc.action_server\x1a\x14mavsdk_options.proto"/\n\x16SetAllowTakeoffRequest\x12\x15\n\rallow_takeoff\x18\x01 \x01(\x08";\n\x11SetArmableRequest\x12\x0f\n\x07\x61rmable\x18\x01 \x01(\x08\x12\x15\n\rforce_armable\x18\x02 \x01(\x08"D\n\x14SetDisarmableRequest\x12\x12\n\ndisarmable\x18\x01 \x01(\x08\x12\x18\n\x10\x66orce_disarmable\x18\x02 \x01(\x08"f\n\x1eSetAllowableFlightModesRequest\x12\x44\n\x0c\x66light_modes\x18\x01 \x01(\x0b\x32..mavsdk.rpc.action_server.AllowableFlightModes"(\n\x14SetArmedStateRequest\x12\x10\n\x08is_armed\x18\x01 \x01(\x08"Q\n\x14SetFlightModeRequest\x12\x39\n\x0b\x66light_mode\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.action_server.FlightMode" \n\x1eGetAllowableFlightModesRequest"\x1b\n\x19SubscribeArmDisarmRequest""\n SubscribeFlightModeChangeRequest"\x19\n\x17SubscribeTakeoffRequest"\x16\n\x14SubscribeLandRequest"\x18\n\x16SubscribeRebootRequest"\x1a\n\x18SubscribeShutdownRequest"\x1b\n\x19SubscribeTerminateRequest"\x91\x01\n\x11\x41rmDisarmResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x30\n\x03\x61rm\x18\x02 \x01(\x0b\x32#.mavsdk.rpc.action_server.ArmDisarm"\xa1\x01\n\x18\x46lightModeChangeResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x39\n\x0b\x66light_mode\x18\x02 \x01(\x0e\x32$.mavsdk.rpc.action_server.FlightMode"n\n\x0fTakeoffResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x0f\n\x07takeoff\x18\x02 \x01(\x08"h\n\x0cLandResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x0c\n\x04land\x18\x02 \x01(\x08"l\n\x0eRebootResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x0e\n\x06reboot\x18\x02 \x01(\x08"p\n\x10ShutdownResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x10\n\x08shutdown\x18\x02 \x01(\x08"r\n\x11TerminateResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult\x12\x11\n\tterminate\x18\x02 \x01(\x08"`\n\x12SetArmableResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult"c\n\x15SetDisarmableResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult"m\n\x1fSetAllowableFlightModesResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult"e\n\x17SetAllowTakeoffResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult"g\n\x1fGetAllowableFlightModesResponse\x12\x44\n\x0c\x66light_modes\x18\x01 \x01(\x0b\x32..mavsdk.rpc.action_server.AllowableFlightModes"c\n\x15SetArmedStateResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult"c\n\x15SetFlightModeResponse\x12J\n\x14\x61\x63tion_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.action_server.ActionServerResult"b\n\x14\x41llowableFlightModes\x12\x15\n\rcan_auto_mode\x18\x01 \x01(\x08\x12\x17\n\x0f\x63\x61n_guided_mode\x18\x02 \x01(\x08\x12\x1a\n\x12\x63\x61n_stabilize_mode\x18\x03 \x01(\x08"\'\n\tArmDisarm\x12\x0b\n\x03\x61rm\x18\x01 \x01(\x08\x12\r\n\x05\x66orce\x18\x02 \x01(\x08"\xe9\x03\n\x12\x41\x63tionServerResult\x12\x43\n\x06result\x18\x01 \x01(\x0e\x32\x33.mavsdk.rpc.action_server.ActionServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xf9\x02\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.\n*RESULT_COMMAND_DENIED_LANDED_STATE_UNKNOWN\x10\x06\x12$\n RESULT_COMMAND_DENIED_NOT_LANDED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12*\n&RESULT_VTOL_TRANSITION_SUPPORT_UNKNOWN\x10\t\x12%\n!RESULT_NO_VTOL_TRANSITION_SUPPORT\x10\n\x12\x1a\n\x16RESULT_PARAMETER_ERROR\x10\x0b\x12\x0f\n\x0bRESULT_NEXT\x10\x0c*\xeb\x02\n\nFlightMode\x12\x17\n\x13\x46LIGHT_MODE_UNKNOWN\x10\x00\x12\x15\n\x11\x46LIGHT_MODE_READY\x10\x01\x12\x17\n\x13\x46LIGHT_MODE_TAKEOFF\x10\x02\x12\x14\n\x10\x46LIGHT_MODE_HOLD\x10\x03\x12\x17\n\x13\x46LIGHT_MODE_MISSION\x10\x04\x12 \n\x1c\x46LIGHT_MODE_RETURN_TO_LAUNCH\x10\x05\x12\x14\n\x10\x46LIGHT_MODE_LAND\x10\x06\x12\x18\n\x14\x46LIGHT_MODE_OFFBOARD\x10\x07\x12\x19\n\x15\x46LIGHT_MODE_FOLLOW_ME\x10\x08\x12\x16\n\x12\x46LIGHT_MODE_MANUAL\x10\t\x12\x16\n\x12\x46LIGHT_MODE_ALTCTL\x10\n\x12\x16\n\x12\x46LIGHT_MODE_POSCTL\x10\x0b\x12\x14\n\x10\x46LIGHT_MODE_ACRO\x10\x0c\x12\x1a\n\x16\x46LIGHT_MODE_STABILIZED\x10\r2\x8d\x0e\n\x13\x41\x63tionServerService\x12~\n\x12SubscribeArmDisarm\x12\x33.mavsdk.rpc.action_server.SubscribeArmDisarmRequest\x1a+.mavsdk.rpc.action_server.ArmDisarmResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x93\x01\n\x19SubscribeFlightModeChange\x12:.mavsdk.rpc.action_server.SubscribeFlightModeChangeRequest\x1a\x32.mavsdk.rpc.action_server.FlightModeChangeResponse"\x04\x80\xb5\x18\x00\x30\x01\x12x\n\x10SubscribeTakeoff\x12\x31.mavsdk.rpc.action_server.SubscribeTakeoffRequest\x1a).mavsdk.rpc.action_server.TakeoffResponse"\x04\x80\xb5\x18\x00\x30\x01\x12o\n\rSubscribeLand\x12..mavsdk.rpc.action_server.SubscribeLandRequest\x1a&.mavsdk.rpc.action_server.LandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12u\n\x0fSubscribeReboot\x12\x30.mavsdk.rpc.action_server.SubscribeRebootRequest\x1a(.mavsdk.rpc.action_server.RebootResponse"\x04\x80\xb5\x18\x00\x30\x01\x12{\n\x11SubscribeShutdown\x12\x32.mavsdk.rpc.action_server.SubscribeShutdownRequest\x1a*.mavsdk.rpc.action_server.ShutdownResponse"\x04\x80\xb5\x18\x00\x30\x01\x12~\n\x12SubscribeTerminate\x12\x33.mavsdk.rpc.action_server.SubscribeTerminateRequest\x1a+.mavsdk.rpc.action_server.TerminateResponse"\x04\x80\xb5\x18\x00\x30\x01\x12|\n\x0fSetAllowTakeoff\x12\x30.mavsdk.rpc.action_server.SetAllowTakeoffRequest\x1a\x31.mavsdk.rpc.action_server.SetAllowTakeoffResponse"\x04\x80\xb5\x18\x01\x12m\n\nSetArmable\x12+.mavsdk.rpc.action_server.SetArmableRequest\x1a,.mavsdk.rpc.action_server.SetArmableResponse"\x04\x80\xb5\x18\x01\x12v\n\rSetDisarmable\x12..mavsdk.rpc.action_server.SetDisarmableRequest\x1a/.mavsdk.rpc.action_server.SetDisarmableResponse"\x04\x80\xb5\x18\x01\x12\x94\x01\n\x17SetAllowableFlightModes\x12\x38.mavsdk.rpc.action_server.SetAllowableFlightModesRequest\x1a\x39.mavsdk.rpc.action_server.SetAllowableFlightModesResponse"\x04\x80\xb5\x18\x01\x12\x94\x01\n\x17GetAllowableFlightModes\x12\x38.mavsdk.rpc.action_server.GetAllowableFlightModesRequest\x1a\x39.mavsdk.rpc.action_server.GetAllowableFlightModesResponse"\x04\x80\xb5\x18\x01\x12v\n\rSetArmedState\x12..mavsdk.rpc.action_server.SetArmedStateRequest\x1a/.mavsdk.rpc.action_server.SetArmedStateResponse"\x04\x80\xb5\x18\x01\x12v\n\rSetFlightMode\x12..mavsdk.rpc.action_server.SetFlightModeRequest\x1a/.mavsdk.rpc.action_server.SetFlightModeResponse"\x04\x80\xb5\x18\x01\x42,\n\x17io.mavsdk.action_serverB\x11\x41\x63tionServerProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'action_server.action_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "action_server.action_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\027io.mavsdk.action_serverB\021ActionServerProto' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeArmDisarm']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeArmDisarm']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeFlightModeChange']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeFlightModeChange']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeTakeoff']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeTakeoff']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeLand']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeLand']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeReboot']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeReboot']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeShutdown']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeShutdown']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeTerminate']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SubscribeTerminate']._serialized_options = b'\200\265\030\000' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetAllowTakeoff']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetAllowTakeoff']._serialized_options = b'\200\265\030\001' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetArmable']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetArmable']._serialized_options = b'\200\265\030\001' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetDisarmable']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetDisarmable']._serialized_options = b'\200\265\030\001' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetAllowableFlightModes']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetAllowableFlightModes']._serialized_options = b'\200\265\030\001' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['GetAllowableFlightModes']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['GetAllowableFlightModes']._serialized_options = b'\200\265\030\001' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetArmedState']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetArmedState']._serialized_options = b'\200\265\030\001' - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetFlightMode']._loaded_options = None - _globals['_ACTIONSERVERSERVICE'].methods_by_name['SetFlightMode']._serialized_options = b'\200\265\030\001' - _globals['_FLIGHTMODE']._serialized_start=2951 - _globals['_FLIGHTMODE']._serialized_end=3314 - _globals['_SETALLOWTAKEOFFREQUEST']._serialized_start=85 - _globals['_SETALLOWTAKEOFFREQUEST']._serialized_end=132 - _globals['_SETARMABLEREQUEST']._serialized_start=134 - _globals['_SETARMABLEREQUEST']._serialized_end=193 - _globals['_SETDISARMABLEREQUEST']._serialized_start=195 - _globals['_SETDISARMABLEREQUEST']._serialized_end=263 - _globals['_SETALLOWABLEFLIGHTMODESREQUEST']._serialized_start=265 - _globals['_SETALLOWABLEFLIGHTMODESREQUEST']._serialized_end=367 - _globals['_SETARMEDSTATEREQUEST']._serialized_start=369 - _globals['_SETARMEDSTATEREQUEST']._serialized_end=409 - _globals['_SETFLIGHTMODEREQUEST']._serialized_start=411 - _globals['_SETFLIGHTMODEREQUEST']._serialized_end=492 - _globals['_GETALLOWABLEFLIGHTMODESREQUEST']._serialized_start=494 - _globals['_GETALLOWABLEFLIGHTMODESREQUEST']._serialized_end=526 - _globals['_SUBSCRIBEARMDISARMREQUEST']._serialized_start=528 - _globals['_SUBSCRIBEARMDISARMREQUEST']._serialized_end=555 - _globals['_SUBSCRIBEFLIGHTMODECHANGEREQUEST']._serialized_start=557 - _globals['_SUBSCRIBEFLIGHTMODECHANGEREQUEST']._serialized_end=591 - _globals['_SUBSCRIBETAKEOFFREQUEST']._serialized_start=593 - _globals['_SUBSCRIBETAKEOFFREQUEST']._serialized_end=618 - _globals['_SUBSCRIBELANDREQUEST']._serialized_start=620 - _globals['_SUBSCRIBELANDREQUEST']._serialized_end=642 - _globals['_SUBSCRIBEREBOOTREQUEST']._serialized_start=644 - _globals['_SUBSCRIBEREBOOTREQUEST']._serialized_end=668 - _globals['_SUBSCRIBESHUTDOWNREQUEST']._serialized_start=670 - _globals['_SUBSCRIBESHUTDOWNREQUEST']._serialized_end=696 - _globals['_SUBSCRIBETERMINATEREQUEST']._serialized_start=698 - _globals['_SUBSCRIBETERMINATEREQUEST']._serialized_end=725 - _globals['_ARMDISARMRESPONSE']._serialized_start=728 - _globals['_ARMDISARMRESPONSE']._serialized_end=873 - _globals['_FLIGHTMODECHANGERESPONSE']._serialized_start=876 - _globals['_FLIGHTMODECHANGERESPONSE']._serialized_end=1037 - _globals['_TAKEOFFRESPONSE']._serialized_start=1039 - _globals['_TAKEOFFRESPONSE']._serialized_end=1149 - _globals['_LANDRESPONSE']._serialized_start=1151 - _globals['_LANDRESPONSE']._serialized_end=1255 - _globals['_REBOOTRESPONSE']._serialized_start=1257 - _globals['_REBOOTRESPONSE']._serialized_end=1365 - _globals['_SHUTDOWNRESPONSE']._serialized_start=1367 - _globals['_SHUTDOWNRESPONSE']._serialized_end=1479 - _globals['_TERMINATERESPONSE']._serialized_start=1481 - _globals['_TERMINATERESPONSE']._serialized_end=1595 - _globals['_SETARMABLERESPONSE']._serialized_start=1597 - _globals['_SETARMABLERESPONSE']._serialized_end=1693 - _globals['_SETDISARMABLERESPONSE']._serialized_start=1695 - _globals['_SETDISARMABLERESPONSE']._serialized_end=1794 - _globals['_SETALLOWABLEFLIGHTMODESRESPONSE']._serialized_start=1796 - _globals['_SETALLOWABLEFLIGHTMODESRESPONSE']._serialized_end=1905 - _globals['_SETALLOWTAKEOFFRESPONSE']._serialized_start=1907 - _globals['_SETALLOWTAKEOFFRESPONSE']._serialized_end=2008 - _globals['_GETALLOWABLEFLIGHTMODESRESPONSE']._serialized_start=2010 - _globals['_GETALLOWABLEFLIGHTMODESRESPONSE']._serialized_end=2113 - _globals['_SETARMEDSTATERESPONSE']._serialized_start=2115 - _globals['_SETARMEDSTATERESPONSE']._serialized_end=2214 - _globals['_SETFLIGHTMODERESPONSE']._serialized_start=2216 - _globals['_SETFLIGHTMODERESPONSE']._serialized_end=2315 - _globals['_ALLOWABLEFLIGHTMODES']._serialized_start=2317 - _globals['_ALLOWABLEFLIGHTMODES']._serialized_end=2415 - _globals['_ARMDISARM']._serialized_start=2417 - _globals['_ARMDISARM']._serialized_end=2456 - _globals['_ACTIONSERVERRESULT']._serialized_start=2459 - _globals['_ACTIONSERVERRESULT']._serialized_end=2948 - _globals['_ACTIONSERVERRESULT_RESULT']._serialized_start=2571 - _globals['_ACTIONSERVERRESULT_RESULT']._serialized_end=2948 - _globals['_ACTIONSERVERSERVICE']._serialized_start=3317 - _globals['_ACTIONSERVERSERVICE']._serialized_end=5122 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\027io.mavsdk.action_serverB\021ActionServerProto" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeArmDisarm" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeArmDisarm" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeFlightModeChange" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeFlightModeChange" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeTakeoff" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeTakeoff" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeLand" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeLand" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeReboot" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeReboot" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeShutdown" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeShutdown" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeTerminate" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SubscribeTerminate" + ]._serialized_options = b"\200\265\030\000" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetAllowTakeoff" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetAllowTakeoff" + ]._serialized_options = b"\200\265\030\001" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetArmable" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetArmable" + ]._serialized_options = b"\200\265\030\001" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetDisarmable" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetDisarmable" + ]._serialized_options = b"\200\265\030\001" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetAllowableFlightModes" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetAllowableFlightModes" + ]._serialized_options = b"\200\265\030\001" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "GetAllowableFlightModes" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "GetAllowableFlightModes" + ]._serialized_options = b"\200\265\030\001" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetArmedState" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetArmedState" + ]._serialized_options = b"\200\265\030\001" + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetFlightMode" + ]._loaded_options = None + _globals["_ACTIONSERVERSERVICE"].methods_by_name[ + "SetFlightMode" + ]._serialized_options = b"\200\265\030\001" + _globals["_FLIGHTMODE"]._serialized_start = 2951 + _globals["_FLIGHTMODE"]._serialized_end = 3314 + _globals["_SETALLOWTAKEOFFREQUEST"]._serialized_start = 85 + _globals["_SETALLOWTAKEOFFREQUEST"]._serialized_end = 132 + _globals["_SETARMABLEREQUEST"]._serialized_start = 134 + _globals["_SETARMABLEREQUEST"]._serialized_end = 193 + _globals["_SETDISARMABLEREQUEST"]._serialized_start = 195 + _globals["_SETDISARMABLEREQUEST"]._serialized_end = 263 + _globals["_SETALLOWABLEFLIGHTMODESREQUEST"]._serialized_start = 265 + _globals["_SETALLOWABLEFLIGHTMODESREQUEST"]._serialized_end = 367 + _globals["_SETARMEDSTATEREQUEST"]._serialized_start = 369 + _globals["_SETARMEDSTATEREQUEST"]._serialized_end = 409 + _globals["_SETFLIGHTMODEREQUEST"]._serialized_start = 411 + _globals["_SETFLIGHTMODEREQUEST"]._serialized_end = 492 + _globals["_GETALLOWABLEFLIGHTMODESREQUEST"]._serialized_start = 494 + _globals["_GETALLOWABLEFLIGHTMODESREQUEST"]._serialized_end = 526 + _globals["_SUBSCRIBEARMDISARMREQUEST"]._serialized_start = 528 + _globals["_SUBSCRIBEARMDISARMREQUEST"]._serialized_end = 555 + _globals["_SUBSCRIBEFLIGHTMODECHANGEREQUEST"]._serialized_start = 557 + _globals["_SUBSCRIBEFLIGHTMODECHANGEREQUEST"]._serialized_end = 591 + _globals["_SUBSCRIBETAKEOFFREQUEST"]._serialized_start = 593 + _globals["_SUBSCRIBETAKEOFFREQUEST"]._serialized_end = 618 + _globals["_SUBSCRIBELANDREQUEST"]._serialized_start = 620 + _globals["_SUBSCRIBELANDREQUEST"]._serialized_end = 642 + _globals["_SUBSCRIBEREBOOTREQUEST"]._serialized_start = 644 + _globals["_SUBSCRIBEREBOOTREQUEST"]._serialized_end = 668 + _globals["_SUBSCRIBESHUTDOWNREQUEST"]._serialized_start = 670 + _globals["_SUBSCRIBESHUTDOWNREQUEST"]._serialized_end = 696 + _globals["_SUBSCRIBETERMINATEREQUEST"]._serialized_start = 698 + _globals["_SUBSCRIBETERMINATEREQUEST"]._serialized_end = 725 + _globals["_ARMDISARMRESPONSE"]._serialized_start = 728 + _globals["_ARMDISARMRESPONSE"]._serialized_end = 873 + _globals["_FLIGHTMODECHANGERESPONSE"]._serialized_start = 876 + _globals["_FLIGHTMODECHANGERESPONSE"]._serialized_end = 1037 + _globals["_TAKEOFFRESPONSE"]._serialized_start = 1039 + _globals["_TAKEOFFRESPONSE"]._serialized_end = 1149 + _globals["_LANDRESPONSE"]._serialized_start = 1151 + _globals["_LANDRESPONSE"]._serialized_end = 1255 + _globals["_REBOOTRESPONSE"]._serialized_start = 1257 + _globals["_REBOOTRESPONSE"]._serialized_end = 1365 + _globals["_SHUTDOWNRESPONSE"]._serialized_start = 1367 + _globals["_SHUTDOWNRESPONSE"]._serialized_end = 1479 + _globals["_TERMINATERESPONSE"]._serialized_start = 1481 + _globals["_TERMINATERESPONSE"]._serialized_end = 1595 + _globals["_SETARMABLERESPONSE"]._serialized_start = 1597 + _globals["_SETARMABLERESPONSE"]._serialized_end = 1693 + _globals["_SETDISARMABLERESPONSE"]._serialized_start = 1695 + _globals["_SETDISARMABLERESPONSE"]._serialized_end = 1794 + _globals["_SETALLOWABLEFLIGHTMODESRESPONSE"]._serialized_start = 1796 + _globals["_SETALLOWABLEFLIGHTMODESRESPONSE"]._serialized_end = 1905 + _globals["_SETALLOWTAKEOFFRESPONSE"]._serialized_start = 1907 + _globals["_SETALLOWTAKEOFFRESPONSE"]._serialized_end = 2008 + _globals["_GETALLOWABLEFLIGHTMODESRESPONSE"]._serialized_start = 2010 + _globals["_GETALLOWABLEFLIGHTMODESRESPONSE"]._serialized_end = 2113 + _globals["_SETARMEDSTATERESPONSE"]._serialized_start = 2115 + _globals["_SETARMEDSTATERESPONSE"]._serialized_end = 2214 + _globals["_SETFLIGHTMODERESPONSE"]._serialized_start = 2216 + _globals["_SETFLIGHTMODERESPONSE"]._serialized_end = 2315 + _globals["_ALLOWABLEFLIGHTMODES"]._serialized_start = 2317 + _globals["_ALLOWABLEFLIGHTMODES"]._serialized_end = 2415 + _globals["_ARMDISARM"]._serialized_start = 2417 + _globals["_ARMDISARM"]._serialized_end = 2456 + _globals["_ACTIONSERVERRESULT"]._serialized_start = 2459 + _globals["_ACTIONSERVERRESULT"]._serialized_end = 2948 + _globals["_ACTIONSERVERRESULT_RESULT"]._serialized_start = 2571 + _globals["_ACTIONSERVERRESULT_RESULT"]._serialized_end = 2948 + _globals["_ACTIONSERVERSERVICE"]._serialized_start = 3317 + _globals["_ACTIONSERVERSERVICE"]._serialized_end = 5122 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/action_server_pb2_grpc.py b/mavsdk/action_server_pb2_grpc.py index ffc2d0cf..5cd936ad 100644 --- a/mavsdk/action_server_pb2_grpc.py +++ b/mavsdk/action_server_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import action_server_pb2 as action__server_dot_action__server__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in action_server/action_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in action_server/action_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ActionServerServiceStub(object): - """Provide vehicle actions (as a server) such as arming, taking off, and landing. - """ + """Provide vehicle actions (as a server) such as arming, taking off, and landing.""" def __init__(self, channel): """Constructor. @@ -36,279 +39,282 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeArmDisarm = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeArmDisarm', - request_serializer=action__server_dot_action__server__pb2.SubscribeArmDisarmRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.ArmDisarmResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeArmDisarm", + request_serializer=action__server_dot_action__server__pb2.SubscribeArmDisarmRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.ArmDisarmResponse.FromString, + _registered_method=True, + ) self.SubscribeFlightModeChange = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeFlightModeChange', - request_serializer=action__server_dot_action__server__pb2.SubscribeFlightModeChangeRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.FlightModeChangeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeFlightModeChange", + request_serializer=action__server_dot_action__server__pb2.SubscribeFlightModeChangeRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.FlightModeChangeResponse.FromString, + _registered_method=True, + ) self.SubscribeTakeoff = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeTakeoff', - request_serializer=action__server_dot_action__server__pb2.SubscribeTakeoffRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.TakeoffResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeTakeoff", + request_serializer=action__server_dot_action__server__pb2.SubscribeTakeoffRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.TakeoffResponse.FromString, + _registered_method=True, + ) self.SubscribeLand = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeLand', - request_serializer=action__server_dot_action__server__pb2.SubscribeLandRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.LandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeLand", + request_serializer=action__server_dot_action__server__pb2.SubscribeLandRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.LandResponse.FromString, + _registered_method=True, + ) self.SubscribeReboot = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeReboot', - request_serializer=action__server_dot_action__server__pb2.SubscribeRebootRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.RebootResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeReboot", + request_serializer=action__server_dot_action__server__pb2.SubscribeRebootRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.RebootResponse.FromString, + _registered_method=True, + ) self.SubscribeShutdown = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeShutdown', - request_serializer=action__server_dot_action__server__pb2.SubscribeShutdownRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.ShutdownResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeShutdown", + request_serializer=action__server_dot_action__server__pb2.SubscribeShutdownRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.ShutdownResponse.FromString, + _registered_method=True, + ) self.SubscribeTerminate = channel.unary_stream( - '/mavsdk.rpc.action_server.ActionServerService/SubscribeTerminate', - request_serializer=action__server_dot_action__server__pb2.SubscribeTerminateRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.TerminateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SubscribeTerminate", + request_serializer=action__server_dot_action__server__pb2.SubscribeTerminateRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.TerminateResponse.FromString, + _registered_method=True, + ) self.SetAllowTakeoff = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/SetAllowTakeoff', - request_serializer=action__server_dot_action__server__pb2.SetAllowTakeoffRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.SetAllowTakeoffResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SetAllowTakeoff", + request_serializer=action__server_dot_action__server__pb2.SetAllowTakeoffRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.SetAllowTakeoffResponse.FromString, + _registered_method=True, + ) self.SetArmable = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/SetArmable', - request_serializer=action__server_dot_action__server__pb2.SetArmableRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.SetArmableResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SetArmable", + request_serializer=action__server_dot_action__server__pb2.SetArmableRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.SetArmableResponse.FromString, + _registered_method=True, + ) self.SetDisarmable = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/SetDisarmable', - request_serializer=action__server_dot_action__server__pb2.SetDisarmableRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.SetDisarmableResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SetDisarmable", + request_serializer=action__server_dot_action__server__pb2.SetDisarmableRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.SetDisarmableResponse.FromString, + _registered_method=True, + ) self.SetAllowableFlightModes = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/SetAllowableFlightModes', - request_serializer=action__server_dot_action__server__pb2.SetAllowableFlightModesRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.SetAllowableFlightModesResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SetAllowableFlightModes", + request_serializer=action__server_dot_action__server__pb2.SetAllowableFlightModesRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.SetAllowableFlightModesResponse.FromString, + _registered_method=True, + ) self.GetAllowableFlightModes = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/GetAllowableFlightModes', - request_serializer=action__server_dot_action__server__pb2.GetAllowableFlightModesRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.GetAllowableFlightModesResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/GetAllowableFlightModes", + request_serializer=action__server_dot_action__server__pb2.GetAllowableFlightModesRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.GetAllowableFlightModesResponse.FromString, + _registered_method=True, + ) self.SetArmedState = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/SetArmedState', - request_serializer=action__server_dot_action__server__pb2.SetArmedStateRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.SetArmedStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SetArmedState", + request_serializer=action__server_dot_action__server__pb2.SetArmedStateRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.SetArmedStateResponse.FromString, + _registered_method=True, + ) self.SetFlightMode = channel.unary_unary( - '/mavsdk.rpc.action_server.ActionServerService/SetFlightMode', - request_serializer=action__server_dot_action__server__pb2.SetFlightModeRequest.SerializeToString, - response_deserializer=action__server_dot_action__server__pb2.SetFlightModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.action_server.ActionServerService/SetFlightMode", + request_serializer=action__server_dot_action__server__pb2.SetFlightModeRequest.SerializeToString, + response_deserializer=action__server_dot_action__server__pb2.SetFlightModeResponse.FromString, + _registered_method=True, + ) class ActionServerServiceServicer(object): - """Provide vehicle actions (as a server) such as arming, taking off, and landing. - """ + """Provide vehicle actions (as a server) such as arming, taking off, and landing.""" def SubscribeArmDisarm(self, request, context): - """Subscribe to ARM/DISARM commands - """ + """Subscribe to ARM/DISARM commands""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFlightModeChange(self, request, context): - """Subscribe to DO_SET_MODE - """ + """Subscribe to DO_SET_MODE""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTakeoff(self, request, context): - """Subscribe to takeoff command - """ + """Subscribe to takeoff command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeLand(self, request, context): - """Subscribe to land command - """ + """Subscribe to land command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeReboot(self, request, context): - """Subscribe to reboot command - """ + """Subscribe to reboot command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeShutdown(self, request, context): - """Subscribe to shutdown command - """ + """Subscribe to shutdown command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTerminate(self, request, context): - """Subscribe to terminate command - """ + """Subscribe to terminate command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAllowTakeoff(self, request, context): - """Can the vehicle takeoff - """ + """Can the vehicle takeoff""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetArmable(self, request, context): - """Can the vehicle arm when requested - """ + """Can the vehicle arm when requested""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetDisarmable(self, request, context): - """Can the vehicle disarm when requested - """ + """Can the vehicle disarm when requested""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAllowableFlightModes(self, request, context): - """Set which modes the vehicle can transition to (Manual always allowed) - """ + """Set which modes the vehicle can transition to (Manual always allowed)""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetAllowableFlightModes(self, request, context): - """Get which modes the vehicle can transition to (Manual always allowed) - """ + """Get which modes the vehicle can transition to (Manual always allowed)""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetArmedState(self, request, context): - """Set/override the armed/disarmed state of the vehicle directly, and notify subscribers - """ + """Set/override the armed/disarmed state of the vehicle directly, and notify subscribers""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetFlightMode(self, request, context): - """Set/override the flight mode of the vehicle directly, and notify subscribers - """ + """Set/override the flight mode of the vehicle directly, and notify subscribers""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ActionServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeArmDisarm': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeArmDisarm, - request_deserializer=action__server_dot_action__server__pb2.SubscribeArmDisarmRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.ArmDisarmResponse.SerializeToString, - ), - 'SubscribeFlightModeChange': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFlightModeChange, - request_deserializer=action__server_dot_action__server__pb2.SubscribeFlightModeChangeRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.FlightModeChangeResponse.SerializeToString, - ), - 'SubscribeTakeoff': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTakeoff, - request_deserializer=action__server_dot_action__server__pb2.SubscribeTakeoffRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.TakeoffResponse.SerializeToString, - ), - 'SubscribeLand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeLand, - request_deserializer=action__server_dot_action__server__pb2.SubscribeLandRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.LandResponse.SerializeToString, - ), - 'SubscribeReboot': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeReboot, - request_deserializer=action__server_dot_action__server__pb2.SubscribeRebootRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.RebootResponse.SerializeToString, - ), - 'SubscribeShutdown': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeShutdown, - request_deserializer=action__server_dot_action__server__pb2.SubscribeShutdownRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.ShutdownResponse.SerializeToString, - ), - 'SubscribeTerminate': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTerminate, - request_deserializer=action__server_dot_action__server__pb2.SubscribeTerminateRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.TerminateResponse.SerializeToString, - ), - 'SetAllowTakeoff': grpc.unary_unary_rpc_method_handler( - servicer.SetAllowTakeoff, - request_deserializer=action__server_dot_action__server__pb2.SetAllowTakeoffRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.SetAllowTakeoffResponse.SerializeToString, - ), - 'SetArmable': grpc.unary_unary_rpc_method_handler( - servicer.SetArmable, - request_deserializer=action__server_dot_action__server__pb2.SetArmableRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.SetArmableResponse.SerializeToString, - ), - 'SetDisarmable': grpc.unary_unary_rpc_method_handler( - servicer.SetDisarmable, - request_deserializer=action__server_dot_action__server__pb2.SetDisarmableRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.SetDisarmableResponse.SerializeToString, - ), - 'SetAllowableFlightModes': grpc.unary_unary_rpc_method_handler( - servicer.SetAllowableFlightModes, - request_deserializer=action__server_dot_action__server__pb2.SetAllowableFlightModesRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.SetAllowableFlightModesResponse.SerializeToString, - ), - 'GetAllowableFlightModes': grpc.unary_unary_rpc_method_handler( - servicer.GetAllowableFlightModes, - request_deserializer=action__server_dot_action__server__pb2.GetAllowableFlightModesRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.GetAllowableFlightModesResponse.SerializeToString, - ), - 'SetArmedState': grpc.unary_unary_rpc_method_handler( - servicer.SetArmedState, - request_deserializer=action__server_dot_action__server__pb2.SetArmedStateRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.SetArmedStateResponse.SerializeToString, - ), - 'SetFlightMode': grpc.unary_unary_rpc_method_handler( - servicer.SetFlightMode, - request_deserializer=action__server_dot_action__server__pb2.SetFlightModeRequest.FromString, - response_serializer=action__server_dot_action__server__pb2.SetFlightModeResponse.SerializeToString, - ), + "SubscribeArmDisarm": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeArmDisarm, + request_deserializer=action__server_dot_action__server__pb2.SubscribeArmDisarmRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.ArmDisarmResponse.SerializeToString, + ), + "SubscribeFlightModeChange": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFlightModeChange, + request_deserializer=action__server_dot_action__server__pb2.SubscribeFlightModeChangeRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.FlightModeChangeResponse.SerializeToString, + ), + "SubscribeTakeoff": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTakeoff, + request_deserializer=action__server_dot_action__server__pb2.SubscribeTakeoffRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.TakeoffResponse.SerializeToString, + ), + "SubscribeLand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeLand, + request_deserializer=action__server_dot_action__server__pb2.SubscribeLandRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.LandResponse.SerializeToString, + ), + "SubscribeReboot": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeReboot, + request_deserializer=action__server_dot_action__server__pb2.SubscribeRebootRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.RebootResponse.SerializeToString, + ), + "SubscribeShutdown": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeShutdown, + request_deserializer=action__server_dot_action__server__pb2.SubscribeShutdownRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.ShutdownResponse.SerializeToString, + ), + "SubscribeTerminate": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTerminate, + request_deserializer=action__server_dot_action__server__pb2.SubscribeTerminateRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.TerminateResponse.SerializeToString, + ), + "SetAllowTakeoff": grpc.unary_unary_rpc_method_handler( + servicer.SetAllowTakeoff, + request_deserializer=action__server_dot_action__server__pb2.SetAllowTakeoffRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.SetAllowTakeoffResponse.SerializeToString, + ), + "SetArmable": grpc.unary_unary_rpc_method_handler( + servicer.SetArmable, + request_deserializer=action__server_dot_action__server__pb2.SetArmableRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.SetArmableResponse.SerializeToString, + ), + "SetDisarmable": grpc.unary_unary_rpc_method_handler( + servicer.SetDisarmable, + request_deserializer=action__server_dot_action__server__pb2.SetDisarmableRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.SetDisarmableResponse.SerializeToString, + ), + "SetAllowableFlightModes": grpc.unary_unary_rpc_method_handler( + servicer.SetAllowableFlightModes, + request_deserializer=action__server_dot_action__server__pb2.SetAllowableFlightModesRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.SetAllowableFlightModesResponse.SerializeToString, + ), + "GetAllowableFlightModes": grpc.unary_unary_rpc_method_handler( + servicer.GetAllowableFlightModes, + request_deserializer=action__server_dot_action__server__pb2.GetAllowableFlightModesRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.GetAllowableFlightModesResponse.SerializeToString, + ), + "SetArmedState": grpc.unary_unary_rpc_method_handler( + servicer.SetArmedState, + request_deserializer=action__server_dot_action__server__pb2.SetArmedStateRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.SetArmedStateResponse.SerializeToString, + ), + "SetFlightMode": grpc.unary_unary_rpc_method_handler( + servicer.SetFlightMode, + request_deserializer=action__server_dot_action__server__pb2.SetFlightModeRequest.FromString, + response_serializer=action__server_dot_action__server__pb2.SetFlightModeResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.action_server.ActionServerService', rpc_method_handlers) + "mavsdk.rpc.action_server.ActionServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.action_server.ActionServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.action_server.ActionServerService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ActionServerService(object): - """Provide vehicle actions (as a server) such as arming, taking off, and landing. - """ + """Provide vehicle actions (as a server) such as arming, taking off, and landing.""" @staticmethod - def SubscribeArmDisarm(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeArmDisarm( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeArmDisarm', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeArmDisarm", action__server_dot_action__server__pb2.SubscribeArmDisarmRequest.SerializeToString, action__server_dot_action__server__pb2.ArmDisarmResponse.FromString, options, @@ -319,23 +325,26 @@ def SubscribeArmDisarm(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeFlightModeChange(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeFlightModeChange( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeFlightModeChange', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeFlightModeChange", action__server_dot_action__server__pb2.SubscribeFlightModeChangeRequest.SerializeToString, action__server_dot_action__server__pb2.FlightModeChangeResponse.FromString, options, @@ -346,23 +355,26 @@ def SubscribeFlightModeChange(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeTakeoff(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTakeoff( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeTakeoff', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeTakeoff", action__server_dot_action__server__pb2.SubscribeTakeoffRequest.SerializeToString, action__server_dot_action__server__pb2.TakeoffResponse.FromString, options, @@ -373,23 +385,26 @@ def SubscribeTakeoff(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeLand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeLand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeLand', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeLand", action__server_dot_action__server__pb2.SubscribeLandRequest.SerializeToString, action__server_dot_action__server__pb2.LandResponse.FromString, options, @@ -400,23 +415,26 @@ def SubscribeLand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeReboot(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeReboot( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeReboot', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeReboot", action__server_dot_action__server__pb2.SubscribeRebootRequest.SerializeToString, action__server_dot_action__server__pb2.RebootResponse.FromString, options, @@ -427,23 +445,26 @@ def SubscribeReboot(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeShutdown(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeShutdown( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeShutdown', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeShutdown", action__server_dot_action__server__pb2.SubscribeShutdownRequest.SerializeToString, action__server_dot_action__server__pb2.ShutdownResponse.FromString, options, @@ -454,23 +475,26 @@ def SubscribeShutdown(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeTerminate(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTerminate( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SubscribeTerminate', + "/mavsdk.rpc.action_server.ActionServerService/SubscribeTerminate", action__server_dot_action__server__pb2.SubscribeTerminateRequest.SerializeToString, action__server_dot_action__server__pb2.TerminateResponse.FromString, options, @@ -481,23 +505,26 @@ def SubscribeTerminate(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAllowTakeoff(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAllowTakeoff( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SetAllowTakeoff', + "/mavsdk.rpc.action_server.ActionServerService/SetAllowTakeoff", action__server_dot_action__server__pb2.SetAllowTakeoffRequest.SerializeToString, action__server_dot_action__server__pb2.SetAllowTakeoffResponse.FromString, options, @@ -508,23 +535,26 @@ def SetAllowTakeoff(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetArmable(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetArmable( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SetArmable', + "/mavsdk.rpc.action_server.ActionServerService/SetArmable", action__server_dot_action__server__pb2.SetArmableRequest.SerializeToString, action__server_dot_action__server__pb2.SetArmableResponse.FromString, options, @@ -535,23 +565,26 @@ def SetArmable(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetDisarmable(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetDisarmable( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SetDisarmable', + "/mavsdk.rpc.action_server.ActionServerService/SetDisarmable", action__server_dot_action__server__pb2.SetDisarmableRequest.SerializeToString, action__server_dot_action__server__pb2.SetDisarmableResponse.FromString, options, @@ -562,23 +595,26 @@ def SetDisarmable(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAllowableFlightModes(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAllowableFlightModes( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SetAllowableFlightModes', + "/mavsdk.rpc.action_server.ActionServerService/SetAllowableFlightModes", action__server_dot_action__server__pb2.SetAllowableFlightModesRequest.SerializeToString, action__server_dot_action__server__pb2.SetAllowableFlightModesResponse.FromString, options, @@ -589,23 +625,26 @@ def SetAllowableFlightModes(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetAllowableFlightModes(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetAllowableFlightModes( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/GetAllowableFlightModes', + "/mavsdk.rpc.action_server.ActionServerService/GetAllowableFlightModes", action__server_dot_action__server__pb2.GetAllowableFlightModesRequest.SerializeToString, action__server_dot_action__server__pb2.GetAllowableFlightModesResponse.FromString, options, @@ -616,23 +655,26 @@ def GetAllowableFlightModes(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetArmedState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetArmedState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SetArmedState', + "/mavsdk.rpc.action_server.ActionServerService/SetArmedState", action__server_dot_action__server__pb2.SetArmedStateRequest.SerializeToString, action__server_dot_action__server__pb2.SetArmedStateResponse.FromString, options, @@ -643,23 +685,26 @@ def SetArmedState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetFlightMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetFlightMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.action_server.ActionServerService/SetFlightMode', + "/mavsdk.rpc.action_server.ActionServerService/SetFlightMode", action__server_dot_action__server__pb2.SetFlightModeRequest.SerializeToString, action__server_dot_action__server__pb2.SetFlightModeResponse.FromString, options, @@ -670,4 +715,5 @@ def SetFlightMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/arm_authorizer_server.py b/mavsdk/arm_authorizer_server.py index af328d83..d3b5b144 100644 --- a/mavsdk/arm_authorizer_server.py +++ b/mavsdk/arm_authorizer_server.py @@ -8,31 +8,30 @@ class RejectionReason(Enum): """ - The rejection reason + The rejection reason - Values - ------ - GENERIC - Not a specific reason + Values + ------ + GENERIC + Not a specific reason - NONE - Authorizer will send the error as string to GCS + NONE + Authorizer will send the error as string to GCS - INVALID_WAYPOINT - At least one waypoint have a invalid value + INVALID_WAYPOINT + At least one waypoint have a invalid value - TIMEOUT - Timeout in the authorizer process(in case it depends on network) + TIMEOUT + Timeout in the authorizer process(in case it depends on network) - AIRSPACE_IN_USE - Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied. + AIRSPACE_IN_USE + Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied. - BAD_WEATHER - Weather is not good to fly + BAD_WEATHER + Weather is not good to fly - """ + """ - GENERIC = 0 NONE = 1 INVALID_WAYPOINT = 2 @@ -56,12 +55,15 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == arm_authorizer_server_pb2.REJECTION_REASON_GENERIC: return RejectionReason.GENERIC if rpc_enum_value == arm_authorizer_server_pb2.REJECTION_REASON_NONE: return RejectionReason.NONE - if rpc_enum_value == arm_authorizer_server_pb2.REJECTION_REASON_INVALID_WAYPOINT: + if ( + rpc_enum_value + == arm_authorizer_server_pb2.REJECTION_REASON_INVALID_WAYPOINT + ): return RejectionReason.INVALID_WAYPOINT if rpc_enum_value == arm_authorizer_server_pb2.REJECTION_REASON_TIMEOUT: return RejectionReason.TIMEOUT @@ -76,125 +78,118 @@ def __str__(self): class ArmAuthorizerServerResult: """ - - Parameters - ---------- - result : Result - Result enum value - result_str : std::string - Human-readable English string describing the result + Parameters + ---------- + result : Result + Result enum value + + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - The result + The result - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Command accepted + SUCCESS + Command accepted - FAILED - Command failed + FAILED + Command failed - """ + """ - UNKNOWN = 0 SUCCESS = 1 FAILED = 2 def translate_to_rpc(self): if self == ArmAuthorizerServerResult.Result.UNKNOWN: - return arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_UNKNOWN + return ( + arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_UNKNOWN + ) if self == ArmAuthorizerServerResult.Result.SUCCESS: - return arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_SUCCESS + return ( + arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_SUCCESS + ) if self == ArmAuthorizerServerResult.Result.FAILED: return arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_FAILED @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_UNKNOWN + ): return ArmAuthorizerServerResult.Result.UNKNOWN - if rpc_enum_value == arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_SUCCESS: + if ( + rpc_enum_value + == arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_SUCCESS + ): return ArmAuthorizerServerResult.Result.SUCCESS - if rpc_enum_value == arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_FAILED: + if ( + rpc_enum_value + == arm_authorizer_server_pb2.ArmAuthorizerServerResult.RESULT_FAILED + ): return ArmAuthorizerServerResult.Result.FAILED def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ArmAuthorizerServerResult object """ + def __init__(self, result, result_str): + """Initializes the ArmAuthorizerServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ArmAuthorizerServerResult are the same """ + """Checks if two ArmAuthorizerServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ArmAuthorizerServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ArmAuthorizerServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ArmAuthorizerServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ArmAuthorizerServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcArmAuthorizerServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ArmAuthorizerServerResult( - - ArmAuthorizerServerResult.Result.translate_from_rpc(rpcArmAuthorizerServerResult.result), - - - rpcArmAuthorizerServerResult.result_str - ) + ArmAuthorizerServerResult.Result.translate_from_rpc( + rpcArmAuthorizerServerResult.result + ), + rpcArmAuthorizerServerResult.result_str, + ) def translate_to_rpc(self, rpcArmAuthorizerServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcArmAuthorizerServerResult.result = self.result.translate_to_rpc() - - - - - - rpcArmAuthorizerServerResult.result_str = self.result_str - - - + rpcArmAuthorizerServerResult.result_str = self.result_str class ArmAuthorizerServerError(Exception): - """ Raised when a ArmAuthorizerServerResult is a fail code """ + """Raised when a ArmAuthorizerServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -207,34 +202,36 @@ def __str__(self): class ArmAuthorizerServer(AsyncBase): """ - Use arm authorization. + Use arm authorization. - Generated by dcsdkgen - MAVSDK ArmAuthorizerServer API + Generated by dcsdkgen - MAVSDK ArmAuthorizerServer API """ # Plugin name name = "ArmAuthorizerServer" def _setup_stub(self, channel): - """ Setups the api stub """ - self._stub = arm_authorizer_server_pb2_grpc.ArmAuthorizerServerServiceStub(channel) + """Setups the api stub""" + self._stub = arm_authorizer_server_pb2_grpc.ArmAuthorizerServerServiceStub( + channel + ) - def _extract_result(self, response): - """ Returns the response status and description """ - return ArmAuthorizerServerResult.translate_from_rpc(response.arm_authorizer_server_result) - + """Returns the response status and description""" + return ArmAuthorizerServerResult.translate_from_rpc( + response.arm_authorizer_server_result + ) async def arm_authorization(self): """ - Subscribe to arm authorization request messages. Each request received should respond to using RespondArmAuthorization + Subscribe to arm authorization request messages. Each request received should respond to using RespondArmAuthorization + + Yields + ------- + system_id : uint32_t + vehicle system id - Yields - ------- - system_id : uint32_t - vehicle system id - """ request = arm_authorizer_server_pb2.SubscribeArmAuthorizationRequest() @@ -242,72 +239,68 @@ async def arm_authorization(self): try: async for response in arm_authorization_stream: - - - yield response.system_id finally: arm_authorization_stream.cancel() async def accept_arm_authorization(self, valid_time_s): """ - Authorize arm for the specific time + Authorize arm for the specific time - Parameters - ---------- - valid_time_s : int32_t - Time in seconds for which this authorization is valid + Parameters + ---------- + valid_time_s : int32_t + Time in seconds for which this authorization is valid - Raises - ------ - ArmAuthorizerServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ArmAuthorizerServerError + If the request fails. The error contains the reason for the failure. """ request = arm_authorizer_server_pb2.AcceptArmAuthorizationRequest() request.valid_time_s = valid_time_s response = await self._stub.AcceptArmAuthorization(request) - result = self._extract_result(response) if result.result != ArmAuthorizerServerResult.Result.SUCCESS: - raise ArmAuthorizerServerError(result, "accept_arm_authorization()", valid_time_s) - + raise ArmAuthorizerServerError( + result, "accept_arm_authorization()", valid_time_s + ) async def reject_arm_authorization(self, temporarily, reason, extra_info): """ - Reject arm authorization request + Reject arm authorization request - Parameters - ---------- - temporarily : bool - True if the answer should be TEMPORARILY_REJECTED, false for DENIED + Parameters + ---------- + temporarily : bool + True if the answer should be TEMPORARILY_REJECTED, false for DENIED - reason : RejectionReason - Reason for the arm to be rejected + reason : RejectionReason + Reason for the arm to be rejected - extra_info : int32_t - Extra information specific to the rejection reason (see https://mavlink.io/en/services/arm_authorization.html) + extra_info : int32_t + Extra information specific to the rejection reason (see https://mavlink.io/en/services/arm_authorization.html) - Raises - ------ - ArmAuthorizerServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ArmAuthorizerServerError + If the request fails. The error contains the reason for the failure. """ request = arm_authorizer_server_pb2.RejectArmAuthorizationRequest() request.temporarily = temporarily - + request.reason = reason.translate_to_rpc() - - + request.extra_info = extra_info response = await self._stub.RejectArmAuthorization(request) - result = self._extract_result(response) if result.result != ArmAuthorizerServerResult.Result.SUCCESS: - raise ArmAuthorizerServerError(result, "reject_arm_authorization()", temporarily, reason, extra_info) - \ No newline at end of file + raise ArmAuthorizerServerError( + result, "reject_arm_authorization()", temporarily, reason, extra_info + ) diff --git a/mavsdk/arm_authorizer_server_pb2.py b/mavsdk/arm_authorizer_server_pb2.py index 191eccc9..aa536881 100644 --- a/mavsdk/arm_authorizer_server_pb2.py +++ b/mavsdk/arm_authorizer_server_pb2.py @@ -4,18 +4,20 @@ # source: arm_authorizer_server/arm_authorizer_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( _runtime_version.Domain.PUBLIC, 5, 29, 0, - '', - 'arm_authorizer_server/arm_authorizer_server.proto' + "", + "arm_authorizer_server/arm_authorizer_server.proto", ) # @@protoc_insertion_point(imports) @@ -25,38 +27,58 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n1arm_authorizer_server/arm_authorizer_server.proto\x12 mavsdk.rpc.arm_authorizer_server\x1a\x14mavsdk_options.proto\"\"\n SubscribeArmAuthorizationRequest\"-\n\x18\x41rmAuthorizationResponse\x12\x11\n\tsystem_id\x18\x01 \x01(\r\"5\n\x1d\x41\x63\x63\x65ptArmAuthorizationRequest\x12\x14\n\x0cvalid_time_s\x18\x01 \x01(\x05\"\x83\x01\n\x1e\x41\x63\x63\x65ptArmAuthorizationResponse\x12\x61\n\x1c\x61rm_authorizer_server_result\x18\x01 \x01(\x0b\x32;.mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerResult\"\x8b\x01\n\x1dRejectArmAuthorizationRequest\x12\x13\n\x0btemporarily\x18\x01 \x01(\x08\x12\x41\n\x06reason\x18\x02 \x01(\x0e\x32\x31.mavsdk.rpc.arm_authorizer_server.RejectionReason\x12\x12\n\nextra_info\x18\x03 \x01(\x05\"\x83\x01\n\x1eRejectArmAuthorizationResponse\x12\x61\n\x1c\x61rm_authorizer_server_result\x18\x01 \x01(\x0b\x32;.mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerResult\"\xc8\x01\n\x19\x41rmAuthorizerServerResult\x12R\n\x06result\x18\x01 \x01(\x0e\x32\x42.mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"C\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x11\n\rRESULT_FAILED\x10\x02*\xd7\x01\n\x0fRejectionReason\x12\x1c\n\x18REJECTION_REASON_GENERIC\x10\x00\x12\x19\n\x15REJECTION_REASON_NONE\x10\x01\x12%\n!REJECTION_REASON_INVALID_WAYPOINT\x10\x02\x12\x1c\n\x18REJECTION_REASON_TIMEOUT\x10\x03\x12$\n REJECTION_REASON_AIRSPACE_IN_USE\x10\x04\x12 \n\x1cREJECTION_REASON_BAD_WEATHER\x10\x05\x32\x8a\x04\n\x1a\x41rmAuthorizerServerService\x12\xa3\x01\n\x19SubscribeArmAuthorization\x12\x42.mavsdk.rpc.arm_authorizer_server.SubscribeArmAuthorizationRequest\x1a:.mavsdk.rpc.arm_authorizer_server.ArmAuthorizationResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\xa1\x01\n\x16\x41\x63\x63\x65ptArmAuthorization\x12?.mavsdk.rpc.arm_authorizer_server.AcceptArmAuthorizationRequest\x1a@.mavsdk.rpc.arm_authorizer_server.AcceptArmAuthorizationResponse\"\x04\x80\xb5\x18\x01\x12\xa1\x01\n\x16RejectArmAuthorization\x12?.mavsdk.rpc.arm_authorizer_server.RejectArmAuthorizationRequest\x1a@.mavsdk.rpc.arm_authorizer_server.RejectArmAuthorizationResponse\"\x04\x80\xb5\x18\x01\x42\x34\n\x18io.mavsdk.arm_authorizerB\x18\x41rmAuthorizerServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n1arm_authorizer_server/arm_authorizer_server.proto\x12 mavsdk.rpc.arm_authorizer_server\x1a\x14mavsdk_options.proto""\n SubscribeArmAuthorizationRequest"-\n\x18\x41rmAuthorizationResponse\x12\x11\n\tsystem_id\x18\x01 \x01(\r"5\n\x1d\x41\x63\x63\x65ptArmAuthorizationRequest\x12\x14\n\x0cvalid_time_s\x18\x01 \x01(\x05"\x83\x01\n\x1e\x41\x63\x63\x65ptArmAuthorizationResponse\x12\x61\n\x1c\x61rm_authorizer_server_result\x18\x01 \x01(\x0b\x32;.mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerResult"\x8b\x01\n\x1dRejectArmAuthorizationRequest\x12\x13\n\x0btemporarily\x18\x01 \x01(\x08\x12\x41\n\x06reason\x18\x02 \x01(\x0e\x32\x31.mavsdk.rpc.arm_authorizer_server.RejectionReason\x12\x12\n\nextra_info\x18\x03 \x01(\x05"\x83\x01\n\x1eRejectArmAuthorizationResponse\x12\x61\n\x1c\x61rm_authorizer_server_result\x18\x01 \x01(\x0b\x32;.mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerResult"\xc8\x01\n\x19\x41rmAuthorizerServerResult\x12R\n\x06result\x18\x01 \x01(\x0e\x32\x42.mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"C\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x11\n\rRESULT_FAILED\x10\x02*\xd7\x01\n\x0fRejectionReason\x12\x1c\n\x18REJECTION_REASON_GENERIC\x10\x00\x12\x19\n\x15REJECTION_REASON_NONE\x10\x01\x12%\n!REJECTION_REASON_INVALID_WAYPOINT\x10\x02\x12\x1c\n\x18REJECTION_REASON_TIMEOUT\x10\x03\x12$\n REJECTION_REASON_AIRSPACE_IN_USE\x10\x04\x12 \n\x1cREJECTION_REASON_BAD_WEATHER\x10\x05\x32\x8a\x04\n\x1a\x41rmAuthorizerServerService\x12\xa3\x01\n\x19SubscribeArmAuthorization\x12\x42.mavsdk.rpc.arm_authorizer_server.SubscribeArmAuthorizationRequest\x1a:.mavsdk.rpc.arm_authorizer_server.ArmAuthorizationResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\xa1\x01\n\x16\x41\x63\x63\x65ptArmAuthorization\x12?.mavsdk.rpc.arm_authorizer_server.AcceptArmAuthorizationRequest\x1a@.mavsdk.rpc.arm_authorizer_server.AcceptArmAuthorizationResponse"\x04\x80\xb5\x18\x01\x12\xa1\x01\n\x16RejectArmAuthorization\x12?.mavsdk.rpc.arm_authorizer_server.RejectArmAuthorizationRequest\x1a@.mavsdk.rpc.arm_authorizer_server.RejectArmAuthorizationResponse"\x04\x80\xb5\x18\x01\x42\x34\n\x18io.mavsdk.arm_authorizerB\x18\x41rmAuthorizerServerProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'arm_authorizer_server.arm_authorizer_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "arm_authorizer_server.arm_authorizer_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\030io.mavsdk.arm_authorizerB\030ArmAuthorizerServerProto' - _globals['_ARMAUTHORIZERSERVERSERVICE'].methods_by_name['SubscribeArmAuthorization']._loaded_options = None - _globals['_ARMAUTHORIZERSERVERSERVICE'].methods_by_name['SubscribeArmAuthorization']._serialized_options = b'\200\265\030\000' - _globals['_ARMAUTHORIZERSERVERSERVICE'].methods_by_name['AcceptArmAuthorization']._loaded_options = None - _globals['_ARMAUTHORIZERSERVERSERVICE'].methods_by_name['AcceptArmAuthorization']._serialized_options = b'\200\265\030\001' - _globals['_ARMAUTHORIZERSERVERSERVICE'].methods_by_name['RejectArmAuthorization']._loaded_options = None - _globals['_ARMAUTHORIZERSERVERSERVICE'].methods_by_name['RejectArmAuthorization']._serialized_options = b'\200\265\030\001' - _globals['_REJECTIONREASON']._serialized_start=861 - _globals['_REJECTIONREASON']._serialized_end=1076 - _globals['_SUBSCRIBEARMAUTHORIZATIONREQUEST']._serialized_start=109 - _globals['_SUBSCRIBEARMAUTHORIZATIONREQUEST']._serialized_end=143 - _globals['_ARMAUTHORIZATIONRESPONSE']._serialized_start=145 - _globals['_ARMAUTHORIZATIONRESPONSE']._serialized_end=190 - _globals['_ACCEPTARMAUTHORIZATIONREQUEST']._serialized_start=192 - _globals['_ACCEPTARMAUTHORIZATIONREQUEST']._serialized_end=245 - _globals['_ACCEPTARMAUTHORIZATIONRESPONSE']._serialized_start=248 - _globals['_ACCEPTARMAUTHORIZATIONRESPONSE']._serialized_end=379 - _globals['_REJECTARMAUTHORIZATIONREQUEST']._serialized_start=382 - _globals['_REJECTARMAUTHORIZATIONREQUEST']._serialized_end=521 - _globals['_REJECTARMAUTHORIZATIONRESPONSE']._serialized_start=524 - _globals['_REJECTARMAUTHORIZATIONRESPONSE']._serialized_end=655 - _globals['_ARMAUTHORIZERSERVERRESULT']._serialized_start=658 - _globals['_ARMAUTHORIZERSERVERRESULT']._serialized_end=858 - _globals['_ARMAUTHORIZERSERVERRESULT_RESULT']._serialized_start=791 - _globals['_ARMAUTHORIZERSERVERRESULT_RESULT']._serialized_end=858 - _globals['_ARMAUTHORIZERSERVERSERVICE']._serialized_start=1079 - _globals['_ARMAUTHORIZERSERVERSERVICE']._serialized_end=1601 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = ( + b"\n\030io.mavsdk.arm_authorizerB\030ArmAuthorizerServerProto" + ) + _globals["_ARMAUTHORIZERSERVERSERVICE"].methods_by_name[ + "SubscribeArmAuthorization" + ]._loaded_options = None + _globals["_ARMAUTHORIZERSERVERSERVICE"].methods_by_name[ + "SubscribeArmAuthorization" + ]._serialized_options = b"\200\265\030\000" + _globals["_ARMAUTHORIZERSERVERSERVICE"].methods_by_name[ + "AcceptArmAuthorization" + ]._loaded_options = None + _globals["_ARMAUTHORIZERSERVERSERVICE"].methods_by_name[ + "AcceptArmAuthorization" + ]._serialized_options = b"\200\265\030\001" + _globals["_ARMAUTHORIZERSERVERSERVICE"].methods_by_name[ + "RejectArmAuthorization" + ]._loaded_options = None + _globals["_ARMAUTHORIZERSERVERSERVICE"].methods_by_name[ + "RejectArmAuthorization" + ]._serialized_options = b"\200\265\030\001" + _globals["_REJECTIONREASON"]._serialized_start = 861 + _globals["_REJECTIONREASON"]._serialized_end = 1076 + _globals["_SUBSCRIBEARMAUTHORIZATIONREQUEST"]._serialized_start = 109 + _globals["_SUBSCRIBEARMAUTHORIZATIONREQUEST"]._serialized_end = 143 + _globals["_ARMAUTHORIZATIONRESPONSE"]._serialized_start = 145 + _globals["_ARMAUTHORIZATIONRESPONSE"]._serialized_end = 190 + _globals["_ACCEPTARMAUTHORIZATIONREQUEST"]._serialized_start = 192 + _globals["_ACCEPTARMAUTHORIZATIONREQUEST"]._serialized_end = 245 + _globals["_ACCEPTARMAUTHORIZATIONRESPONSE"]._serialized_start = 248 + _globals["_ACCEPTARMAUTHORIZATIONRESPONSE"]._serialized_end = 379 + _globals["_REJECTARMAUTHORIZATIONREQUEST"]._serialized_start = 382 + _globals["_REJECTARMAUTHORIZATIONREQUEST"]._serialized_end = 521 + _globals["_REJECTARMAUTHORIZATIONRESPONSE"]._serialized_start = 524 + _globals["_REJECTARMAUTHORIZATIONRESPONSE"]._serialized_end = 655 + _globals["_ARMAUTHORIZERSERVERRESULT"]._serialized_start = 658 + _globals["_ARMAUTHORIZERSERVERRESULT"]._serialized_end = 858 + _globals["_ARMAUTHORIZERSERVERRESULT_RESULT"]._serialized_start = 791 + _globals["_ARMAUTHORIZERSERVERRESULT_RESULT"]._serialized_end = 858 + _globals["_ARMAUTHORIZERSERVERSERVICE"]._serialized_start = 1079 + _globals["_ARMAUTHORIZERSERVERSERVICE"]._serialized_end = 1601 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/arm_authorizer_server_pb2_grpc.py b/mavsdk/arm_authorizer_server_pb2_grpc.py index 180e5437..76f60f92 100644 --- a/mavsdk/arm_authorizer_server_pb2_grpc.py +++ b/mavsdk/arm_authorizer_server_pb2_grpc.py @@ -1,33 +1,38 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings -from . import arm_authorizer_server_pb2 as arm__authorizer__server_dot_arm__authorizer__server__pb2 +from . import ( + arm_authorizer_server_pb2 as arm__authorizer__server_dot_arm__authorizer__server__pb2, +) -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in arm_authorizer_server/arm_authorizer_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in arm_authorizer_server/arm_authorizer_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ArmAuthorizerServerServiceStub(object): - """Use arm authorization. - """ + """Use arm authorization.""" def __init__(self, channel): """Constructor. @@ -36,92 +41,97 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeArmAuthorization = channel.unary_stream( - '/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/SubscribeArmAuthorization', - request_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.SubscribeArmAuthorizationRequest.SerializeToString, - response_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.ArmAuthorizationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/SubscribeArmAuthorization", + request_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.SubscribeArmAuthorizationRequest.SerializeToString, + response_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.ArmAuthorizationResponse.FromString, + _registered_method=True, + ) self.AcceptArmAuthorization = channel.unary_unary( - '/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/AcceptArmAuthorization', - request_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationRequest.SerializeToString, - response_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/AcceptArmAuthorization", + request_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationRequest.SerializeToString, + response_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationResponse.FromString, + _registered_method=True, + ) self.RejectArmAuthorization = channel.unary_unary( - '/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/RejectArmAuthorization', - request_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationRequest.SerializeToString, - response_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/RejectArmAuthorization", + request_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationRequest.SerializeToString, + response_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationResponse.FromString, + _registered_method=True, + ) class ArmAuthorizerServerServiceServicer(object): - """Use arm authorization. - """ + """Use arm authorization.""" def SubscribeArmAuthorization(self, request, context): - """Subscribe to arm authorization request messages. Each request received should respond to using RespondArmAuthorization - """ + """Subscribe to arm authorization request messages. Each request received should respond to using RespondArmAuthorization""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def AcceptArmAuthorization(self, request, context): - """Authorize arm for the specific time - """ + """Authorize arm for the specific time""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RejectArmAuthorization(self, request, context): - """Reject arm authorization request - """ + """Reject arm authorization request""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ArmAuthorizerServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeArmAuthorization': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeArmAuthorization, - request_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.SubscribeArmAuthorizationRequest.FromString, - response_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.ArmAuthorizationResponse.SerializeToString, - ), - 'AcceptArmAuthorization': grpc.unary_unary_rpc_method_handler( - servicer.AcceptArmAuthorization, - request_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationRequest.FromString, - response_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationResponse.SerializeToString, - ), - 'RejectArmAuthorization': grpc.unary_unary_rpc_method_handler( - servicer.RejectArmAuthorization, - request_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationRequest.FromString, - response_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationResponse.SerializeToString, - ), + "SubscribeArmAuthorization": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeArmAuthorization, + request_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.SubscribeArmAuthorizationRequest.FromString, + response_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.ArmAuthorizationResponse.SerializeToString, + ), + "AcceptArmAuthorization": grpc.unary_unary_rpc_method_handler( + servicer.AcceptArmAuthorization, + request_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationRequest.FromString, + response_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationResponse.SerializeToString, + ), + "RejectArmAuthorization": grpc.unary_unary_rpc_method_handler( + servicer.RejectArmAuthorization, + request_deserializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationRequest.FromString, + response_serializer=arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService', rpc_method_handlers) + "mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService", + rpc_method_handlers, + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService", + rpc_method_handlers, + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ArmAuthorizerServerService(object): - """Use arm authorization. - """ + """Use arm authorization.""" @staticmethod - def SubscribeArmAuthorization(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeArmAuthorization( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/SubscribeArmAuthorization', + "/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/SubscribeArmAuthorization", arm__authorizer__server_dot_arm__authorizer__server__pb2.SubscribeArmAuthorizationRequest.SerializeToString, arm__authorizer__server_dot_arm__authorizer__server__pb2.ArmAuthorizationResponse.FromString, options, @@ -132,23 +142,26 @@ def SubscribeArmAuthorization(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def AcceptArmAuthorization(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def AcceptArmAuthorization( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/AcceptArmAuthorization', + "/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/AcceptArmAuthorization", arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationRequest.SerializeToString, arm__authorizer__server_dot_arm__authorizer__server__pb2.AcceptArmAuthorizationResponse.FromString, options, @@ -159,23 +172,26 @@ def AcceptArmAuthorization(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RejectArmAuthorization(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RejectArmAuthorization( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/RejectArmAuthorization', + "/mavsdk.rpc.arm_authorizer_server.ArmAuthorizerServerService/RejectArmAuthorization", arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationRequest.SerializeToString, arm__authorizer__server_dot_arm__authorizer__server__pb2.RejectArmAuthorizationResponse.FromString, options, @@ -186,4 +202,5 @@ def RejectArmAuthorization(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/async_plugin_manager.py b/mavsdk/async_plugin_manager.py index 6cfa3f18..c9ac565d 100644 --- a/mavsdk/async_plugin_manager.py +++ b/mavsdk/async_plugin_manager.py @@ -7,9 +7,9 @@ class AsyncPluginManager: """ Connects to a running mavsdk server or starts one and manages plugins """ + @classmethod async def create(cls, host, port=50051): - self = AsyncPluginManager() self.host = host @@ -26,12 +26,12 @@ async def _connect_backend(self): """ #: gRPC channel - self._channel = aio.insecure_channel( - "{}:{}".format(self.host, self.port) - ) + self._channel = aio.insecure_channel("{}:{}".format(self.host, self.port)) logger = logging.getLogger(__name__) - logger.addHandler(logging.NullHandler()) # Avoid errors when user has not configured logging + logger.addHandler( + logging.NullHandler() + ) # Avoid errors when user has not configured logging logger.debug("Waiting for mavsdk_server to be ready...") await self._channel.channel_ready() diff --git a/mavsdk/calibration.py b/mavsdk/calibration.py index 52a5f80a..d73ebf45 100644 --- a/mavsdk/calibration.py +++ b/mavsdk/calibration.py @@ -8,65 +8,62 @@ class CalibrationResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for calibration commands + Possible results returned for calibration commands - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - The calibration succeeded + SUCCESS + The calibration succeeded - NEXT - Intermediate message showing progress or instructions on the next steps + NEXT + Intermediate message showing progress or instructions on the next steps - FAILED - Calibration failed + FAILED + Calibration failed - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - TIMEOUT - Command timed out + TIMEOUT + Command timed out - CANCELLED - Calibration process was cancelled + CANCELLED + Calibration process was cancelled - FAILED_ARMED - Calibration process failed since the vehicle is armed + FAILED_ARMED + Calibration process failed since the vehicle is armed - UNSUPPORTED - Functionality not supported + UNSUPPORTED + Functionality not supported - """ + """ - UNKNOWN = 0 SUCCESS = 1 NEXT = 2 @@ -108,7 +105,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_UNKNOWN: return CalibrationResult.Result.UNKNOWN if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_SUCCESS: @@ -119,11 +116,17 @@ def translate_from_rpc(rpc_enum_value): return CalibrationResult.Result.FAILED if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_NO_SYSTEM: return CalibrationResult.Result.NO_SYSTEM - if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == calibration_pb2.CalibrationResult.RESULT_CONNECTION_ERROR + ): return CalibrationResult.Result.CONNECTION_ERROR if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_BUSY: return CalibrationResult.Result.BUSY - if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_COMMAND_DENIED: + if ( + rpc_enum_value + == calibration_pb2.CalibrationResult.RESULT_COMMAND_DENIED + ): return CalibrationResult.Result.COMMAND_DENIED if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_TIMEOUT: return CalibrationResult.Result.TIMEOUT @@ -136,177 +139,129 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the CalibrationResult object """ + def __init__(self, result, result_str): + """Initializes the CalibrationResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two CalibrationResult are the same """ + """Checks if two CalibrationResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # CalibrationResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ CalibrationResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """CalibrationResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"CalibrationResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCalibrationResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CalibrationResult( - - CalibrationResult.Result.translate_from_rpc(rpcCalibrationResult.result), - - - rpcCalibrationResult.result_str - ) + CalibrationResult.Result.translate_from_rpc(rpcCalibrationResult.result), + rpcCalibrationResult.result_str, + ) def translate_to_rpc(self, rpcCalibrationResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCalibrationResult.result = self.result.translate_to_rpc() - - - - - + rpcCalibrationResult.result_str = self.result_str - - - class ProgressData: """ - Progress data coming from calibration. + Progress data coming from calibration. - Can be a progress percentage, or an instruction text. + Can be a progress percentage, or an instruction text. - Parameters - ---------- - has_progress : bool - Whether this ProgressData contains a 'progress' status or not + Parameters + ---------- + has_progress : bool + Whether this ProgressData contains a 'progress' status or not - progress : float - Progress (percentage) + progress : float + Progress (percentage) - has_status_text : bool - Whether this ProgressData contains a 'status_text' or not + has_status_text : bool + Whether this ProgressData contains a 'status_text' or not - status_text : std::string - Instruction text + status_text : std::string + Instruction text - """ - - + """ - def __init__( - self, - has_progress, - progress, - has_status_text, - status_text): - """ Initializes the ProgressData object """ + def __init__(self, has_progress, progress, has_status_text, status_text): + """Initializes the ProgressData object""" self.has_progress = has_progress self.progress = progress self.has_status_text = has_status_text self.status_text = status_text def __eq__(self, to_compare): - """ Checks if two ProgressData are the same """ + """Checks if two ProgressData are the same""" try: # Try to compare - this likely fails when it is compared to a non # ProgressData object - return \ - (self.has_progress == to_compare.has_progress) and \ - (self.progress == to_compare.progress) and \ - (self.has_status_text == to_compare.has_status_text) and \ - (self.status_text == to_compare.status_text) + return ( + (self.has_progress == to_compare.has_progress) + and (self.progress == to_compare.progress) + and (self.has_status_text == to_compare.has_status_text) + and (self.status_text == to_compare.status_text) + ) except AttributeError: return False def __str__(self): - """ ProgressData in string representation """ - struct_repr = ", ".join([ + """ProgressData in string representation""" + struct_repr = ", ".join( + [ "has_progress: " + str(self.has_progress), "progress: " + str(self.progress), "has_status_text: " + str(self.has_status_text), - "status_text: " + str(self.status_text) - ]) + "status_text: " + str(self.status_text), + ] + ) return f"ProgressData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcProgressData): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ProgressData( - - rpcProgressData.has_progress, - - - rpcProgressData.progress, - - - rpcProgressData.has_status_text, - - - rpcProgressData.status_text - ) + rpcProgressData.has_progress, + rpcProgressData.progress, + rpcProgressData.has_status_text, + rpcProgressData.status_text, + ) def translate_to_rpc(self, rpcProgressData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcProgressData.has_progress = self.has_progress - - - - - + rpcProgressData.progress = self.progress - - - - - + rpcProgressData.has_status_text = self.has_status_text - - - - - - rpcProgressData.status_text = self.status_text - - - + rpcProgressData.status_text = self.status_text class CalibrationError(Exception): - """ Raised when a CalibrationResult is a fail code """ + """Raised when a CalibrationResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -319,37 +274,35 @@ def __str__(self): class Calibration(AsyncBase): """ - Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer. + Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer. - Generated by dcsdkgen - MAVSDK Calibration API + Generated by dcsdkgen - MAVSDK Calibration API """ # Plugin name name = "Calibration" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = calibration_pb2_grpc.CalibrationServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return CalibrationResult.translate_from_rpc(response.calibration_result) - async def calibrate_gyro(self): """ - Perform gyro calibration. + Perform gyro calibration. - Yields - ------- - progress_data : ProgressData - Progress data + Yields + ------- + progress_data : ProgressData + Progress data - Raises - ------ - CalibrationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CalibrationError + If the request fails. The error contains the reason for the failure. """ request = calibration_pb2.SubscribeCalibrateGyroRequest() @@ -357,202 +310,203 @@ async def calibrate_gyro(self): try: async for response in calibrate_gyro_stream: - result = self._extract_result(response) success_codes = [CalibrationResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]: + if "NEXT" in [ + return_code.name for return_code in CalibrationResult.Result + ]: success_codes.append(CalibrationResult.Result.NEXT) if result.result not in success_codes: raise CalibrationError(result, "calibrate_gyro()") if result.result == CalibrationResult.Result.SUCCESS: - calibrate_gyro_stream.cancel(); + calibrate_gyro_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: calibrate_gyro_stream.cancel() async def calibrate_accelerometer(self): """ - Perform accelerometer calibration. + Perform accelerometer calibration. - Yields - ------- - progress_data : ProgressData - Progress data + Yields + ------- + progress_data : ProgressData + Progress data - Raises - ------ - CalibrationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CalibrationError + If the request fails. The error contains the reason for the failure. """ request = calibration_pb2.SubscribeCalibrateAccelerometerRequest() - calibrate_accelerometer_stream = self._stub.SubscribeCalibrateAccelerometer(request) + calibrate_accelerometer_stream = self._stub.SubscribeCalibrateAccelerometer( + request + ) try: async for response in calibrate_accelerometer_stream: - result = self._extract_result(response) success_codes = [CalibrationResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]: + if "NEXT" in [ + return_code.name for return_code in CalibrationResult.Result + ]: success_codes.append(CalibrationResult.Result.NEXT) if result.result not in success_codes: raise CalibrationError(result, "calibrate_accelerometer()") if result.result == CalibrationResult.Result.SUCCESS: - calibrate_accelerometer_stream.cancel(); + calibrate_accelerometer_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: calibrate_accelerometer_stream.cancel() async def calibrate_magnetometer(self): """ - Perform magnetometer calibration. + Perform magnetometer calibration. - Yields - ------- - progress_data : ProgressData - Progress data + Yields + ------- + progress_data : ProgressData + Progress data - Raises - ------ - CalibrationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CalibrationError + If the request fails. The error contains the reason for the failure. """ request = calibration_pb2.SubscribeCalibrateMagnetometerRequest() - calibrate_magnetometer_stream = self._stub.SubscribeCalibrateMagnetometer(request) + calibrate_magnetometer_stream = self._stub.SubscribeCalibrateMagnetometer( + request + ) try: async for response in calibrate_magnetometer_stream: - result = self._extract_result(response) success_codes = [CalibrationResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]: + if "NEXT" in [ + return_code.name for return_code in CalibrationResult.Result + ]: success_codes.append(CalibrationResult.Result.NEXT) if result.result not in success_codes: raise CalibrationError(result, "calibrate_magnetometer()") if result.result == CalibrationResult.Result.SUCCESS: - calibrate_magnetometer_stream.cancel(); + calibrate_magnetometer_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: calibrate_magnetometer_stream.cancel() async def calibrate_level_horizon(self): """ - Perform board level horizon calibration. + Perform board level horizon calibration. - Yields - ------- - progress_data : ProgressData - Progress data + Yields + ------- + progress_data : ProgressData + Progress data - Raises - ------ - CalibrationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CalibrationError + If the request fails. The error contains the reason for the failure. """ request = calibration_pb2.SubscribeCalibrateLevelHorizonRequest() - calibrate_level_horizon_stream = self._stub.SubscribeCalibrateLevelHorizon(request) + calibrate_level_horizon_stream = self._stub.SubscribeCalibrateLevelHorizon( + request + ) try: async for response in calibrate_level_horizon_stream: - result = self._extract_result(response) success_codes = [CalibrationResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]: + if "NEXT" in [ + return_code.name for return_code in CalibrationResult.Result + ]: success_codes.append(CalibrationResult.Result.NEXT) if result.result not in success_codes: raise CalibrationError(result, "calibrate_level_horizon()") if result.result == CalibrationResult.Result.SUCCESS: - calibrate_level_horizon_stream.cancel(); + calibrate_level_horizon_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: calibrate_level_horizon_stream.cancel() async def calibrate_gimbal_accelerometer(self): """ - Perform gimbal accelerometer calibration. + Perform gimbal accelerometer calibration. - Yields - ------- - progress_data : ProgressData - Progress data + Yields + ------- + progress_data : ProgressData + Progress data - Raises - ------ - CalibrationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CalibrationError + If the request fails. The error contains the reason for the failure. """ request = calibration_pb2.SubscribeCalibrateGimbalAccelerometerRequest() - calibrate_gimbal_accelerometer_stream = self._stub.SubscribeCalibrateGimbalAccelerometer(request) + calibrate_gimbal_accelerometer_stream = ( + self._stub.SubscribeCalibrateGimbalAccelerometer(request) + ) try: async for response in calibrate_gimbal_accelerometer_stream: - result = self._extract_result(response) success_codes = [CalibrationResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]: + if "NEXT" in [ + return_code.name for return_code in CalibrationResult.Result + ]: success_codes.append(CalibrationResult.Result.NEXT) if result.result not in success_codes: raise CalibrationError(result, "calibrate_gimbal_accelerometer()") if result.result == CalibrationResult.Result.SUCCESS: - calibrate_gimbal_accelerometer_stream.cancel(); + calibrate_gimbal_accelerometer_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: calibrate_gimbal_accelerometer_stream.cancel() async def cancel(self): """ - Cancel ongoing calibration process. + Cancel ongoing calibration process. - Raises - ------ - CalibrationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CalibrationError + If the request fails. The error contains the reason for the failure. """ request = calibration_pb2.CancelRequest() response = await self._stub.Cancel(request) - result = self._extract_result(response) if result.result != CalibrationResult.Result.SUCCESS: raise CalibrationError(result, "cancel()") - \ No newline at end of file diff --git a/mavsdk/calibration_pb2.py b/mavsdk/calibration_pb2.py index 239de8ee..527e8841 100644 --- a/mavsdk/calibration_pb2.py +++ b/mavsdk/calibration_pb2.py @@ -4,18 +4,15 @@ # source: calibration/calibration.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'calibration/calibration.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "calibration/calibration.proto" ) # @@protoc_insertion_point(imports) @@ -25,62 +22,96 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x1d\x63\x61libration/calibration.proto\x12\x16mavsdk.rpc.calibration\x1a\x14mavsdk_options.proto\"\x1f\n\x1dSubscribeCalibrateGyroRequest\"\x9b\x01\n\x15\x43\x61librateGyroResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"(\n&SubscribeCalibrateAccelerometerRequest\"\xa4\x01\n\x1e\x43\x61librateAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\'\n%SubscribeCalibrateMagnetometerRequest\"\xa3\x01\n\x1d\x43\x61librateMagnetometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\'\n%SubscribeCalibrateLevelHorizonRequest\"\xa3\x01\n\x1d\x43\x61librateLevelHorizonResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\".\n,SubscribeCalibrateGimbalAccelerometerRequest\"\xaa\x01\n$CalibrateGimbalAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\x0f\n\rCancelRequest\"W\n\x0e\x43\x61ncelResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\"\xfa\x02\n\x11\x43\x61librationResult\x12@\n\x06result\x18\x01 \x01(\x0e\x32\x30.mavsdk.rpc.calibration.CalibrationResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x8e\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x11\n\rRESULT_FAILED\x10\x03\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x04\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x05\x12\x0f\n\x0bRESULT_BUSY\x10\x06\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12\x14\n\x10RESULT_CANCELLED\x10\t\x12\x17\n\x13RESULT_FAILED_ARMED\x10\n\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x0b\"\x83\x01\n\x0cProgressData\x12\x1f\n\x0chas_progress\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x19\n\x08progress\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x0fhas_status_text\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x13\n\x0bstatus_text\x18\x04 \x01(\t2\xac\x07\n\x12\x43\x61librationService\x12\x8a\x01\n\x16SubscribeCalibrateGyro\x12\x35.mavsdk.rpc.calibration.SubscribeCalibrateGyroRequest\x1a-.mavsdk.rpc.calibration.CalibrateGyroResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa5\x01\n\x1fSubscribeCalibrateAccelerometer\x12>.mavsdk.rpc.calibration.SubscribeCalibrateAccelerometerRequest\x1a\x36.mavsdk.rpc.calibration.CalibrateAccelerometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateMagnetometer\x12=.mavsdk.rpc.calibration.SubscribeCalibrateMagnetometerRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateMagnetometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateLevelHorizon\x12=.mavsdk.rpc.calibration.SubscribeCalibrateLevelHorizonRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateLevelHorizonResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xb7\x01\n%SubscribeCalibrateGimbalAccelerometer\x12\x44.mavsdk.rpc.calibration.SubscribeCalibrateGimbalAccelerometerRequest\x1a<.mavsdk.rpc.calibration.CalibrateGimbalAccelerometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12]\n\x06\x43\x61ncel\x12%.mavsdk.rpc.calibration.CancelRequest\x1a&.mavsdk.rpc.calibration.CancelResponse\"\x04\x80\xb5\x18\x01\x42)\n\x15io.mavsdk.calibrationB\x10\x43\x61librationProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x1d\x63\x61libration/calibration.proto\x12\x16mavsdk.rpc.calibration\x1a\x14mavsdk_options.proto"\x1f\n\x1dSubscribeCalibrateGyroRequest"\x9b\x01\n\x15\x43\x61librateGyroResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData"(\n&SubscribeCalibrateAccelerometerRequest"\xa4\x01\n\x1e\x43\x61librateAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData"\'\n%SubscribeCalibrateMagnetometerRequest"\xa3\x01\n\x1d\x43\x61librateMagnetometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData"\'\n%SubscribeCalibrateLevelHorizonRequest"\xa3\x01\n\x1d\x43\x61librateLevelHorizonResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData".\n,SubscribeCalibrateGimbalAccelerometerRequest"\xaa\x01\n$CalibrateGimbalAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData"\x0f\n\rCancelRequest"W\n\x0e\x43\x61ncelResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult"\xfa\x02\n\x11\x43\x61librationResult\x12@\n\x06result\x18\x01 \x01(\x0e\x32\x30.mavsdk.rpc.calibration.CalibrationResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\x8e\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x11\n\rRESULT_FAILED\x10\x03\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x04\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x05\x12\x0f\n\x0bRESULT_BUSY\x10\x06\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12\x14\n\x10RESULT_CANCELLED\x10\t\x12\x17\n\x13RESULT_FAILED_ARMED\x10\n\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x0b"\x83\x01\n\x0cProgressData\x12\x1f\n\x0chas_progress\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x19\n\x08progress\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12"\n\x0fhas_status_text\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x13\n\x0bstatus_text\x18\x04 \x01(\t2\xac\x07\n\x12\x43\x61librationService\x12\x8a\x01\n\x16SubscribeCalibrateGyro\x12\x35.mavsdk.rpc.calibration.SubscribeCalibrateGyroRequest\x1a-.mavsdk.rpc.calibration.CalibrateGyroResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa5\x01\n\x1fSubscribeCalibrateAccelerometer\x12>.mavsdk.rpc.calibration.SubscribeCalibrateAccelerometerRequest\x1a\x36.mavsdk.rpc.calibration.CalibrateAccelerometerResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateMagnetometer\x12=.mavsdk.rpc.calibration.SubscribeCalibrateMagnetometerRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateMagnetometerResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateLevelHorizon\x12=.mavsdk.rpc.calibration.SubscribeCalibrateLevelHorizonRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateLevelHorizonResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xb7\x01\n%SubscribeCalibrateGimbalAccelerometer\x12\x44.mavsdk.rpc.calibration.SubscribeCalibrateGimbalAccelerometerRequest\x1a<.mavsdk.rpc.calibration.CalibrateGimbalAccelerometerResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12]\n\x06\x43\x61ncel\x12%.mavsdk.rpc.calibration.CancelRequest\x1a&.mavsdk.rpc.calibration.CancelResponse"\x04\x80\xb5\x18\x01\x42)\n\x15io.mavsdk.calibrationB\x10\x43\x61librationProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'calibration.calibration_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "calibration.calibration_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\025io.mavsdk.calibrationB\020CalibrationProto' - _globals['_PROGRESSDATA'].fields_by_name['has_progress']._loaded_options = None - _globals['_PROGRESSDATA'].fields_by_name['has_progress']._serialized_options = b'\202\265\030\005false' - _globals['_PROGRESSDATA'].fields_by_name['progress']._loaded_options = None - _globals['_PROGRESSDATA'].fields_by_name['progress']._serialized_options = b'\202\265\030\003NaN' - _globals['_PROGRESSDATA'].fields_by_name['has_status_text']._loaded_options = None - _globals['_PROGRESSDATA'].fields_by_name['has_status_text']._serialized_options = b'\202\265\030\005false' - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateGyro']._loaded_options = None - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateGyro']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateAccelerometer']._loaded_options = None - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateAccelerometer']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateMagnetometer']._loaded_options = None - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateMagnetometer']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateLevelHorizon']._loaded_options = None - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateLevelHorizon']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateGimbalAccelerometer']._loaded_options = None - _globals['_CALIBRATIONSERVICE'].methods_by_name['SubscribeCalibrateGimbalAccelerometer']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_CALIBRATIONSERVICE'].methods_by_name['Cancel']._loaded_options = None - _globals['_CALIBRATIONSERVICE'].methods_by_name['Cancel']._serialized_options = b'\200\265\030\001' - _globals['_SUBSCRIBECALIBRATEGYROREQUEST']._serialized_start=79 - _globals['_SUBSCRIBECALIBRATEGYROREQUEST']._serialized_end=110 - _globals['_CALIBRATEGYRORESPONSE']._serialized_start=113 - _globals['_CALIBRATEGYRORESPONSE']._serialized_end=268 - _globals['_SUBSCRIBECALIBRATEACCELEROMETERREQUEST']._serialized_start=270 - _globals['_SUBSCRIBECALIBRATEACCELEROMETERREQUEST']._serialized_end=310 - _globals['_CALIBRATEACCELEROMETERRESPONSE']._serialized_start=313 - _globals['_CALIBRATEACCELEROMETERRESPONSE']._serialized_end=477 - _globals['_SUBSCRIBECALIBRATEMAGNETOMETERREQUEST']._serialized_start=479 - _globals['_SUBSCRIBECALIBRATEMAGNETOMETERREQUEST']._serialized_end=518 - _globals['_CALIBRATEMAGNETOMETERRESPONSE']._serialized_start=521 - _globals['_CALIBRATEMAGNETOMETERRESPONSE']._serialized_end=684 - _globals['_SUBSCRIBECALIBRATELEVELHORIZONREQUEST']._serialized_start=686 - _globals['_SUBSCRIBECALIBRATELEVELHORIZONREQUEST']._serialized_end=725 - _globals['_CALIBRATELEVELHORIZONRESPONSE']._serialized_start=728 - _globals['_CALIBRATELEVELHORIZONRESPONSE']._serialized_end=891 - _globals['_SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST']._serialized_start=893 - _globals['_SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST']._serialized_end=939 - _globals['_CALIBRATEGIMBALACCELEROMETERRESPONSE']._serialized_start=942 - _globals['_CALIBRATEGIMBALACCELEROMETERRESPONSE']._serialized_end=1112 - _globals['_CANCELREQUEST']._serialized_start=1114 - _globals['_CANCELREQUEST']._serialized_end=1129 - _globals['_CANCELRESPONSE']._serialized_start=1131 - _globals['_CANCELRESPONSE']._serialized_end=1218 - _globals['_CALIBRATIONRESULT']._serialized_start=1221 - _globals['_CALIBRATIONRESULT']._serialized_end=1599 - _globals['_CALIBRATIONRESULT_RESULT']._serialized_start=1329 - _globals['_CALIBRATIONRESULT_RESULT']._serialized_end=1599 - _globals['_PROGRESSDATA']._serialized_start=1602 - _globals['_PROGRESSDATA']._serialized_end=1733 - _globals['_CALIBRATIONSERVICE']._serialized_start=1736 - _globals['_CALIBRATIONSERVICE']._serialized_end=2676 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\025io.mavsdk.calibrationB\020CalibrationProto" + _globals["_PROGRESSDATA"].fields_by_name["has_progress"]._loaded_options = None + _globals["_PROGRESSDATA"].fields_by_name[ + "has_progress" + ]._serialized_options = b"\202\265\030\005false" + _globals["_PROGRESSDATA"].fields_by_name["progress"]._loaded_options = None + _globals["_PROGRESSDATA"].fields_by_name[ + "progress" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_PROGRESSDATA"].fields_by_name["has_status_text"]._loaded_options = None + _globals["_PROGRESSDATA"].fields_by_name[ + "has_status_text" + ]._serialized_options = b"\202\265\030\005false" + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateGyro" + ]._loaded_options = None + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateGyro" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateAccelerometer" + ]._loaded_options = None + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateAccelerometer" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateMagnetometer" + ]._loaded_options = None + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateMagnetometer" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateLevelHorizon" + ]._loaded_options = None + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateLevelHorizon" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateGimbalAccelerometer" + ]._loaded_options = None + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "SubscribeCalibrateGimbalAccelerometer" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_CALIBRATIONSERVICE"].methods_by_name["Cancel"]._loaded_options = None + _globals["_CALIBRATIONSERVICE"].methods_by_name[ + "Cancel" + ]._serialized_options = b"\200\265\030\001" + _globals["_SUBSCRIBECALIBRATEGYROREQUEST"]._serialized_start = 79 + _globals["_SUBSCRIBECALIBRATEGYROREQUEST"]._serialized_end = 110 + _globals["_CALIBRATEGYRORESPONSE"]._serialized_start = 113 + _globals["_CALIBRATEGYRORESPONSE"]._serialized_end = 268 + _globals["_SUBSCRIBECALIBRATEACCELEROMETERREQUEST"]._serialized_start = 270 + _globals["_SUBSCRIBECALIBRATEACCELEROMETERREQUEST"]._serialized_end = 310 + _globals["_CALIBRATEACCELEROMETERRESPONSE"]._serialized_start = 313 + _globals["_CALIBRATEACCELEROMETERRESPONSE"]._serialized_end = 477 + _globals["_SUBSCRIBECALIBRATEMAGNETOMETERREQUEST"]._serialized_start = 479 + _globals["_SUBSCRIBECALIBRATEMAGNETOMETERREQUEST"]._serialized_end = 518 + _globals["_CALIBRATEMAGNETOMETERRESPONSE"]._serialized_start = 521 + _globals["_CALIBRATEMAGNETOMETERRESPONSE"]._serialized_end = 684 + _globals["_SUBSCRIBECALIBRATELEVELHORIZONREQUEST"]._serialized_start = 686 + _globals["_SUBSCRIBECALIBRATELEVELHORIZONREQUEST"]._serialized_end = 725 + _globals["_CALIBRATELEVELHORIZONRESPONSE"]._serialized_start = 728 + _globals["_CALIBRATELEVELHORIZONRESPONSE"]._serialized_end = 891 + _globals["_SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST"]._serialized_start = 893 + _globals["_SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST"]._serialized_end = 939 + _globals["_CALIBRATEGIMBALACCELEROMETERRESPONSE"]._serialized_start = 942 + _globals["_CALIBRATEGIMBALACCELEROMETERRESPONSE"]._serialized_end = 1112 + _globals["_CANCELREQUEST"]._serialized_start = 1114 + _globals["_CANCELREQUEST"]._serialized_end = 1129 + _globals["_CANCELRESPONSE"]._serialized_start = 1131 + _globals["_CANCELRESPONSE"]._serialized_end = 1218 + _globals["_CALIBRATIONRESULT"]._serialized_start = 1221 + _globals["_CALIBRATIONRESULT"]._serialized_end = 1599 + _globals["_CALIBRATIONRESULT_RESULT"]._serialized_start = 1329 + _globals["_CALIBRATIONRESULT_RESULT"]._serialized_end = 1599 + _globals["_PROGRESSDATA"]._serialized_start = 1602 + _globals["_PROGRESSDATA"]._serialized_end = 1733 + _globals["_CALIBRATIONSERVICE"]._serialized_start = 1736 + _globals["_CALIBRATIONSERVICE"]._serialized_end = 2676 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/calibration_pb2_grpc.py b/mavsdk/calibration_pb2_grpc.py index c97340a5..5edfb414 100644 --- a/mavsdk/calibration_pb2_grpc.py +++ b/mavsdk/calibration_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import calibration_pb2 as calibration_dot_calibration__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in calibration/calibration_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in calibration/calibration_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class CalibrationServiceStub(object): - """Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer. - """ + """Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer.""" def __init__(self, channel): """Constructor. @@ -36,143 +39,146 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeCalibrateGyro = channel.unary_stream( - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGyro', - request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateGyroRequest.SerializeToString, - response_deserializer=calibration_dot_calibration__pb2.CalibrateGyroResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGyro", + request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateGyroRequest.SerializeToString, + response_deserializer=calibration_dot_calibration__pb2.CalibrateGyroResponse.FromString, + _registered_method=True, + ) self.SubscribeCalibrateAccelerometer = channel.unary_stream( - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateAccelerometer', - request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateAccelerometerRequest.SerializeToString, - response_deserializer=calibration_dot_calibration__pb2.CalibrateAccelerometerResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateAccelerometer", + request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateAccelerometerRequest.SerializeToString, + response_deserializer=calibration_dot_calibration__pb2.CalibrateAccelerometerResponse.FromString, + _registered_method=True, + ) self.SubscribeCalibrateMagnetometer = channel.unary_stream( - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateMagnetometer', - request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateMagnetometerRequest.SerializeToString, - response_deserializer=calibration_dot_calibration__pb2.CalibrateMagnetometerResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateMagnetometer", + request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateMagnetometerRequest.SerializeToString, + response_deserializer=calibration_dot_calibration__pb2.CalibrateMagnetometerResponse.FromString, + _registered_method=True, + ) self.SubscribeCalibrateLevelHorizon = channel.unary_stream( - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateLevelHorizon', - request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateLevelHorizonRequest.SerializeToString, - response_deserializer=calibration_dot_calibration__pb2.CalibrateLevelHorizonResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateLevelHorizon", + request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateLevelHorizonRequest.SerializeToString, + response_deserializer=calibration_dot_calibration__pb2.CalibrateLevelHorizonResponse.FromString, + _registered_method=True, + ) self.SubscribeCalibrateGimbalAccelerometer = channel.unary_stream( - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGimbalAccelerometer', - request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.SerializeToString, - response_deserializer=calibration_dot_calibration__pb2.CalibrateGimbalAccelerometerResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGimbalAccelerometer", + request_serializer=calibration_dot_calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.SerializeToString, + response_deserializer=calibration_dot_calibration__pb2.CalibrateGimbalAccelerometerResponse.FromString, + _registered_method=True, + ) self.Cancel = channel.unary_unary( - '/mavsdk.rpc.calibration.CalibrationService/Cancel', - request_serializer=calibration_dot_calibration__pb2.CancelRequest.SerializeToString, - response_deserializer=calibration_dot_calibration__pb2.CancelResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.calibration.CalibrationService/Cancel", + request_serializer=calibration_dot_calibration__pb2.CancelRequest.SerializeToString, + response_deserializer=calibration_dot_calibration__pb2.CancelResponse.FromString, + _registered_method=True, + ) class CalibrationServiceServicer(object): - """Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer. - """ + """Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer.""" def SubscribeCalibrateGyro(self, request, context): - """Perform gyro calibration. - """ + """Perform gyro calibration.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCalibrateAccelerometer(self, request, context): - """Perform accelerometer calibration. - """ + """Perform accelerometer calibration.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCalibrateMagnetometer(self, request, context): - """Perform magnetometer calibration. - """ + """Perform magnetometer calibration.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCalibrateLevelHorizon(self, request, context): - """Perform board level horizon calibration. - """ + """Perform board level horizon calibration.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCalibrateGimbalAccelerometer(self, request, context): - """Perform gimbal accelerometer calibration. - """ + """Perform gimbal accelerometer calibration.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Cancel(self, request, context): - """Cancel ongoing calibration process. - """ + """Cancel ongoing calibration process.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_CalibrationServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeCalibrateGyro': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCalibrateGyro, - request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateGyroRequest.FromString, - response_serializer=calibration_dot_calibration__pb2.CalibrateGyroResponse.SerializeToString, - ), - 'SubscribeCalibrateAccelerometer': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCalibrateAccelerometer, - request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateAccelerometerRequest.FromString, - response_serializer=calibration_dot_calibration__pb2.CalibrateAccelerometerResponse.SerializeToString, - ), - 'SubscribeCalibrateMagnetometer': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCalibrateMagnetometer, - request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateMagnetometerRequest.FromString, - response_serializer=calibration_dot_calibration__pb2.CalibrateMagnetometerResponse.SerializeToString, - ), - 'SubscribeCalibrateLevelHorizon': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCalibrateLevelHorizon, - request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateLevelHorizonRequest.FromString, - response_serializer=calibration_dot_calibration__pb2.CalibrateLevelHorizonResponse.SerializeToString, - ), - 'SubscribeCalibrateGimbalAccelerometer': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCalibrateGimbalAccelerometer, - request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.FromString, - response_serializer=calibration_dot_calibration__pb2.CalibrateGimbalAccelerometerResponse.SerializeToString, - ), - 'Cancel': grpc.unary_unary_rpc_method_handler( - servicer.Cancel, - request_deserializer=calibration_dot_calibration__pb2.CancelRequest.FromString, - response_serializer=calibration_dot_calibration__pb2.CancelResponse.SerializeToString, - ), + "SubscribeCalibrateGyro": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCalibrateGyro, + request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateGyroRequest.FromString, + response_serializer=calibration_dot_calibration__pb2.CalibrateGyroResponse.SerializeToString, + ), + "SubscribeCalibrateAccelerometer": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCalibrateAccelerometer, + request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateAccelerometerRequest.FromString, + response_serializer=calibration_dot_calibration__pb2.CalibrateAccelerometerResponse.SerializeToString, + ), + "SubscribeCalibrateMagnetometer": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCalibrateMagnetometer, + request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateMagnetometerRequest.FromString, + response_serializer=calibration_dot_calibration__pb2.CalibrateMagnetometerResponse.SerializeToString, + ), + "SubscribeCalibrateLevelHorizon": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCalibrateLevelHorizon, + request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateLevelHorizonRequest.FromString, + response_serializer=calibration_dot_calibration__pb2.CalibrateLevelHorizonResponse.SerializeToString, + ), + "SubscribeCalibrateGimbalAccelerometer": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCalibrateGimbalAccelerometer, + request_deserializer=calibration_dot_calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.FromString, + response_serializer=calibration_dot_calibration__pb2.CalibrateGimbalAccelerometerResponse.SerializeToString, + ), + "Cancel": grpc.unary_unary_rpc_method_handler( + servicer.Cancel, + request_deserializer=calibration_dot_calibration__pb2.CancelRequest.FromString, + response_serializer=calibration_dot_calibration__pb2.CancelResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.calibration.CalibrationService', rpc_method_handlers) + "mavsdk.rpc.calibration.CalibrationService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.calibration.CalibrationService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.calibration.CalibrationService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class CalibrationService(object): - """Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer. - """ + """Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer.""" @staticmethod - def SubscribeCalibrateGyro(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCalibrateGyro( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGyro', + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGyro", calibration_dot_calibration__pb2.SubscribeCalibrateGyroRequest.SerializeToString, calibration_dot_calibration__pb2.CalibrateGyroResponse.FromString, options, @@ -183,23 +189,26 @@ def SubscribeCalibrateGyro(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCalibrateAccelerometer(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCalibrateAccelerometer( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateAccelerometer', + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateAccelerometer", calibration_dot_calibration__pb2.SubscribeCalibrateAccelerometerRequest.SerializeToString, calibration_dot_calibration__pb2.CalibrateAccelerometerResponse.FromString, options, @@ -210,23 +219,26 @@ def SubscribeCalibrateAccelerometer(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCalibrateMagnetometer(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCalibrateMagnetometer( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateMagnetometer', + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateMagnetometer", calibration_dot_calibration__pb2.SubscribeCalibrateMagnetometerRequest.SerializeToString, calibration_dot_calibration__pb2.CalibrateMagnetometerResponse.FromString, options, @@ -237,23 +249,26 @@ def SubscribeCalibrateMagnetometer(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCalibrateLevelHorizon(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCalibrateLevelHorizon( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateLevelHorizon', + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateLevelHorizon", calibration_dot_calibration__pb2.SubscribeCalibrateLevelHorizonRequest.SerializeToString, calibration_dot_calibration__pb2.CalibrateLevelHorizonResponse.FromString, options, @@ -264,23 +279,26 @@ def SubscribeCalibrateLevelHorizon(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCalibrateGimbalAccelerometer(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCalibrateGimbalAccelerometer( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGimbalAccelerometer', + "/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGimbalAccelerometer", calibration_dot_calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.SerializeToString, calibration_dot_calibration__pb2.CalibrateGimbalAccelerometerResponse.FromString, options, @@ -291,23 +309,26 @@ def SubscribeCalibrateGimbalAccelerometer(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Cancel(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Cancel( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.calibration.CalibrationService/Cancel', + "/mavsdk.rpc.calibration.CalibrationService/Cancel", calibration_dot_calibration__pb2.CancelRequest.SerializeToString, calibration_dot_calibration__pb2.CancelResponse.FromString, options, @@ -318,4 +339,5 @@ def Cancel(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/camera.py b/mavsdk/camera.py index a2393d29..032e9c98 100644 --- a/mavsdk/camera.py +++ b/mavsdk/camera.py @@ -8,22 +8,21 @@ class Mode(Enum): """ - Camera mode type. + Camera mode type. - Values - ------ - UNKNOWN - Unknown + Values + ------ + UNKNOWN + Unknown - PHOTO - Photo mode + PHOTO + Photo mode - VIDEO - Video mode + VIDEO + Video mode - """ + """ - UNKNOWN = 0 PHOTO = 1 VIDEO = 2 @@ -38,7 +37,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_pb2.MODE_UNKNOWN: return Mode.UNKNOWN if rpc_enum_value == camera_pb2.MODE_PHOTO: @@ -52,19 +51,18 @@ def __str__(self): class PhotosRange(Enum): """ - Photos range type. + Photos range type. - Values - ------ - ALL - All the photos present on the camera + Values + ------ + ALL + All the photos present on the camera - SINCE_CONNECTION - Photos taken since MAVSDK got connected + SINCE_CONNECTION + Photos taken since MAVSDK got connected - """ + """ - ALL = 0 SINCE_CONNECTION = 1 @@ -76,7 +74,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_pb2.PHOTOS_RANGE_ALL: return PhotosRange.ALL if rpc_enum_value == camera_pb2.PHOTOS_RANGE_SINCE_CONNECTION: @@ -88,217 +86,163 @@ def __str__(self): class Option: """ - Type to represent a setting option. - - Parameters - ---------- - option_id : std::string - Name of the option (machine readable) + Type to represent a setting option. - option_description : std::string - Description of the option (human readable) + Parameters + ---------- + option_id : std::string + Name of the option (machine readable) - """ + option_description : std::string + Description of the option (human readable) - + """ - def __init__( - self, - option_id, - option_description): - """ Initializes the Option object """ + def __init__(self, option_id, option_description): + """Initializes the Option object""" self.option_id = option_id self.option_description = option_description def __eq__(self, to_compare): - """ Checks if two Option are the same """ + """Checks if two Option are the same""" try: # Try to compare - this likely fails when it is compared to a non # Option object - return \ - (self.option_id == to_compare.option_id) and \ - (self.option_description == to_compare.option_description) + return (self.option_id == to_compare.option_id) and ( + self.option_description == to_compare.option_description + ) except AttributeError: return False def __str__(self): - """ Option in string representation """ - struct_repr = ", ".join([ + """Option in string representation""" + struct_repr = ", ".join( + [ "option_id: " + str(self.option_id), - "option_description: " + str(self.option_description) - ]) + "option_description: " + str(self.option_description), + ] + ) return f"Option: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcOption): - """ Translates a gRPC struct to the SDK equivalent """ - return Option( - - rpcOption.option_id, - - - rpcOption.option_description - ) + """Translates a gRPC struct to the SDK equivalent""" + return Option(rpcOption.option_id, rpcOption.option_description) def translate_to_rpc(self, rpcOption): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcOption.option_id = self.option_id - - - - - + rpcOption.option_description = self.option_description - - - class Setting: """ - Type to represent a setting with a selected option. - - Parameters - ---------- - setting_id : std::string - Name of a setting (machine readable) + Type to represent a setting with a selected option. - setting_description : std::string - Description of the setting (human readable). This field is meant to be read from the drone, ignore it when setting. + Parameters + ---------- + setting_id : std::string + Name of a setting (machine readable) - option : Option - Selected option + setting_description : std::string + Description of the setting (human readable). This field is meant to be read from the drone, ignore it when setting. - is_range : bool - If option is given as a range. This field is meant to be read from the drone, ignore it when setting. + option : Option + Selected option - """ + is_range : bool + If option is given as a range. This field is meant to be read from the drone, ignore it when setting. - + """ - def __init__( - self, - setting_id, - setting_description, - option, - is_range): - """ Initializes the Setting object """ + def __init__(self, setting_id, setting_description, option, is_range): + """Initializes the Setting object""" self.setting_id = setting_id self.setting_description = setting_description self.option = option self.is_range = is_range def __eq__(self, to_compare): - """ Checks if two Setting are the same """ + """Checks if two Setting are the same""" try: # Try to compare - this likely fails when it is compared to a non # Setting object - return \ - (self.setting_id == to_compare.setting_id) and \ - (self.setting_description == to_compare.setting_description) and \ - (self.option == to_compare.option) and \ - (self.is_range == to_compare.is_range) + return ( + (self.setting_id == to_compare.setting_id) + and (self.setting_description == to_compare.setting_description) + and (self.option == to_compare.option) + and (self.is_range == to_compare.is_range) + ) except AttributeError: return False def __str__(self): - """ Setting in string representation """ - struct_repr = ", ".join([ + """Setting in string representation""" + struct_repr = ", ".join( + [ "setting_id: " + str(self.setting_id), "setting_description: " + str(self.setting_description), "option: " + str(self.option), - "is_range: " + str(self.is_range) - ]) + "is_range: " + str(self.is_range), + ] + ) return f"Setting: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcSetting): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Setting( - - rpcSetting.setting_id, - - - rpcSetting.setting_description, - - - Option.translate_from_rpc(rpcSetting.option), - - - rpcSetting.is_range - ) + rpcSetting.setting_id, + rpcSetting.setting_description, + Option.translate_from_rpc(rpcSetting.option), + rpcSetting.is_range, + ) def translate_to_rpc(self, rpcSetting): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcSetting.setting_id = self.setting_id - - - - - + rpcSetting.setting_description = self.setting_description - - - - - + self.option.translate_to_rpc(rpcSetting.option) - - - - - + rpcSetting.is_range = self.is_range - - - class SettingOptions: """ - Type to represent a setting with a list of options to choose from. + Type to represent a setting with a list of options to choose from. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - setting_id : std::string - Name of the setting (machine readable) + setting_id : std::string + Name of the setting (machine readable) - setting_description : std::string - Description of the setting (human readable) + setting_description : std::string + Description of the setting (human readable) - options : [Option] - List of options or if range [min, max] or [min, max, interval] + options : [Option] + List of options or if range [min, max] or [min, max, interval] - is_range : bool - If option is given as a range + is_range : bool + If option is given as a range - """ - - + """ def __init__( - self, - component_id, - setting_id, - setting_description, - options, - is_range): - """ Initializes the SettingOptions object """ + self, component_id, setting_id, setting_description, options, is_range + ): + """Initializes the SettingOptions object""" self.component_id = component_id self.setting_id = setting_id self.setting_description = setting_description @@ -306,136 +250,111 @@ def __init__( self.is_range = is_range def __eq__(self, to_compare): - """ Checks if two SettingOptions are the same """ + """Checks if two SettingOptions are the same""" try: # Try to compare - this likely fails when it is compared to a non # SettingOptions object - return \ - (self.component_id == to_compare.component_id) and \ - (self.setting_id == to_compare.setting_id) and \ - (self.setting_description == to_compare.setting_description) and \ - (self.options == to_compare.options) and \ - (self.is_range == to_compare.is_range) + return ( + (self.component_id == to_compare.component_id) + and (self.setting_id == to_compare.setting_id) + and (self.setting_description == to_compare.setting_description) + and (self.options == to_compare.options) + and (self.is_range == to_compare.is_range) + ) except AttributeError: return False def __str__(self): - """ SettingOptions in string representation """ - struct_repr = ", ".join([ + """SettingOptions in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), "setting_id: " + str(self.setting_id), "setting_description: " + str(self.setting_description), "options: " + str(self.options), - "is_range: " + str(self.is_range) - ]) + "is_range: " + str(self.is_range), + ] + ) return f"SettingOptions: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcSettingOptions): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return SettingOptions( - - rpcSettingOptions.component_id, - - - rpcSettingOptions.setting_id, - - - rpcSettingOptions.setting_description, - - - list(map(lambda elem: Option.translate_from_rpc(elem), rpcSettingOptions.options)), - - - rpcSettingOptions.is_range + rpcSettingOptions.component_id, + rpcSettingOptions.setting_id, + rpcSettingOptions.setting_description, + list( + map( + lambda elem: Option.translate_from_rpc(elem), + rpcSettingOptions.options, ) + ), + rpcSettingOptions.is_range, + ) def translate_to_rpc(self, rpcSettingOptions): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcSettingOptions.component_id = self.component_id - - - - - + rpcSettingOptions.setting_id = self.setting_id - - - - - + rpcSettingOptions.setting_description = self.setting_description - - - - - + rpc_elems_list = [] for elem in self.options: - rpc_elem = camera_pb2.Option() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcSettingOptions.options.extend(rpc_elems_list) - - - - - + rpcSettingOptions.is_range = self.is_range - - - class VideoStreamSettings: """ - Type for video stream settings. + Type for video stream settings. - Parameters - ---------- - frame_rate_hz : float - Frames per second + Parameters + ---------- + frame_rate_hz : float + Frames per second - horizontal_resolution_pix : uint32_t - Horizontal resolution (in pixels) + horizontal_resolution_pix : uint32_t + Horizontal resolution (in pixels) - vertical_resolution_pix : uint32_t - Vertical resolution (in pixels) + vertical_resolution_pix : uint32_t + Vertical resolution (in pixels) - bit_rate_b_s : uint32_t - Bit rate (in bits per second) + bit_rate_b_s : uint32_t + Bit rate (in bits per second) - rotation_deg : uint32_t - Video image rotation (clockwise, 0-359 degrees) + rotation_deg : uint32_t + Video image rotation (clockwise, 0-359 degrees) - uri : std::string - Video stream URI + uri : std::string + Video stream URI - horizontal_fov_deg : float - Horizontal fov in degrees + horizontal_fov_deg : float + Horizontal fov in degrees - """ - - + """ def __init__( - self, - frame_rate_hz, - horizontal_resolution_pix, - vertical_resolution_pix, - bit_rate_b_s, - rotation_deg, - uri, - horizontal_fov_deg): - """ Initializes the VideoStreamSettings object """ + self, + frame_rate_hz, + horizontal_resolution_pix, + vertical_resolution_pix, + bit_rate_b_s, + rotation_deg, + uri, + horizontal_fov_deg, + ): + """Initializes the VideoStreamSettings object""" self.frame_rate_hz = frame_rate_hz self.horizontal_resolution_pix = horizontal_resolution_pix self.vertical_resolution_pix = vertical_resolution_pix @@ -445,147 +364,109 @@ def __init__( self.horizontal_fov_deg = horizontal_fov_deg def __eq__(self, to_compare): - """ Checks if two VideoStreamSettings are the same """ + """Checks if two VideoStreamSettings are the same""" try: # Try to compare - this likely fails when it is compared to a non # VideoStreamSettings object - return \ - (self.frame_rate_hz == to_compare.frame_rate_hz) and \ - (self.horizontal_resolution_pix == to_compare.horizontal_resolution_pix) and \ - (self.vertical_resolution_pix == to_compare.vertical_resolution_pix) and \ - (self.bit_rate_b_s == to_compare.bit_rate_b_s) and \ - (self.rotation_deg == to_compare.rotation_deg) and \ - (self.uri == to_compare.uri) and \ - (self.horizontal_fov_deg == to_compare.horizontal_fov_deg) + return ( + (self.frame_rate_hz == to_compare.frame_rate_hz) + and ( + self.horizontal_resolution_pix + == to_compare.horizontal_resolution_pix + ) + and (self.vertical_resolution_pix == to_compare.vertical_resolution_pix) + and (self.bit_rate_b_s == to_compare.bit_rate_b_s) + and (self.rotation_deg == to_compare.rotation_deg) + and (self.uri == to_compare.uri) + and (self.horizontal_fov_deg == to_compare.horizontal_fov_deg) + ) except AttributeError: return False def __str__(self): - """ VideoStreamSettings in string representation """ - struct_repr = ", ".join([ + """VideoStreamSettings in string representation""" + struct_repr = ", ".join( + [ "frame_rate_hz: " + str(self.frame_rate_hz), "horizontal_resolution_pix: " + str(self.horizontal_resolution_pix), "vertical_resolution_pix: " + str(self.vertical_resolution_pix), "bit_rate_b_s: " + str(self.bit_rate_b_s), "rotation_deg: " + str(self.rotation_deg), "uri: " + str(self.uri), - "horizontal_fov_deg: " + str(self.horizontal_fov_deg) - ]) + "horizontal_fov_deg: " + str(self.horizontal_fov_deg), + ] + ) return f"VideoStreamSettings: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVideoStreamSettings): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VideoStreamSettings( - - rpcVideoStreamSettings.frame_rate_hz, - - - rpcVideoStreamSettings.horizontal_resolution_pix, - - - rpcVideoStreamSettings.vertical_resolution_pix, - - - rpcVideoStreamSettings.bit_rate_b_s, - - - rpcVideoStreamSettings.rotation_deg, - - - rpcVideoStreamSettings.uri, - - - rpcVideoStreamSettings.horizontal_fov_deg - ) + rpcVideoStreamSettings.frame_rate_hz, + rpcVideoStreamSettings.horizontal_resolution_pix, + rpcVideoStreamSettings.vertical_resolution_pix, + rpcVideoStreamSettings.bit_rate_b_s, + rpcVideoStreamSettings.rotation_deg, + rpcVideoStreamSettings.uri, + rpcVideoStreamSettings.horizontal_fov_deg, + ) def translate_to_rpc(self, rpcVideoStreamSettings): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVideoStreamSettings.frame_rate_hz = self.frame_rate_hz - - - - - - rpcVideoStreamSettings.horizontal_resolution_pix = self.horizontal_resolution_pix - - - - - + + rpcVideoStreamSettings.horizontal_resolution_pix = ( + self.horizontal_resolution_pix + ) + rpcVideoStreamSettings.vertical_resolution_pix = self.vertical_resolution_pix - - - - - + rpcVideoStreamSettings.bit_rate_b_s = self.bit_rate_b_s - - - - - + rpcVideoStreamSettings.rotation_deg = self.rotation_deg - - - - - + rpcVideoStreamSettings.uri = self.uri - - - - - + rpcVideoStreamSettings.horizontal_fov_deg = self.horizontal_fov_deg - - - class VideoStreamInfo: """ - Information about the video stream. + Information about the video stream. - Parameters - ---------- - stream_id : int32_t - Stream ID + Parameters + ---------- + stream_id : int32_t + Stream ID - settings : VideoStreamSettings - Video stream settings + settings : VideoStreamSettings + Video stream settings - status : VideoStreamStatus - Current status of video streaming + status : VideoStreamStatus + Current status of video streaming - spectrum : VideoStreamSpectrum - Light-spectrum of the video stream + spectrum : VideoStreamSpectrum + Light-spectrum of the video stream - """ + """ - - class VideoStreamStatus(Enum): """ - Video stream status type. + Video stream status type. - Values - ------ - NOT_RUNNING - Video stream is not running + Values + ------ + NOT_RUNNING + Video stream is not running - IN_PROGRESS - Video stream is running + IN_PROGRESS + Video stream is running - """ + """ - NOT_RUNNING = 0 IN_PROGRESS = 1 @@ -597,34 +478,38 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == camera_pb2.VideoStreamInfo.VIDEO_STREAM_STATUS_NOT_RUNNING: + """Parses a gRPC response""" + if ( + rpc_enum_value + == camera_pb2.VideoStreamInfo.VIDEO_STREAM_STATUS_NOT_RUNNING + ): return VideoStreamInfo.VideoStreamStatus.NOT_RUNNING - if rpc_enum_value == camera_pb2.VideoStreamInfo.VIDEO_STREAM_STATUS_IN_PROGRESS: + if ( + rpc_enum_value + == camera_pb2.VideoStreamInfo.VIDEO_STREAM_STATUS_IN_PROGRESS + ): return VideoStreamInfo.VideoStreamStatus.IN_PROGRESS def __str__(self): return self.name - - + class VideoStreamSpectrum(Enum): """ - Video stream light spectrum type + Video stream light spectrum type - Values - ------ - UNKNOWN - Unknown + Values + ------ + UNKNOWN + Unknown - VISIBLE_LIGHT - Visible light + VISIBLE_LIGHT + Visible light - INFRARED - Infrared + INFRARED + Infrared - """ + """ - UNKNOWN = 0 VISIBLE_LIGHT = 1 INFRARED = 2 @@ -639,314 +524,260 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == camera_pb2.VideoStreamInfo.VIDEO_STREAM_SPECTRUM_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == camera_pb2.VideoStreamInfo.VIDEO_STREAM_SPECTRUM_UNKNOWN + ): return VideoStreamInfo.VideoStreamSpectrum.UNKNOWN - if rpc_enum_value == camera_pb2.VideoStreamInfo.VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT: + if ( + rpc_enum_value + == camera_pb2.VideoStreamInfo.VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT + ): return VideoStreamInfo.VideoStreamSpectrum.VISIBLE_LIGHT - if rpc_enum_value == camera_pb2.VideoStreamInfo.VIDEO_STREAM_SPECTRUM_INFRARED: + if ( + rpc_enum_value + == camera_pb2.VideoStreamInfo.VIDEO_STREAM_SPECTRUM_INFRARED + ): return VideoStreamInfo.VideoStreamSpectrum.INFRARED def __str__(self): return self.name - - def __init__( - self, - stream_id, - settings, - status, - spectrum): - """ Initializes the VideoStreamInfo object """ + def __init__(self, stream_id, settings, status, spectrum): + """Initializes the VideoStreamInfo object""" self.stream_id = stream_id self.settings = settings self.status = status self.spectrum = spectrum def __eq__(self, to_compare): - """ Checks if two VideoStreamInfo are the same """ + """Checks if two VideoStreamInfo are the same""" try: # Try to compare - this likely fails when it is compared to a non # VideoStreamInfo object - return \ - (self.stream_id == to_compare.stream_id) and \ - (self.settings == to_compare.settings) and \ - (self.status == to_compare.status) and \ - (self.spectrum == to_compare.spectrum) + return ( + (self.stream_id == to_compare.stream_id) + and (self.settings == to_compare.settings) + and (self.status == to_compare.status) + and (self.spectrum == to_compare.spectrum) + ) except AttributeError: return False def __str__(self): - """ VideoStreamInfo in string representation """ - struct_repr = ", ".join([ + """VideoStreamInfo in string representation""" + struct_repr = ", ".join( + [ "stream_id: " + str(self.stream_id), "settings: " + str(self.settings), "status: " + str(self.status), - "spectrum: " + str(self.spectrum) - ]) + "spectrum: " + str(self.spectrum), + ] + ) return f"VideoStreamInfo: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVideoStreamInfo): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VideoStreamInfo( - - rpcVideoStreamInfo.stream_id, - - - VideoStreamSettings.translate_from_rpc(rpcVideoStreamInfo.settings), - - - VideoStreamInfo.VideoStreamStatus.translate_from_rpc(rpcVideoStreamInfo.status), - - - VideoStreamInfo.VideoStreamSpectrum.translate_from_rpc(rpcVideoStreamInfo.spectrum) - ) + rpcVideoStreamInfo.stream_id, + VideoStreamSettings.translate_from_rpc(rpcVideoStreamInfo.settings), + VideoStreamInfo.VideoStreamStatus.translate_from_rpc( + rpcVideoStreamInfo.status + ), + VideoStreamInfo.VideoStreamSpectrum.translate_from_rpc( + rpcVideoStreamInfo.spectrum + ), + ) def translate_to_rpc(self, rpcVideoStreamInfo): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVideoStreamInfo.stream_id = self.stream_id - - - - - + self.settings.translate_to_rpc(rpcVideoStreamInfo.settings) - - - - - + rpcVideoStreamInfo.status = self.status.translate_to_rpc() - - - - - + rpcVideoStreamInfo.spectrum = self.spectrum.translate_to_rpc() - - - class ModeUpdate: """ - An update about the current mode + An update about the current mode - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - mode : Mode - Camera mode + mode : Mode + Camera mode - """ - - + """ - def __init__( - self, - component_id, - mode): - """ Initializes the ModeUpdate object """ + def __init__(self, component_id, mode): + """Initializes the ModeUpdate object""" self.component_id = component_id self.mode = mode def __eq__(self, to_compare): - """ Checks if two ModeUpdate are the same """ + """Checks if two ModeUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # ModeUpdate object - return \ - (self.component_id == to_compare.component_id) and \ - (self.mode == to_compare.mode) + return (self.component_id == to_compare.component_id) and ( + self.mode == to_compare.mode + ) except AttributeError: return False def __str__(self): - """ ModeUpdate in string representation """ - struct_repr = ", ".join([ - "component_id: " + str(self.component_id), - "mode: " + str(self.mode) - ]) + """ModeUpdate in string representation""" + struct_repr = ", ".join( + ["component_id: " + str(self.component_id), "mode: " + str(self.mode)] + ) return f"ModeUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcModeUpdate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ModeUpdate( - - rpcModeUpdate.component_id, - - - Mode.translate_from_rpc(rpcModeUpdate.mode) - ) + rpcModeUpdate.component_id, Mode.translate_from_rpc(rpcModeUpdate.mode) + ) def translate_to_rpc(self, rpcModeUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcModeUpdate.component_id = self.component_id - - - - - + rpcModeUpdate.mode = self.mode.translate_to_rpc() - - - class VideoStreamUpdate: """ - An update about a video stream - - Parameters - ---------- - component_id : int32_t - Component ID + An update about a video stream - video_stream_info : VideoStreamInfo - Video stream info + Parameters + ---------- + component_id : int32_t + Component ID - """ + video_stream_info : VideoStreamInfo + Video stream info - + """ - def __init__( - self, - component_id, - video_stream_info): - """ Initializes the VideoStreamUpdate object """ + def __init__(self, component_id, video_stream_info): + """Initializes the VideoStreamUpdate object""" self.component_id = component_id self.video_stream_info = video_stream_info def __eq__(self, to_compare): - """ Checks if two VideoStreamUpdate are the same """ + """Checks if two VideoStreamUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # VideoStreamUpdate object - return \ - (self.component_id == to_compare.component_id) and \ - (self.video_stream_info == to_compare.video_stream_info) + return (self.component_id == to_compare.component_id) and ( + self.video_stream_info == to_compare.video_stream_info + ) except AttributeError: return False def __str__(self): - """ VideoStreamUpdate in string representation """ - struct_repr = ", ".join([ + """VideoStreamUpdate in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), - "video_stream_info: " + str(self.video_stream_info) - ]) + "video_stream_info: " + str(self.video_stream_info), + ] + ) return f"VideoStreamUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVideoStreamUpdate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VideoStreamUpdate( - - rpcVideoStreamUpdate.component_id, - - - VideoStreamInfo.translate_from_rpc(rpcVideoStreamUpdate.video_stream_info) - ) + rpcVideoStreamUpdate.component_id, + VideoStreamInfo.translate_from_rpc(rpcVideoStreamUpdate.video_stream_info), + ) def translate_to_rpc(self, rpcVideoStreamUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVideoStreamUpdate.component_id = self.component_id - - - - - + self.video_stream_info.translate_to_rpc(rpcVideoStreamUpdate.video_stream_info) - - - class Storage: """ - Information about the camera's storage status. + Information about the camera's storage status. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - video_on : bool - Whether video recording is currently in process + video_on : bool + Whether video recording is currently in process - photo_interval_on : bool - Whether a photo interval is currently in process + photo_interval_on : bool + Whether a photo interval is currently in process - used_storage_mib : float - Used storage (in MiB) + used_storage_mib : float + Used storage (in MiB) - available_storage_mib : float - Available storage (in MiB) + available_storage_mib : float + Available storage (in MiB) - total_storage_mib : float - Total storage (in MiB) + total_storage_mib : float + Total storage (in MiB) - recording_time_s : float - Elapsed time since starting the video recording (in seconds) + recording_time_s : float + Elapsed time since starting the video recording (in seconds) - media_folder_name : std::string - Current folder name where media are saved + media_folder_name : std::string + Current folder name where media are saved - storage_status : StorageStatus - Storage status + storage_status : StorageStatus + Storage status - storage_id : uint32_t - Storage ID starting at 1 + storage_id : uint32_t + Storage ID starting at 1 - storage_type : StorageType - Storage type + storage_type : StorageType + Storage type - """ + """ - - class StorageStatus(Enum): """ - Storage status type. + Storage status type. - Values - ------ - NOT_AVAILABLE - Status not available + Values + ------ + NOT_AVAILABLE + Status not available - UNFORMATTED - Storage is not formatted (i.e. has no recognized file system) + UNFORMATTED + Storage is not formatted (i.e. has no recognized file system) - FORMATTED - Storage is formatted (i.e. has recognized a file system) + FORMATTED + Storage is formatted (i.e. has recognized a file system) - NOT_SUPPORTED - Storage status is not supported + NOT_SUPPORTED + Storage status is not supported - """ + """ - NOT_AVAILABLE = 0 UNFORMATTED = 1 FORMATTED = 2 @@ -964,7 +795,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_pb2.Storage.STORAGE_STATUS_NOT_AVAILABLE: return Storage.StorageStatus.NOT_AVAILABLE if rpc_enum_value == camera_pb2.Storage.STORAGE_STATUS_UNFORMATTED: @@ -976,35 +807,33 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - + class StorageType(Enum): """ - Storage type. + Storage type. - Values - ------ - UNKNOWN - Storage type unknown + Values + ------ + UNKNOWN + Storage type unknown - USB_STICK - Storage type USB stick + USB_STICK + Storage type USB stick - SD - Storage type SD card + SD + Storage type SD card - MICROSD - Storage type MicroSD card + MICROSD + Storage type MicroSD card - HD - Storage type HD mass storage + HD + Storage type HD mass storage - OTHER - Storage type other, not listed + OTHER + Storage type other, not listed - """ + """ - UNKNOWN = 0 USB_STICK = 1 SD = 2 @@ -1028,7 +857,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_pb2.Storage.STORAGE_TYPE_UNKNOWN: return Storage.StorageType.UNKNOWN if rpc_enum_value == camera_pb2.Storage.STORAGE_TYPE_USB_STICK: @@ -1044,22 +873,22 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - def __init__( - self, - component_id, - video_on, - photo_interval_on, - used_storage_mib, - available_storage_mib, - total_storage_mib, - recording_time_s, - media_folder_name, - storage_status, - storage_id, - storage_type): - """ Initializes the Storage object """ + self, + component_id, + video_on, + photo_interval_on, + used_storage_mib, + available_storage_mib, + total_storage_mib, + recording_time_s, + media_folder_name, + storage_status, + storage_id, + storage_type, + ): + """Initializes the Storage object""" self.component_id = component_id self.video_on = video_on self.photo_interval_on = photo_interval_on @@ -1073,29 +902,31 @@ def __init__( self.storage_type = storage_type def __eq__(self, to_compare): - """ Checks if two Storage are the same """ + """Checks if two Storage are the same""" try: # Try to compare - this likely fails when it is compared to a non # Storage object - return \ - (self.component_id == to_compare.component_id) and \ - (self.video_on == to_compare.video_on) and \ - (self.photo_interval_on == to_compare.photo_interval_on) and \ - (self.used_storage_mib == to_compare.used_storage_mib) and \ - (self.available_storage_mib == to_compare.available_storage_mib) and \ - (self.total_storage_mib == to_compare.total_storage_mib) and \ - (self.recording_time_s == to_compare.recording_time_s) and \ - (self.media_folder_name == to_compare.media_folder_name) and \ - (self.storage_status == to_compare.storage_status) and \ - (self.storage_id == to_compare.storage_id) and \ - (self.storage_type == to_compare.storage_type) + return ( + (self.component_id == to_compare.component_id) + and (self.video_on == to_compare.video_on) + and (self.photo_interval_on == to_compare.photo_interval_on) + and (self.used_storage_mib == to_compare.used_storage_mib) + and (self.available_storage_mib == to_compare.available_storage_mib) + and (self.total_storage_mib == to_compare.total_storage_mib) + and (self.recording_time_s == to_compare.recording_time_s) + and (self.media_folder_name == to_compare.media_folder_name) + and (self.storage_status == to_compare.storage_status) + and (self.storage_id == to_compare.storage_id) + and (self.storage_type == to_compare.storage_type) + ) except AttributeError: return False def __str__(self): - """ Storage in string representation """ - struct_repr = ", ".join([ + """Storage in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), "video_on: " + str(self.video_on), "photo_interval_on: " + str(self.photo_interval_on), @@ -1106,421 +937,309 @@ def __str__(self): "media_folder_name: " + str(self.media_folder_name), "storage_status: " + str(self.storage_status), "storage_id: " + str(self.storage_id), - "storage_type: " + str(self.storage_type) - ]) + "storage_type: " + str(self.storage_type), + ] + ) return f"Storage: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStorage): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Storage( - - rpcStorage.component_id, - - - rpcStorage.video_on, - - - rpcStorage.photo_interval_on, - - - rpcStorage.used_storage_mib, - - - rpcStorage.available_storage_mib, - - - rpcStorage.total_storage_mib, - - - rpcStorage.recording_time_s, - - - rpcStorage.media_folder_name, - - - Storage.StorageStatus.translate_from_rpc(rpcStorage.storage_status), - - - rpcStorage.storage_id, - - - Storage.StorageType.translate_from_rpc(rpcStorage.storage_type) - ) + rpcStorage.component_id, + rpcStorage.video_on, + rpcStorage.photo_interval_on, + rpcStorage.used_storage_mib, + rpcStorage.available_storage_mib, + rpcStorage.total_storage_mib, + rpcStorage.recording_time_s, + rpcStorage.media_folder_name, + Storage.StorageStatus.translate_from_rpc(rpcStorage.storage_status), + rpcStorage.storage_id, + Storage.StorageType.translate_from_rpc(rpcStorage.storage_type), + ) def translate_to_rpc(self, rpcStorage): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStorage.component_id = self.component_id - - - - - + rpcStorage.video_on = self.video_on - - - - - + rpcStorage.photo_interval_on = self.photo_interval_on - - - - - + rpcStorage.used_storage_mib = self.used_storage_mib - - - - - + rpcStorage.available_storage_mib = self.available_storage_mib - - - - - + rpcStorage.total_storage_mib = self.total_storage_mib - - - - - + rpcStorage.recording_time_s = self.recording_time_s - - - - - + rpcStorage.media_folder_name = self.media_folder_name - - - - - + rpcStorage.storage_status = self.storage_status.translate_to_rpc() - - - - - + rpcStorage.storage_id = self.storage_id - - - - - + rpcStorage.storage_type = self.storage_type.translate_to_rpc() - - - class StorageUpdate: """ - An update about storage + An update about storage - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - storage : Storage - Storage + storage : Storage + Storage - """ - - + """ - def __init__( - self, - component_id, - storage): - """ Initializes the StorageUpdate object """ + def __init__(self, component_id, storage): + """Initializes the StorageUpdate object""" self.component_id = component_id self.storage = storage def __eq__(self, to_compare): - """ Checks if two StorageUpdate are the same """ + """Checks if two StorageUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # StorageUpdate object - return \ - (self.component_id == to_compare.component_id) and \ - (self.storage == to_compare.storage) + return (self.component_id == to_compare.component_id) and ( + self.storage == to_compare.storage + ) except AttributeError: return False def __str__(self): - """ StorageUpdate in string representation """ - struct_repr = ", ".join([ - "component_id: " + str(self.component_id), - "storage: " + str(self.storage) - ]) + """StorageUpdate in string representation""" + struct_repr = ", ".join( + ["component_id: " + str(self.component_id), "storage: " + str(self.storage)] + ) return f"StorageUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStorageUpdate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return StorageUpdate( - - rpcStorageUpdate.component_id, - - - Storage.translate_from_rpc(rpcStorageUpdate.storage) - ) + rpcStorageUpdate.component_id, + Storage.translate_from_rpc(rpcStorageUpdate.storage), + ) def translate_to_rpc(self, rpcStorageUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStorageUpdate.component_id = self.component_id - - - - - + self.storage.translate_to_rpc(rpcStorageUpdate.storage) - - - class CurrentSettingsUpdate: """ - An update about a current setting + An update about a current setting - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - current_settings : [Setting] - List of current settings + current_settings : [Setting] + List of current settings - """ - - + """ - def __init__( - self, - component_id, - current_settings): - """ Initializes the CurrentSettingsUpdate object """ + def __init__(self, component_id, current_settings): + """Initializes the CurrentSettingsUpdate object""" self.component_id = component_id self.current_settings = current_settings def __eq__(self, to_compare): - """ Checks if two CurrentSettingsUpdate are the same """ + """Checks if two CurrentSettingsUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # CurrentSettingsUpdate object - return \ - (self.component_id == to_compare.component_id) and \ - (self.current_settings == to_compare.current_settings) + return (self.component_id == to_compare.component_id) and ( + self.current_settings == to_compare.current_settings + ) except AttributeError: return False def __str__(self): - """ CurrentSettingsUpdate in string representation """ - struct_repr = ", ".join([ + """CurrentSettingsUpdate in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), - "current_settings: " + str(self.current_settings) - ]) + "current_settings: " + str(self.current_settings), + ] + ) return f"CurrentSettingsUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCurrentSettingsUpdate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CurrentSettingsUpdate( - - rpcCurrentSettingsUpdate.component_id, - - - list(map(lambda elem: Setting.translate_from_rpc(elem), rpcCurrentSettingsUpdate.current_settings)) + rpcCurrentSettingsUpdate.component_id, + list( + map( + lambda elem: Setting.translate_from_rpc(elem), + rpcCurrentSettingsUpdate.current_settings, ) + ), + ) def translate_to_rpc(self, rpcCurrentSettingsUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCurrentSettingsUpdate.component_id = self.component_id - - - - - + rpc_elems_list = [] for elem in self.current_settings: - rpc_elem = camera_pb2.Setting() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcCurrentSettingsUpdate.current_settings.extend(rpc_elems_list) - - - class PossibleSettingOptionsUpdate: """ - An update about possible setting options + An update about possible setting options - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - setting_options : [SettingOptions] - List of settings that can be changed + setting_options : [SettingOptions] + List of settings that can be changed - """ - - + """ - def __init__( - self, - component_id, - setting_options): - """ Initializes the PossibleSettingOptionsUpdate object """ + def __init__(self, component_id, setting_options): + """Initializes the PossibleSettingOptionsUpdate object""" self.component_id = component_id self.setting_options = setting_options def __eq__(self, to_compare): - """ Checks if two PossibleSettingOptionsUpdate are the same """ + """Checks if two PossibleSettingOptionsUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # PossibleSettingOptionsUpdate object - return \ - (self.component_id == to_compare.component_id) and \ - (self.setting_options == to_compare.setting_options) + return (self.component_id == to_compare.component_id) and ( + self.setting_options == to_compare.setting_options + ) except AttributeError: return False def __str__(self): - """ PossibleSettingOptionsUpdate in string representation """ - struct_repr = ", ".join([ + """PossibleSettingOptionsUpdate in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), - "setting_options: " + str(self.setting_options) - ]) + "setting_options: " + str(self.setting_options), + ] + ) return f"PossibleSettingOptionsUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPossibleSettingOptionsUpdate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PossibleSettingOptionsUpdate( - - rpcPossibleSettingOptionsUpdate.component_id, - - - list(map(lambda elem: SettingOptions.translate_from_rpc(elem), rpcPossibleSettingOptionsUpdate.setting_options)) + rpcPossibleSettingOptionsUpdate.component_id, + list( + map( + lambda elem: SettingOptions.translate_from_rpc(elem), + rpcPossibleSettingOptionsUpdate.setting_options, ) + ), + ) def translate_to_rpc(self, rpcPossibleSettingOptionsUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPossibleSettingOptionsUpdate.component_id = self.component_id - - - - - + rpc_elems_list = [] for elem in self.setting_options: - rpc_elem = camera_pb2.SettingOptions() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcPossibleSettingOptionsUpdate.setting_options.extend(rpc_elems_list) - - - class CameraResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for camera commands + Possible results returned for camera commands - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Command executed successfully + SUCCESS + Command executed successfully - IN_PROGRESS - Command in progress + IN_PROGRESS + Command in progress - BUSY - Camera is busy and rejected command + BUSY + Camera is busy and rejected command - DENIED - Camera denied the command + DENIED + Camera denied the command - ERROR - An error has occurred while executing the command + ERROR + An error has occurred while executing the command - TIMEOUT - Command timed out + TIMEOUT + Command timed out - WRONG_ARGUMENT - Command has wrong argument(s) + WRONG_ARGUMENT + Command has wrong argument(s) - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - PROTOCOL_UNSUPPORTED - Definition file protocol not supported + PROTOCOL_UNSUPPORTED + Definition file protocol not supported - UNAVAILABLE - Not available (yet) + UNAVAILABLE + Not available (yet) - CAMERA_ID_INVALID - Camera with camera ID not found + CAMERA_ID_INVALID + Camera with camera ID not found - ACTION_UNSUPPORTED - Camera action not supported + ACTION_UNSUPPORTED + Camera action not supported - """ + """ - UNKNOWN = 0 SUCCESS = 1 IN_PROGRESS = 2 @@ -1565,7 +1284,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_pb2.CameraResult.RESULT_UNKNOWN: return CameraResult.Result.UNKNOWN if rpc_enum_value == camera_pb2.CameraResult.RESULT_SUCCESS: @@ -1595,425 +1314,323 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the CameraResult object """ + def __init__(self, result, result_str): + """Initializes the CameraResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two CameraResult are the same """ + """Checks if two CameraResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # CameraResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ CameraResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """CameraResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"CameraResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCameraResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CameraResult( - - CameraResult.Result.translate_from_rpc(rpcCameraResult.result), - - - rpcCameraResult.result_str - ) + CameraResult.Result.translate_from_rpc(rpcCameraResult.result), + rpcCameraResult.result_str, + ) def translate_to_rpc(self, rpcCameraResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCameraResult.result = self.result.translate_to_rpc() - - - - - + rpcCameraResult.result_str = self.result_str - - - class Position: """ - Position type in global coordinates. + Position type in global coordinates. - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - longitude_deg : double - Longitude in degrees (range: -180 to +180) + longitude_deg : double + Longitude in degrees (range: -180 to +180) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - relative_altitude_m : float - Altitude relative to takeoff altitude in metres + relative_altitude_m : float + Altitude relative to takeoff altitude in metres - """ - - + """ def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m, - relative_altitude_m): - """ Initializes the Position object """ + self, latitude_deg, longitude_deg, absolute_altitude_m, relative_altitude_m + ): + """Initializes the Position object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m def __eq__(self, to_compare): - """ Checks if two Position are the same """ + """Checks if two Position are the same""" try: # Try to compare - this likely fails when it is compared to a non # Position object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.relative_altitude_m == to_compare.relative_altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.relative_altitude_m == to_compare.relative_altitude_m) + ) except AttributeError: return False def __str__(self): - """ Position in string representation """ - struct_repr = ", ".join([ + """Position in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), "absolute_altitude_m: " + str(self.absolute_altitude_m), - "relative_altitude_m: " + str(self.relative_altitude_m) - ]) + "relative_altitude_m: " + str(self.relative_altitude_m), + ] + ) return f"Position: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPosition): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Position( - - rpcPosition.latitude_deg, - - - rpcPosition.longitude_deg, - - - rpcPosition.absolute_altitude_m, - - - rpcPosition.relative_altitude_m - ) + rpcPosition.latitude_deg, + rpcPosition.longitude_deg, + rpcPosition.absolute_altitude_m, + rpcPosition.relative_altitude_m, + ) def translate_to_rpc(self, rpcPosition): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPosition.latitude_deg = self.latitude_deg - - - - - + rpcPosition.longitude_deg = self.longitude_deg - - - - - + rpcPosition.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcPosition.relative_altitude_m = self.relative_altitude_m - - - class Quaternion: """ - Quaternion type. + Quaternion type. - All rotations and axis systems follow the right-hand rule. - The Hamilton quaternion product definition is used. - A zero-rotation quaternion is represented by (1,0,0,0). - The quaternion could also be written as w + xi + yj + zk. + All rotations and axis systems follow the right-hand rule. + The Hamilton quaternion product definition is used. + A zero-rotation quaternion is represented by (1,0,0,0). + The quaternion could also be written as w + xi + yj + zk. - For more info see: https://en.wikipedia.org/wiki/Quaternion + For more info see: https://en.wikipedia.org/wiki/Quaternion - Parameters - ---------- - w : float - Quaternion entry 0, also denoted as a + Parameters + ---------- + w : float + Quaternion entry 0, also denoted as a - x : float - Quaternion entry 1, also denoted as b + x : float + Quaternion entry 1, also denoted as b - y : float - Quaternion entry 2, also denoted as c + y : float + Quaternion entry 2, also denoted as c - z : float - Quaternion entry 3, also denoted as d + z : float + Quaternion entry 3, also denoted as d - """ - - + """ - def __init__( - self, - w, - x, - y, - z): - """ Initializes the Quaternion object """ + def __init__(self, w, x, y, z): + """Initializes the Quaternion object""" self.w = w self.x = x self.y = y self.z = z def __eq__(self, to_compare): - """ Checks if two Quaternion are the same """ + """Checks if two Quaternion are the same""" try: # Try to compare - this likely fails when it is compared to a non # Quaternion object - return \ - (self.w == to_compare.w) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) + return ( + (self.w == to_compare.w) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + ) except AttributeError: return False def __str__(self): - """ Quaternion in string representation """ - struct_repr = ", ".join([ + """Quaternion in string representation""" + struct_repr = ", ".join( + [ "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), - "z: " + str(self.z) - ]) + "z: " + str(self.z), + ] + ) return f"Quaternion: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcQuaternion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Quaternion( - - rpcQuaternion.w, - - - rpcQuaternion.x, - - - rpcQuaternion.y, - - - rpcQuaternion.z - ) + rpcQuaternion.w, rpcQuaternion.x, rpcQuaternion.y, rpcQuaternion.z + ) def translate_to_rpc(self, rpcQuaternion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcQuaternion.w = self.w - - - - - + rpcQuaternion.x = self.x - - - - - + rpcQuaternion.y = self.y - - - - - + rpcQuaternion.z = self.z - - - class EulerAngle: """ - Euler angle type. + Euler angle type. - All rotations and axis systems follow the right-hand rule. - The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. + All rotations and axis systems follow the right-hand rule. + The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. - For more info see https://en.wikipedia.org/wiki/Euler_angles + For more info see https://en.wikipedia.org/wiki/Euler_angles - Parameters - ---------- - roll_deg : float - Roll angle in degrees, positive is banking to the right + Parameters + ---------- + roll_deg : float + Roll angle in degrees, positive is banking to the right - pitch_deg : float - Pitch angle in degrees, positive is pitching nose up + pitch_deg : float + Pitch angle in degrees, positive is pitching nose up - yaw_deg : float - Yaw angle in degrees, positive is clock-wise seen from above + yaw_deg : float + Yaw angle in degrees, positive is clock-wise seen from above - """ - - + """ - def __init__( - self, - roll_deg, - pitch_deg, - yaw_deg): - """ Initializes the EulerAngle object """ + def __init__(self, roll_deg, pitch_deg, yaw_deg): + """Initializes the EulerAngle object""" self.roll_deg = roll_deg self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg def __eq__(self, to_compare): - """ Checks if two EulerAngle are the same """ + """Checks if two EulerAngle are the same""" try: # Try to compare - this likely fails when it is compared to a non # EulerAngle object - return \ - (self.roll_deg == to_compare.roll_deg) and \ - (self.pitch_deg == to_compare.pitch_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) + return ( + (self.roll_deg == to_compare.roll_deg) + and (self.pitch_deg == to_compare.pitch_deg) + and (self.yaw_deg == to_compare.yaw_deg) + ) except AttributeError: return False def __str__(self): - """ EulerAngle in string representation """ - struct_repr = ", ".join([ + """EulerAngle in string representation""" + struct_repr = ", ".join( + [ "roll_deg: " + str(self.roll_deg), "pitch_deg: " + str(self.pitch_deg), - "yaw_deg: " + str(self.yaw_deg) - ]) + "yaw_deg: " + str(self.yaw_deg), + ] + ) return f"EulerAngle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEulerAngle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return EulerAngle( - - rpcEulerAngle.roll_deg, - - - rpcEulerAngle.pitch_deg, - - - rpcEulerAngle.yaw_deg - ) + rpcEulerAngle.roll_deg, rpcEulerAngle.pitch_deg, rpcEulerAngle.yaw_deg + ) def translate_to_rpc(self, rpcEulerAngle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEulerAngle.roll_deg = self.roll_deg - - - - - + rpcEulerAngle.pitch_deg = self.pitch_deg - - - - - + rpcEulerAngle.yaw_deg = self.yaw_deg - - - class CaptureInfo: """ - Information about a picture just captured. - - Parameters - ---------- - component_id : int32_t - Component ID + Information about a picture just captured. - position : Position - Location where the picture was taken + Parameters + ---------- + component_id : int32_t + Component ID - attitude_quaternion : Quaternion - Attitude of the camera when the picture was taken (quaternion) + position : Position + Location where the picture was taken - attitude_euler_angle : EulerAngle - Attitude of the camera when the picture was taken (euler angle) + attitude_quaternion : Quaternion + Attitude of the camera when the picture was taken (quaternion) - time_utc_us : uint64_t - Timestamp in UTC (since UNIX epoch) in microseconds + attitude_euler_angle : EulerAngle + Attitude of the camera when the picture was taken (euler angle) - is_success : bool - True if the capture was successful + time_utc_us : uint64_t + Timestamp in UTC (since UNIX epoch) in microseconds - index : int32_t - Zero-based index of this image since vehicle was armed + is_success : bool + True if the capture was successful - file_url : std::string - Download URL of this image + index : int32_t + Zero-based index of this image since vehicle was armed - """ + file_url : std::string + Download URL of this image - + """ def __init__( - self, - component_id, - position, - attitude_quaternion, - attitude_euler_angle, - time_utc_us, - is_success, - index, - file_url): - """ Initializes the CaptureInfo object """ + self, + component_id, + position, + attitude_quaternion, + attitude_euler_angle, + time_utc_us, + is_success, + index, + file_url, + ): + """Initializes the CaptureInfo object""" self.component_id = component_id self.position = position self.attitude_quaternion = attitude_quaternion @@ -2024,26 +1641,28 @@ def __init__( self.file_url = file_url def __eq__(self, to_compare): - """ Checks if two CaptureInfo are the same """ + """Checks if two CaptureInfo are the same""" try: # Try to compare - this likely fails when it is compared to a non # CaptureInfo object - return \ - (self.component_id == to_compare.component_id) and \ - (self.position == to_compare.position) and \ - (self.attitude_quaternion == to_compare.attitude_quaternion) and \ - (self.attitude_euler_angle == to_compare.attitude_euler_angle) and \ - (self.time_utc_us == to_compare.time_utc_us) and \ - (self.is_success == to_compare.is_success) and \ - (self.index == to_compare.index) and \ - (self.file_url == to_compare.file_url) + return ( + (self.component_id == to_compare.component_id) + and (self.position == to_compare.position) + and (self.attitude_quaternion == to_compare.attitude_quaternion) + and (self.attitude_euler_angle == to_compare.attitude_euler_angle) + and (self.time_utc_us == to_compare.time_utc_us) + and (self.is_success == to_compare.is_success) + and (self.index == to_compare.index) + and (self.file_url == to_compare.file_url) + ) except AttributeError: return False def __str__(self): - """ CaptureInfo in string representation """ - struct_repr = ", ".join([ + """CaptureInfo in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), "position: " + str(self.position), "attitude_quaternion: " + str(self.attitude_quaternion), @@ -2051,139 +1670,90 @@ def __str__(self): "time_utc_us: " + str(self.time_utc_us), "is_success: " + str(self.is_success), "index: " + str(self.index), - "file_url: " + str(self.file_url) - ]) + "file_url: " + str(self.file_url), + ] + ) return f"CaptureInfo: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCaptureInfo): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CaptureInfo( - - rpcCaptureInfo.component_id, - - - Position.translate_from_rpc(rpcCaptureInfo.position), - - - Quaternion.translate_from_rpc(rpcCaptureInfo.attitude_quaternion), - - - EulerAngle.translate_from_rpc(rpcCaptureInfo.attitude_euler_angle), - - - rpcCaptureInfo.time_utc_us, - - - rpcCaptureInfo.is_success, - - - rpcCaptureInfo.index, - - - rpcCaptureInfo.file_url - ) + rpcCaptureInfo.component_id, + Position.translate_from_rpc(rpcCaptureInfo.position), + Quaternion.translate_from_rpc(rpcCaptureInfo.attitude_quaternion), + EulerAngle.translate_from_rpc(rpcCaptureInfo.attitude_euler_angle), + rpcCaptureInfo.time_utc_us, + rpcCaptureInfo.is_success, + rpcCaptureInfo.index, + rpcCaptureInfo.file_url, + ) def translate_to_rpc(self, rpcCaptureInfo): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCaptureInfo.component_id = self.component_id - - - - - + self.position.translate_to_rpc(rpcCaptureInfo.position) - - - - - + self.attitude_quaternion.translate_to_rpc(rpcCaptureInfo.attitude_quaternion) - - - - - + self.attitude_euler_angle.translate_to_rpc(rpcCaptureInfo.attitude_euler_angle) - - - - - + rpcCaptureInfo.time_utc_us = self.time_utc_us - - - - - + rpcCaptureInfo.is_success = self.is_success - - - - - + rpcCaptureInfo.index = self.index - - - - - + rpcCaptureInfo.file_url = self.file_url - - - class Information: """ - Type to represent a camera information. + Type to represent a camera information. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - vendor_name : std::string - Name of the camera vendor + vendor_name : std::string + Name of the camera vendor - model_name : std::string - Name of the camera model + model_name : std::string + Name of the camera model - focal_length_mm : float - Focal length + focal_length_mm : float + Focal length - horizontal_sensor_size_mm : float - Horizontal sensor size + horizontal_sensor_size_mm : float + Horizontal sensor size - vertical_sensor_size_mm : float - Vertical sensor size + vertical_sensor_size_mm : float + Vertical sensor size - horizontal_resolution_px : uint32_t - Horizontal image resolution in pixels + horizontal_resolution_px : uint32_t + Horizontal image resolution in pixels - vertical_resolution_px : uint32_t - Vertical image resolution in pixels + vertical_resolution_px : uint32_t + Vertical image resolution in pixels - """ - - + """ def __init__( - self, - component_id, - vendor_name, - model_name, - focal_length_mm, - horizontal_sensor_size_mm, - vertical_sensor_size_mm, - horizontal_resolution_px, - vertical_resolution_px): - """ Initializes the Information object """ + self, + component_id, + vendor_name, + model_name, + focal_length_mm, + horizontal_sensor_size_mm, + vertical_sensor_size_mm, + horizontal_resolution_px, + vertical_resolution_px, + ): + """Initializes the Information object""" self.component_id = component_id self.vendor_name = vendor_name self.model_name = model_name @@ -2194,26 +1764,33 @@ def __init__( self.vertical_resolution_px = vertical_resolution_px def __eq__(self, to_compare): - """ Checks if two Information are the same """ + """Checks if two Information are the same""" try: # Try to compare - this likely fails when it is compared to a non # Information object - return \ - (self.component_id == to_compare.component_id) and \ - (self.vendor_name == to_compare.vendor_name) and \ - (self.model_name == to_compare.model_name) and \ - (self.focal_length_mm == to_compare.focal_length_mm) and \ - (self.horizontal_sensor_size_mm == to_compare.horizontal_sensor_size_mm) and \ - (self.vertical_sensor_size_mm == to_compare.vertical_sensor_size_mm) and \ - (self.horizontal_resolution_px == to_compare.horizontal_resolution_px) and \ - (self.vertical_resolution_px == to_compare.vertical_resolution_px) + return ( + (self.component_id == to_compare.component_id) + and (self.vendor_name == to_compare.vendor_name) + and (self.model_name == to_compare.model_name) + and (self.focal_length_mm == to_compare.focal_length_mm) + and ( + self.horizontal_sensor_size_mm + == to_compare.horizontal_sensor_size_mm + ) + and (self.vertical_sensor_size_mm == to_compare.vertical_sensor_size_mm) + and ( + self.horizontal_resolution_px == to_compare.horizontal_resolution_px + ) + and (self.vertical_resolution_px == to_compare.vertical_resolution_px) + ) except AttributeError: return False def __str__(self): - """ Information in string representation """ - struct_repr = ", ".join([ + """Information in string representation""" + struct_repr = ", ".join( + [ "component_id: " + str(self.component_id), "vendor_name: " + str(self.vendor_name), "model_name: " + str(self.model_name), @@ -2221,162 +1798,103 @@ def __str__(self): "horizontal_sensor_size_mm: " + str(self.horizontal_sensor_size_mm), "vertical_sensor_size_mm: " + str(self.vertical_sensor_size_mm), "horizontal_resolution_px: " + str(self.horizontal_resolution_px), - "vertical_resolution_px: " + str(self.vertical_resolution_px) - ]) + "vertical_resolution_px: " + str(self.vertical_resolution_px), + ] + ) return f"Information: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcInformation): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Information( - - rpcInformation.component_id, - - - rpcInformation.vendor_name, - - - rpcInformation.model_name, - - - rpcInformation.focal_length_mm, - - - rpcInformation.horizontal_sensor_size_mm, - - - rpcInformation.vertical_sensor_size_mm, - - - rpcInformation.horizontal_resolution_px, - - - rpcInformation.vertical_resolution_px - ) + rpcInformation.component_id, + rpcInformation.vendor_name, + rpcInformation.model_name, + rpcInformation.focal_length_mm, + rpcInformation.horizontal_sensor_size_mm, + rpcInformation.vertical_sensor_size_mm, + rpcInformation.horizontal_resolution_px, + rpcInformation.vertical_resolution_px, + ) def translate_to_rpc(self, rpcInformation): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcInformation.component_id = self.component_id - - - - - + rpcInformation.vendor_name = self.vendor_name - - - - - + rpcInformation.model_name = self.model_name - - - - - + rpcInformation.focal_length_mm = self.focal_length_mm - - - - - + rpcInformation.horizontal_sensor_size_mm = self.horizontal_sensor_size_mm - - - - - + rpcInformation.vertical_sensor_size_mm = self.vertical_sensor_size_mm - - - - - + rpcInformation.horizontal_resolution_px = self.horizontal_resolution_px - - - - - + rpcInformation.vertical_resolution_px = self.vertical_resolution_px - - - class CameraList: """ - Camera list - - Parameters - ---------- - cameras : [Information] - Camera items. + Camera list - """ + Parameters + ---------- + cameras : [Information] + Camera items. - + """ - def __init__( - self, - cameras): - """ Initializes the CameraList object """ + def __init__(self, cameras): + """Initializes the CameraList object""" self.cameras = cameras def __eq__(self, to_compare): - """ Checks if two CameraList are the same """ + """Checks if two CameraList are the same""" try: # Try to compare - this likely fails when it is compared to a non # CameraList object - return \ - (self.cameras == to_compare.cameras) + return self.cameras == to_compare.cameras except AttributeError: return False def __str__(self): - """ CameraList in string representation """ - struct_repr = ", ".join([ - "cameras: " + str(self.cameras) - ]) + """CameraList in string representation""" + struct_repr = ", ".join(["cameras: " + str(self.cameras)]) return f"CameraList: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCameraList): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CameraList( - - list(map(lambda elem: Information.translate_from_rpc(elem), rpcCameraList.cameras)) + list( + map( + lambda elem: Information.translate_from_rpc(elem), + rpcCameraList.cameras, ) + ) + ) def translate_to_rpc(self, rpcCameraList): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.cameras: - rpc_elem = camera_pb2.Information() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - - rpcCameraList.cameras.extend(rpc_elems_list) - - - + rpcCameraList.cameras.extend(rpc_elems_list) class CameraError(Exception): - """ Raised when a CameraResult is a fail code """ + """Raised when a CameraResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -2389,72 +1907,68 @@ def __str__(self): class Camera(AsyncBase): """ - Can be used to manage cameras that implement the MAVLink - Camera Protocol: https://mavlink.io/en/protocol/camera.html. + Can be used to manage cameras that implement the MAVLink + Camera Protocol: https://mavlink.io/en/protocol/camera.html. - Currently only a single camera is supported. - When multiple cameras are supported the plugin will need to be - instantiated separately for every camera and the camera selected using - `select_camera`. + Currently only a single camera is supported. + When multiple cameras are supported the plugin will need to be + instantiated separately for every camera and the camera selected using + `select_camera`. - Generated by dcsdkgen - MAVSDK Camera API + Generated by dcsdkgen - MAVSDK Camera API """ # Plugin name name = "Camera" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = camera_pb2_grpc.CameraServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return CameraResult.translate_from_rpc(response.camera_result) - async def take_photo(self, component_id): """ - Take one photo. + Take one photo. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.TakePhotoRequest() request.component_id = component_id response = await self._stub.TakePhoto(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "take_photo()", component_id) - async def start_photo_interval(self, component_id, interval_s): """ - Start photo timelapse with a given interval. + Start photo timelapse with a given interval. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - interval_s : float - Interval between photos (in seconds) + interval_s : float + Interval between photos (in seconds) - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.StartPhotoIntervalRequest() @@ -2462,107 +1976,101 @@ async def start_photo_interval(self, component_id, interval_s): request.interval_s = interval_s response = await self._stub.StartPhotoInterval(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: - raise CameraError(result, "start_photo_interval()", component_id, interval_s) - + raise CameraError( + result, "start_photo_interval()", component_id, interval_s + ) async def stop_photo_interval(self, component_id): """ - Stop a running photo timelapse. + Stop a running photo timelapse. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.StopPhotoIntervalRequest() request.component_id = component_id response = await self._stub.StopPhotoInterval(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "stop_photo_interval()", component_id) - async def start_video(self, component_id): """ - Start a video recording. + Start a video recording. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.StartVideoRequest() request.component_id = component_id response = await self._stub.StartVideo(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "start_video()", component_id) - async def stop_video(self, component_id): """ - Stop a running video recording. + Stop a running video recording. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.StopVideoRequest() request.component_id = component_id response = await self._stub.StopVideo(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "stop_video()", component_id) - async def start_video_streaming(self, component_id, stream_id): """ - Start video streaming. + Start video streaming. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - stream_id : int32_t - video stream id + stream_id : int32_t + video stream id - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.StartVideoStreamingRequest() @@ -2570,29 +2078,29 @@ async def start_video_streaming(self, component_id, stream_id): request.stream_id = stream_id response = await self._stub.StartVideoStreaming(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: - raise CameraError(result, "start_video_streaming()", component_id, stream_id) - + raise CameraError( + result, "start_video_streaming()", component_id, stream_id + ) async def stop_video_streaming(self, component_id, stream_id): """ - Stop current video streaming. + Stop current video streaming. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - stream_id : int32_t - video stream id + stream_id : int32_t + video stream id - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.StopVideoStreamingRequest() @@ -2600,113 +2108,100 @@ async def stop_video_streaming(self, component_id, stream_id): request.stream_id = stream_id response = await self._stub.StopVideoStreaming(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "stop_video_streaming()", component_id, stream_id) - async def set_mode(self, component_id, mode): """ - Set camera mode. + Set camera mode. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - mode : Mode - Camera mode to set + mode : Mode + Camera mode to set - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.SetModeRequest() request.component_id = component_id - + request.mode = mode.translate_to_rpc() - - + response = await self._stub.SetMode(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "set_mode()", component_id, mode) - async def list_photos(self, component_id, photos_range): """ - List photos available on the camera. + List photos available on the camera. - Note that this might need to be called initially to set the PhotosRange accordingly. - Once set to 'all' rather than 'since connection', it will try to request the previous - images over time. + Note that this might need to be called initially to set the PhotosRange accordingly. + Once set to 'all' rather than 'since connection', it will try to request the previous + images over time. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - photos_range : PhotosRange - Which photos should be listed (all or since connection) + photos_range : PhotosRange + Which photos should be listed (all or since connection) - Returns - ------- - capture_infos : [CaptureInfo] - List of capture infos (representing the photos) + Returns + ------- + capture_infos : [CaptureInfo] + List of capture infos (representing the photos) - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.ListPhotosRequest() - - + request.component_id = component_id - - - - + request.photos_range = photos_range.translate_to_rpc() - - + response = await self._stub.ListPhotos(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "list_photos()", component_id, photos_range) - capture_infos = [] for capture_infos_rpc in response.capture_infos: capture_infos.append(CaptureInfo.translate_from_rpc(capture_infos_rpc)) return capture_infos - async def camera_list(self): """ - Subscribe to list of cameras. + Subscribe to list of cameras. + + This allows to find out what cameras are connected to the system. + Based on the camera ID, we can then address a specific camera. - This allows to find out what cameras are connected to the system. - Based on the camera ID, we can then address a specific camera. + Yields + ------- + camera_list : CameraList + Camera list - Yields - ------- - camera_list : CameraList - Camera list - """ request = camera_pb2.SubscribeCameraListRequest() @@ -2714,23 +2209,20 @@ async def camera_list(self): try: async for response in camera_list_stream: - - - yield CameraList.translate_from_rpc(response.camera_list) finally: camera_list_stream.cancel() async def mode(self): """ - Subscribe to camera mode updates. + Subscribe to camera mode updates. + + Yields + ------- + update : ModeUpdate + Mode update for camera - Yields - ------- - update : ModeUpdate - Mode update for camera - """ request = camera_pb2.SubscribeModeRequest() @@ -2738,60 +2230,53 @@ async def mode(self): try: async for response in mode_stream: - - - yield ModeUpdate.translate_from_rpc(response.update) finally: mode_stream.cancel() async def get_mode(self, component_id): """ - Get camera mode. + Get camera mode. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Returns - ------- - mode : Mode - Mode + Returns + ------- + mode : Mode + Mode - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.GetModeRequest() - - + request.component_id = component_id - + response = await self._stub.GetMode(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_mode()", component_id) - return Mode.translate_from_rpc(response.mode) - async def video_stream_info(self): """ - Subscribe to video stream info updates. + Subscribe to video stream info updates. + + Yields + ------- + update : VideoStreamUpdate + Video stream update for camera - Yields - ------- - update : VideoStreamUpdate - Video stream update for camera - """ request = camera_pb2.SubscribeVideoStreamInfoRequest() @@ -2799,60 +2284,53 @@ async def video_stream_info(self): try: async for response in video_stream_info_stream: - - - yield VideoStreamUpdate.translate_from_rpc(response.update) finally: video_stream_info_stream.cancel() async def get_video_stream_info(self, component_id): """ - Get video stream info. + Get video stream info. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Returns - ------- - video_stream_info : VideoStreamInfo - Video stream info + Returns + ------- + video_stream_info : VideoStreamInfo + Video stream info - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.GetVideoStreamInfoRequest() - - + request.component_id = component_id - + response = await self._stub.GetVideoStreamInfo(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_video_stream_info()", component_id) - return VideoStreamInfo.translate_from_rpc(response.video_stream_info) - async def capture_info(self): """ - Subscribe to capture info updates. + Subscribe to capture info updates. + + Yields + ------- + capture_info : CaptureInfo + Capture info - Yields - ------- - capture_info : CaptureInfo - Capture info - """ request = camera_pb2.SubscribeCaptureInfoRequest() @@ -2860,23 +2338,20 @@ async def capture_info(self): try: async for response in capture_info_stream: - - - yield CaptureInfo.translate_from_rpc(response.capture_info) finally: capture_info_stream.cancel() async def storage(self): """ - Subscribe to camera's storage status updates. + Subscribe to camera's storage status updates. + + Yields + ------- + update : StorageUpdate + Camera's storage status - Yields - ------- - update : StorageUpdate - Camera's storage status - """ request = camera_pb2.SubscribeStorageRequest() @@ -2884,60 +2359,53 @@ async def storage(self): try: async for response in storage_stream: - - - yield StorageUpdate.translate_from_rpc(response.update) finally: storage_stream.cancel() async def get_storage(self, component_id): """ - Get camera's storage status. + Get camera's storage status. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Returns - ------- - storage : Storage - Camera's storage status + Returns + ------- + storage : Storage + Camera's storage status - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.GetStorageRequest() - - + request.component_id = component_id - + response = await self._stub.GetStorage(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_storage()", component_id) - return Storage.translate_from_rpc(response.storage) - async def current_settings(self): """ - Get the list of current camera settings. + Get the list of current camera settings. + + Yields + ------- + update : CurrentSettingsUpdate + Current setting update per camera - Yields - ------- - update : CurrentSettingsUpdate - Current setting update per camera - """ request = camera_pb2.SubscribeCurrentSettingsRequest() @@ -2945,220 +2413,199 @@ async def current_settings(self): try: async for response in current_settings_stream: - - - yield CurrentSettingsUpdate.translate_from_rpc(response.update) finally: current_settings_stream.cancel() async def get_current_settings(self, component_id): """ - Get current settings. + Get current settings. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Returns - ------- - current_settings : [Setting] - List of current settings + Returns + ------- + current_settings : [Setting] + List of current settings - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.GetCurrentSettingsRequest() - - + request.component_id = component_id - + response = await self._stub.GetCurrentSettings(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_current_settings()", component_id) - current_settings = [] for current_settings_rpc in response.current_settings: current_settings.append(Setting.translate_from_rpc(current_settings_rpc)) return current_settings - async def possible_setting_options(self): """ - Get the list of settings that can be changed. + Get the list of settings that can be changed. + + Yields + ------- + update : PossibleSettingOptionsUpdate + Possible setting update per camera - Yields - ------- - update : PossibleSettingOptionsUpdate - Possible setting update per camera - """ request = camera_pb2.SubscribePossibleSettingOptionsRequest() - possible_setting_options_stream = self._stub.SubscribePossibleSettingOptions(request) + possible_setting_options_stream = self._stub.SubscribePossibleSettingOptions( + request + ) try: async for response in possible_setting_options_stream: - - - yield PossibleSettingOptionsUpdate.translate_from_rpc(response.update) finally: possible_setting_options_stream.cancel() async def get_possible_setting_options(self, component_id): """ - Get possible setting options. + Get possible setting options. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Returns - ------- - setting_options : [SettingOptions] - List of settings that can be changed + Returns + ------- + setting_options : [SettingOptions] + List of settings that can be changed - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.GetPossibleSettingOptionsRequest() - - + request.component_id = component_id - + response = await self._stub.GetPossibleSettingOptions(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_possible_setting_options()", component_id) - setting_options = [] for setting_options_rpc in response.setting_options: - setting_options.append(SettingOptions.translate_from_rpc(setting_options_rpc)) + setting_options.append( + SettingOptions.translate_from_rpc(setting_options_rpc) + ) return setting_options - async def set_setting(self, component_id, setting): """ - Set a setting to some value. + Set a setting to some value. - Only setting_id of setting and option_id of option needs to be set. + Only setting_id of setting and option_id of option needs to be set. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - setting : Setting - Desired setting + setting : Setting + Desired setting - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.SetSettingRequest() request.component_id = component_id - + setting.translate_to_rpc(request.setting) - - + response = await self._stub.SetSetting(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "set_setting()", component_id, setting) - async def get_setting(self, component_id, setting): """ - Get a setting. + Get a setting. - Only setting_id of setting needs to be set. + Only setting_id of setting needs to be set. - Parameters - ---------- - component_id : int32_t - Component ID (0/all not available) + Parameters + ---------- + component_id : int32_t + Component ID (0/all not available) - setting : Setting - Requested setting + setting : Setting + Requested setting - Returns - ------- - setting : Setting - Setting + Returns + ------- + setting : Setting + Setting - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.GetSettingRequest() - - + request.component_id = component_id - - - - + setting.translate_to_rpc(request.setting) - - + response = await self._stub.GetSetting(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_setting()", component_id, setting) - return Setting.translate_from_rpc(response.setting) - async def format_storage(self, component_id, storage_id): """ - Format storage (e.g. SD card) in camera. + Format storage (e.g. SD card) in camera. - This will delete all content of the camera storage! + This will delete all content of the camera storage! - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - storage_id : int32_t - Storage identify to be format + storage_id : int32_t + Storage identify to be format - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.FormatStorageRequest() @@ -3166,135 +2613,125 @@ async def format_storage(self, component_id, storage_id): request.storage_id = storage_id response = await self._stub.FormatStorage(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "format_storage()", component_id, storage_id) - async def reset_settings(self, component_id): """ - Reset all settings in camera. + Reset all settings in camera. - This will reset all camera settings to default value + This will reset all camera settings to default value - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.ResetSettingsRequest() request.component_id = component_id response = await self._stub.ResetSettings(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "reset_settings()", component_id) - async def zoom_in_start(self, component_id): """ - Start zooming in. + Start zooming in. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.ZoomInStartRequest() request.component_id = component_id response = await self._stub.ZoomInStart(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "zoom_in_start()", component_id) - async def zoom_out_start(self, component_id): """ - Start zooming out. + Start zooming out. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.ZoomOutStartRequest() request.component_id = component_id response = await self._stub.ZoomOutStart(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "zoom_out_start()", component_id) - async def zoom_stop(self, component_id): """ - Stop zooming. + Stop zooming. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.ZoomStopRequest() request.component_id = component_id response = await self._stub.ZoomStop(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "zoom_stop()", component_id) - async def zoom_range(self, component_id, range): """ - Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - range : float - Range must be between 0.0 and 100.0 + range : float + Range must be between 0.0 and 100.0 - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.ZoomRangeRequest() @@ -3302,35 +2739,33 @@ async def zoom_range(self, component_id, range): request.range = range response = await self._stub.ZoomRange(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "zoom_range()", component_id, range) - async def track_point(self, component_id, point_x, point_y, radius): """ - Track point. + Track point. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - point_x : float - Point in X axis (0..1, 0 is left, 1 is right) + point_x : float + Point in X axis (0..1, 0 is left, 1 is right) - point_y : float - Point in Y axis (0..1, 0 is top, 1 is bottom) + point_y : float + Point in Y axis (0..1, 0 is top, 1 is bottom) - radius : float - Radius (0 is one pixel, 1 is full image width) + radius : float + Radius (0 is one pixel, 1 is full image width) - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.TrackPointRequest() @@ -3340,38 +2775,40 @@ async def track_point(self, component_id, point_x, point_y, radius): request.radius = radius response = await self._stub.TrackPoint(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: - raise CameraError(result, "track_point()", component_id, point_x, point_y, radius) - + raise CameraError( + result, "track_point()", component_id, point_x, point_y, radius + ) - async def track_rectangle(self, component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y): + async def track_rectangle( + self, component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y + ): """ - Track rectangle. + Track rectangle. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - top_left_x : float - Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right) + top_left_x : float + Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right) - top_left_y : float - Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom) + top_left_y : float + Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom) - bottom_right_x : float - Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right) + bottom_right_x : float + Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right) - bottom_right_y : float - Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom) + bottom_right_y : float + Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom) - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.TrackRectangleRequest() @@ -3382,133 +2819,131 @@ async def track_rectangle(self, component_id, top_left_x, top_left_y, bottom_rig request.bottom_right_y = bottom_right_y response = await self._stub.TrackRectangle(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: - raise CameraError(result, "track_rectangle()", component_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y) - + raise CameraError( + result, + "track_rectangle()", + component_id, + top_left_x, + top_left_y, + bottom_right_x, + bottom_right_y, + ) async def track_stop(self, component_id): """ - Stop tracking. + Stop tracking. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.TrackStopRequest() request.component_id = component_id response = await self._stub.TrackStop(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "track_stop()", component_id) - async def focus_in_start(self, component_id): """ - Start focusing in. + Start focusing in. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.FocusInStartRequest() request.component_id = component_id response = await self._stub.FocusInStart(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "focus_in_start()", component_id) - async def focus_out_start(self, component_id): """ - Start focusing out. + Start focusing out. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.FocusOutStartRequest() request.component_id = component_id response = await self._stub.FocusOutStart(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "focus_out_start()", component_id) - async def focus_stop(self, component_id): """ - Stop focus. + Stop focus. - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.FocusStopRequest() request.component_id = component_id response = await self._stub.FocusStop(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "focus_stop()", component_id) - async def focus_range(self, component_id, range): """ - Focus with range value of full range (value between 0.0 and 100.0). + Focus with range value of full range (value between 0.0 and 100.0). - Parameters - ---------- - component_id : int32_t - Component ID + Parameters + ---------- + component_id : int32_t + Component ID - range : float - Range must be between 0.0 - 100.0 + range : float + Range must be between 0.0 - 100.0 - Raises - ------ - CameraError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraError + If the request fails. The error contains the reason for the failure. """ request = camera_pb2.FocusRangeRequest() @@ -3516,9 +2951,7 @@ async def focus_range(self, component_id, range): request.range = range response = await self._stub.FocusRange(request) - result = self._extract_result(response) if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "focus_range()", component_id, range) - \ No newline at end of file diff --git a/mavsdk/camera_pb2.py b/mavsdk/camera_pb2.py index dee0a5d2..92f119d5 100644 --- a/mavsdk/camera_pb2.py +++ b/mavsdk/camera_pb2.py @@ -4,18 +4,15 @@ # source: camera/camera.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'camera/camera.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "camera/camera.proto" ) # @@protoc_insertion_point(imports) @@ -25,234 +22,284 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13\x63\x61mera/camera.proto\x12\x11mavsdk.rpc.camera\x1a\x14mavsdk_options.proto\"7\n\x06Option\x12\x11\n\toption_id\x18\x01 \x01(\t\x12\x1a\n\x12option_description\x18\x02 \x01(\t\"w\n\x07Setting\x12\x12\n\nsetting_id\x18\x01 \x01(\t\x12\x1b\n\x13setting_description\x18\x02 \x01(\t\x12)\n\x06option\x18\x03 \x01(\x0b\x32\x19.mavsdk.rpc.camera.Option\x12\x10\n\x08is_range\x18\x04 \x01(\x08\"\x95\x01\n\x0eSettingOptions\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\nsetting_id\x18\x02 \x01(\t\x12\x1b\n\x13setting_description\x18\x03 \x01(\t\x12*\n\x07options\x18\x04 \x03(\x0b\x32\x19.mavsdk.rpc.camera.Option\x12\x10\n\x08is_range\x18\x05 \x01(\x08\"\xc5\x01\n\x13VideoStreamSettings\x12\x15\n\rframe_rate_hz\x18\x01 \x01(\x02\x12!\n\x19horizontal_resolution_pix\x18\x02 \x01(\r\x12\x1f\n\x17vertical_resolution_pix\x18\x03 \x01(\r\x12\x14\n\x0c\x62it_rate_b_s\x18\x04 \x01(\r\x12\x14\n\x0crotation_deg\x18\x05 \x01(\r\x12\x0b\n\x03uri\x18\x06 \x01(\t\x12\x1a\n\x12horizontal_fov_deg\x18\x07 \x01(\x02\"\xd5\x03\n\x0fVideoStreamInfo\x12\x11\n\tstream_id\x18\x01 \x01(\x05\x12\x38\n\x08settings\x18\x02 \x01(\x0b\x32&.mavsdk.rpc.camera.VideoStreamSettings\x12\x44\n\x06status\x18\x03 \x01(\x0e\x32\x34.mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus\x12H\n\x08spectrum\x18\x04 \x01(\x0e\x32\x36.mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum\"]\n\x11VideoStreamStatus\x12#\n\x1fVIDEO_STREAM_STATUS_NOT_RUNNING\x10\x00\x12#\n\x1fVIDEO_STREAM_STATUS_IN_PROGRESS\x10\x01\"\x85\x01\n\x13VideoStreamSpectrum\x12!\n\x1dVIDEO_STREAM_SPECTRUM_UNKNOWN\x10\x00\x12\'\n#VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT\x10\x01\x12\"\n\x1eVIDEO_STREAM_SPECTRUM_INFRARED\x10\x02\"(\n\x10TakePhotoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"K\n\x11TakePhotoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"E\n\x19StartPhotoIntervalRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\ninterval_s\x18\x02 \x01(\x02\"T\n\x1aStartPhotoIntervalResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"0\n\x18StopPhotoIntervalRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"S\n\x19StopPhotoIntervalResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\")\n\x11StartVideoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"L\n\x12StartVideoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"(\n\x10StopVideoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"K\n\x11StopVideoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"E\n\x1aStartVideoStreamingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x11\n\tstream_id\x18\x02 \x01(\x05\"U\n\x1bStartVideoStreamingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"D\n\x19StopVideoStreamingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x11\n\tstream_id\x18\x02 \x01(\x05\"T\n\x1aStopVideoStreamingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"M\n\x0eSetModeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12%\n\x04mode\x18\x02 \x01(\x0e\x32\x17.mavsdk.rpc.camera.Mode\"I\n\x0fSetModeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"_\n\x11ListPhotosRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x34\n\x0cphotos_range\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.camera.PhotosRange\"\x83\x01\n\x12ListPhotosResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12\x35\n\rcapture_infos\x18\x02 \x03(\x0b\x32\x1e.mavsdk.rpc.camera.CaptureInfo\"\x1c\n\x1aSubscribeCameraListRequest\"H\n\x12\x43\x61meraListResponse\x12\x32\n\x0b\x63\x61mera_list\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.CameraList\"I\n\nModeUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12%\n\x04mode\x18\x02 \x01(\x0e\x32\x17.mavsdk.rpc.camera.Mode\"\x16\n\x14SubscribeModeRequest\"=\n\x0cModeResponse\x12-\n\x06update\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.ModeUpdate\"h\n\x11VideoStreamUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12=\n\x11video_stream_info\x18\x02 \x01(\x0b\x32\".mavsdk.rpc.camera.VideoStreamInfo\"!\n\x1fSubscribeVideoStreamInfoRequest\"O\n\x17VideoStreamInfoResponse\x12\x34\n\x06update\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.camera.VideoStreamUpdate\"\x1d\n\x1bSubscribeCaptureInfoRequest\"K\n\x13\x43\x61ptureInfoResponse\x12\x34\n\x0c\x63\x61pture_info\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.camera.CaptureInfo\"\xa0\x05\n\x07Storage\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x10\n\x08video_on\x18\x02 \x01(\x08\x12\x19\n\x11photo_interval_on\x18\x03 \x01(\x08\x12\x18\n\x10used_storage_mib\x18\x04 \x01(\x02\x12\x1d\n\x15\x61vailable_storage_mib\x18\x05 \x01(\x02\x12\x19\n\x11total_storage_mib\x18\x06 \x01(\x02\x12\x18\n\x10recording_time_s\x18\x07 \x01(\x02\x12\x19\n\x11media_folder_name\x18\x08 \x01(\t\x12@\n\x0estorage_status\x18\t \x01(\x0e\x32(.mavsdk.rpc.camera.Storage.StorageStatus\x12\x12\n\nstorage_id\x18\n \x01(\r\x12<\n\x0cstorage_type\x18\x0b \x01(\x0e\x32&.mavsdk.rpc.camera.Storage.StorageType\"\x91\x01\n\rStorageStatus\x12 \n\x1cSTORAGE_STATUS_NOT_AVAILABLE\x10\x00\x12\x1e\n\x1aSTORAGE_STATUS_UNFORMATTED\x10\x01\x12\x1c\n\x18STORAGE_STATUS_FORMATTED\x10\x02\x12 \n\x1cSTORAGE_STATUS_NOT_SUPPORTED\x10\x03\"\xa0\x01\n\x0bStorageType\x12\x18\n\x14STORAGE_TYPE_UNKNOWN\x10\x00\x12\x1a\n\x16STORAGE_TYPE_USB_STICK\x10\x01\x12\x13\n\x0fSTORAGE_TYPE_SD\x10\x02\x12\x18\n\x14STORAGE_TYPE_MICROSD\x10\x03\x12\x13\n\x0fSTORAGE_TYPE_HD\x10\x07\x12\x17\n\x12STORAGE_TYPE_OTHER\x10\xfe\x01\"R\n\rStorageUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12+\n\x07storage\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Storage\"\x19\n\x17SubscribeStorageRequest\"C\n\x0fStorageResponse\x12\x30\n\x06update\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.camera.StorageUpdate\"c\n\x15\x43urrentSettingsUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x34\n\x10\x63urrent_settings\x18\x02 \x03(\x0b\x32\x1a.mavsdk.rpc.camera.Setting\"!\n\x1fSubscribeCurrentSettingsRequest\"S\n\x17\x43urrentSettingsResponse\x12\x38\n\x06update\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera.CurrentSettingsUpdate\"p\n\x1cPossibleSettingOptionsUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12:\n\x0fsetting_options\x18\x02 \x03(\x0b\x32!.mavsdk.rpc.camera.SettingOptions\"(\n&SubscribePossibleSettingOptionsRequest\"a\n\x1ePossibleSettingOptionsResponse\x12?\n\x06update\x18\x01 \x01(\x0b\x32/.mavsdk.rpc.camera.PossibleSettingOptionsUpdate\"V\n\x11SetSettingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12+\n\x07setting\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Setting\"L\n\x12SetSettingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"&\n\x0eGetModeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"p\n\x0fGetModeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12%\n\x04mode\x18\x02 \x01(\x0e\x32\x17.mavsdk.rpc.camera.Mode\"1\n\x19GetVideoStreamInfoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"\x93\x01\n\x1aGetVideoStreamInfoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12=\n\x11video_stream_info\x18\x02 \x01(\x0b\x32\".mavsdk.rpc.camera.VideoStreamInfo\")\n\x11GetStorageRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"y\n\x12GetStorageResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12+\n\x07storage\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Storage\"1\n\x19GetCurrentSettingsRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"\x8a\x01\n\x1aGetCurrentSettingsResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12\x34\n\x10\x63urrent_settings\x18\x02 \x03(\x0b\x32\x1a.mavsdk.rpc.camera.Setting\"8\n GetPossibleSettingOptionsRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"\x97\x01\n!GetPossibleSettingOptionsResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12:\n\x0fsetting_options\x18\x02 \x03(\x0b\x32!.mavsdk.rpc.camera.SettingOptions\"V\n\x11GetSettingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12+\n\x07setting\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Setting\"y\n\x12GetSettingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12+\n\x07setting\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Setting\"@\n\x14\x46ormatStorageRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\nstorage_id\x18\x02 \x01(\x05\"O\n\x15\x46ormatStorageResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\",\n\x14ResetSettingsRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"O\n\x15ResetSettingsResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"*\n\x12ZoomInStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"M\n\x13ZoomInStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"+\n\x13ZoomOutStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"N\n\x14ZoomOutStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"\'\n\x0fZoomStopRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"J\n\x10ZoomStopResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"7\n\x10ZoomRangeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\r\n\x05range\x18\x02 \x01(\x02\"K\n\x11ZoomRangeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"[\n\x11TrackPointRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x0f\n\x07point_x\x18\x02 \x01(\x02\x12\x0f\n\x07point_y\x18\x03 \x01(\x02\x12\x0e\n\x06radius\x18\x04 \x01(\x02\"L\n\x12TrackPointResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"\x85\x01\n\x15TrackRectangleRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\ntop_left_x\x18\x02 \x01(\x02\x12\x12\n\ntop_left_y\x18\x03 \x01(\x02\x12\x16\n\x0e\x62ottom_right_x\x18\x04 \x01(\x02\x12\x16\n\x0e\x62ottom_right_y\x18\x05 \x01(\x02\"P\n\x16TrackRectangleResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"(\n\x10TrackStopRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"K\n\x11TrackStopResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"+\n\x13\x46ocusInStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"N\n\x14\x46ocusInStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\",\n\x14\x46ocusOutStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"O\n\x15\x46ocusOutStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"(\n\x10\x46ocusStopRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\"K\n\x11\x46ocusStopResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"8\n\x11\x46ocusRangeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\r\n\x05range\x18\x02 \x01(\x02\"L\n\x12\x46ocusRangeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\"\x96\x03\n\x0c\x43\x61meraResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.camera.CameraResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xb9\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x16\n\x12RESULT_IN_PROGRESS\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x10\n\x0cRESULT_ERROR\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x19\n\x15RESULT_WRONG_ARGUMENT\x10\x07\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x08\x12\x1f\n\x1bRESULT_PROTOCOL_UNSUPPORTED\x10\t\x12\x16\n\x12RESULT_UNAVAILABLE\x10\n\x12\x1c\n\x18RESULT_CAMERA_ID_INVALID\x10\x0b\x12\x1d\n\x19RESULT_ACTION_UNSUPPORTED\x10\x0c\"q\n\x08Position\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x12\x1b\n\x13relative_altitude_m\x18\x04 \x01(\x02\"8\n\nQuaternion\x12\t\n\x01w\x18\x01 \x01(\x02\x12\t\n\x01x\x18\x02 \x01(\x02\x12\t\n\x01y\x18\x03 \x01(\x02\x12\t\n\x01z\x18\x04 \x01(\x02\"B\n\nEulerAngle\x12\x10\n\x08roll_deg\x18\x01 \x01(\x02\x12\x11\n\tpitch_deg\x18\x02 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x03 \x01(\x02\"\x95\x02\n\x0b\x43\x61ptureInfo\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12-\n\x08position\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.camera.Position\x12:\n\x13\x61ttitude_quaternion\x18\x03 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.Quaternion\x12;\n\x14\x61ttitude_euler_angle\x18\x04 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.EulerAngle\x12\x13\n\x0btime_utc_us\x18\x05 \x01(\x04\x12\x12\n\nis_success\x18\x06 \x01(\x08\x12\r\n\x05index\x18\x07 \x01(\x05\x12\x10\n\x08\x66ile_url\x18\x08 \x01(\t\"\xeb\x01\n\x0bInformation\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nmodel_name\x18\x03 \x01(\t\x12\x17\n\x0f\x66ocal_length_mm\x18\x04 \x01(\x02\x12!\n\x19horizontal_sensor_size_mm\x18\x05 \x01(\x02\x12\x1f\n\x17vertical_sensor_size_mm\x18\x06 \x01(\x02\x12 \n\x18horizontal_resolution_px\x18\x07 \x01(\r\x12\x1e\n\x16vertical_resolution_px\x18\x08 \x01(\r\"=\n\nCameraList\x12/\n\x07\x63\x61meras\x18\x01 \x03(\x0b\x32\x1e.mavsdk.rpc.camera.Information*8\n\x04Mode\x12\x10\n\x0cMODE_UNKNOWN\x10\x00\x12\x0e\n\nMODE_PHOTO\x10\x01\x12\x0e\n\nMODE_VIDEO\x10\x02*F\n\x0bPhotosRange\x12\x14\n\x10PHOTOS_RANGE_ALL\x10\x00\x12!\n\x1dPHOTOS_RANGE_SINCE_CONNECTION\x10\x01\x32\xdd\x1d\n\rCameraService\x12X\n\tTakePhoto\x12#.mavsdk.rpc.camera.TakePhotoRequest\x1a$.mavsdk.rpc.camera.TakePhotoResponse\"\x00\x12s\n\x12StartPhotoInterval\x12,.mavsdk.rpc.camera.StartPhotoIntervalRequest\x1a-.mavsdk.rpc.camera.StartPhotoIntervalResponse\"\x00\x12p\n\x11StopPhotoInterval\x12+.mavsdk.rpc.camera.StopPhotoIntervalRequest\x1a,.mavsdk.rpc.camera.StopPhotoIntervalResponse\"\x00\x12[\n\nStartVideo\x12$.mavsdk.rpc.camera.StartVideoRequest\x1a%.mavsdk.rpc.camera.StartVideoResponse\"\x00\x12X\n\tStopVideo\x12#.mavsdk.rpc.camera.StopVideoRequest\x1a$.mavsdk.rpc.camera.StopVideoResponse\"\x00\x12z\n\x13StartVideoStreaming\x12-.mavsdk.rpc.camera.StartVideoStreamingRequest\x1a..mavsdk.rpc.camera.StartVideoStreamingResponse\"\x04\x80\xb5\x18\x01\x12w\n\x12StopVideoStreaming\x12,.mavsdk.rpc.camera.StopVideoStreamingRequest\x1a-.mavsdk.rpc.camera.StopVideoStreamingResponse\"\x04\x80\xb5\x18\x01\x12R\n\x07SetMode\x12!.mavsdk.rpc.camera.SetModeRequest\x1a\".mavsdk.rpc.camera.SetModeResponse\"\x00\x12[\n\nListPhotos\x12$.mavsdk.rpc.camera.ListPhotosRequest\x1a%.mavsdk.rpc.camera.ListPhotosResponse\"\x00\x12o\n\x13SubscribeCameraList\x12-.mavsdk.rpc.camera.SubscribeCameraListRequest\x1a%.mavsdk.rpc.camera.CameraListResponse\"\x00\x30\x01\x12\x61\n\rSubscribeMode\x12\'.mavsdk.rpc.camera.SubscribeModeRequest\x1a\x1f.mavsdk.rpc.camera.ModeResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12V\n\x07GetMode\x12!.mavsdk.rpc.camera.GetModeRequest\x1a\".mavsdk.rpc.camera.GetModeResponse\"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x18SubscribeVideoStreamInfo\x12\x32.mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest\x1a*.mavsdk.rpc.camera.VideoStreamInfoResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12w\n\x12GetVideoStreamInfo\x12,.mavsdk.rpc.camera.GetVideoStreamInfoRequest\x1a-.mavsdk.rpc.camera.GetVideoStreamInfoResponse\"\x04\x80\xb5\x18\x01\x12v\n\x14SubscribeCaptureInfo\x12..mavsdk.rpc.camera.SubscribeCaptureInfoRequest\x1a&.mavsdk.rpc.camera.CaptureInfoResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12j\n\x10SubscribeStorage\x12*.mavsdk.rpc.camera.SubscribeStorageRequest\x1a\".mavsdk.rpc.camera.StorageResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12_\n\nGetStorage\x12$.mavsdk.rpc.camera.GetStorageRequest\x1a%.mavsdk.rpc.camera.GetStorageResponse\"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x18SubscribeCurrentSettings\x12\x32.mavsdk.rpc.camera.SubscribeCurrentSettingsRequest\x1a*.mavsdk.rpc.camera.CurrentSettingsResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12w\n\x12GetCurrentSettings\x12,.mavsdk.rpc.camera.GetCurrentSettingsRequest\x1a-.mavsdk.rpc.camera.GetCurrentSettingsResponse\"\x04\x80\xb5\x18\x01\x12\x97\x01\n\x1fSubscribePossibleSettingOptions\x12\x39.mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest\x1a\x31.mavsdk.rpc.camera.PossibleSettingOptionsResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x8c\x01\n\x19GetPossibleSettingOptions\x12\x33.mavsdk.rpc.camera.GetPossibleSettingOptionsRequest\x1a\x34.mavsdk.rpc.camera.GetPossibleSettingOptionsResponse\"\x04\x80\xb5\x18\x01\x12[\n\nSetSetting\x12$.mavsdk.rpc.camera.SetSettingRequest\x1a%.mavsdk.rpc.camera.SetSettingResponse\"\x00\x12[\n\nGetSetting\x12$.mavsdk.rpc.camera.GetSettingRequest\x1a%.mavsdk.rpc.camera.GetSettingResponse\"\x00\x12\x64\n\rFormatStorage\x12\'.mavsdk.rpc.camera.FormatStorageRequest\x1a(.mavsdk.rpc.camera.FormatStorageResponse\"\x00\x12\x64\n\rResetSettings\x12\'.mavsdk.rpc.camera.ResetSettingsRequest\x1a(.mavsdk.rpc.camera.ResetSettingsResponse\"\x00\x12^\n\x0bZoomInStart\x12%.mavsdk.rpc.camera.ZoomInStartRequest\x1a&.mavsdk.rpc.camera.ZoomInStartResponse\"\x00\x12\x61\n\x0cZoomOutStart\x12&.mavsdk.rpc.camera.ZoomOutStartRequest\x1a\'.mavsdk.rpc.camera.ZoomOutStartResponse\"\x00\x12U\n\x08ZoomStop\x12\".mavsdk.rpc.camera.ZoomStopRequest\x1a#.mavsdk.rpc.camera.ZoomStopResponse\"\x00\x12X\n\tZoomRange\x12#.mavsdk.rpc.camera.ZoomRangeRequest\x1a$.mavsdk.rpc.camera.ZoomRangeResponse\"\x00\x12[\n\nTrackPoint\x12$.mavsdk.rpc.camera.TrackPointRequest\x1a%.mavsdk.rpc.camera.TrackPointResponse\"\x00\x12g\n\x0eTrackRectangle\x12(.mavsdk.rpc.camera.TrackRectangleRequest\x1a).mavsdk.rpc.camera.TrackRectangleResponse\"\x00\x12X\n\tTrackStop\x12#.mavsdk.rpc.camera.TrackStopRequest\x1a$.mavsdk.rpc.camera.TrackStopResponse\"\x00\x12\x61\n\x0c\x46ocusInStart\x12&.mavsdk.rpc.camera.FocusInStartRequest\x1a\'.mavsdk.rpc.camera.FocusInStartResponse\"\x00\x12\x64\n\rFocusOutStart\x12\'.mavsdk.rpc.camera.FocusOutStartRequest\x1a(.mavsdk.rpc.camera.FocusOutStartResponse\"\x00\x12X\n\tFocusStop\x12#.mavsdk.rpc.camera.FocusStopRequest\x1a$.mavsdk.rpc.camera.FocusStopResponse\"\x00\x12[\n\nFocusRange\x12$.mavsdk.rpc.camera.FocusRangeRequest\x1a%.mavsdk.rpc.camera.FocusRangeResponse\"\x00\x42\x1f\n\x10io.mavsdk.cameraB\x0b\x43\x61meraProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x13\x63\x61mera/camera.proto\x12\x11mavsdk.rpc.camera\x1a\x14mavsdk_options.proto"7\n\x06Option\x12\x11\n\toption_id\x18\x01 \x01(\t\x12\x1a\n\x12option_description\x18\x02 \x01(\t"w\n\x07Setting\x12\x12\n\nsetting_id\x18\x01 \x01(\t\x12\x1b\n\x13setting_description\x18\x02 \x01(\t\x12)\n\x06option\x18\x03 \x01(\x0b\x32\x19.mavsdk.rpc.camera.Option\x12\x10\n\x08is_range\x18\x04 \x01(\x08"\x95\x01\n\x0eSettingOptions\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\nsetting_id\x18\x02 \x01(\t\x12\x1b\n\x13setting_description\x18\x03 \x01(\t\x12*\n\x07options\x18\x04 \x03(\x0b\x32\x19.mavsdk.rpc.camera.Option\x12\x10\n\x08is_range\x18\x05 \x01(\x08"\xc5\x01\n\x13VideoStreamSettings\x12\x15\n\rframe_rate_hz\x18\x01 \x01(\x02\x12!\n\x19horizontal_resolution_pix\x18\x02 \x01(\r\x12\x1f\n\x17vertical_resolution_pix\x18\x03 \x01(\r\x12\x14\n\x0c\x62it_rate_b_s\x18\x04 \x01(\r\x12\x14\n\x0crotation_deg\x18\x05 \x01(\r\x12\x0b\n\x03uri\x18\x06 \x01(\t\x12\x1a\n\x12horizontal_fov_deg\x18\x07 \x01(\x02"\xd5\x03\n\x0fVideoStreamInfo\x12\x11\n\tstream_id\x18\x01 \x01(\x05\x12\x38\n\x08settings\x18\x02 \x01(\x0b\x32&.mavsdk.rpc.camera.VideoStreamSettings\x12\x44\n\x06status\x18\x03 \x01(\x0e\x32\x34.mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus\x12H\n\x08spectrum\x18\x04 \x01(\x0e\x32\x36.mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum"]\n\x11VideoStreamStatus\x12#\n\x1fVIDEO_STREAM_STATUS_NOT_RUNNING\x10\x00\x12#\n\x1fVIDEO_STREAM_STATUS_IN_PROGRESS\x10\x01"\x85\x01\n\x13VideoStreamSpectrum\x12!\n\x1dVIDEO_STREAM_SPECTRUM_UNKNOWN\x10\x00\x12\'\n#VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT\x10\x01\x12"\n\x1eVIDEO_STREAM_SPECTRUM_INFRARED\x10\x02"(\n\x10TakePhotoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"K\n\x11TakePhotoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"E\n\x19StartPhotoIntervalRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\ninterval_s\x18\x02 \x01(\x02"T\n\x1aStartPhotoIntervalResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"0\n\x18StopPhotoIntervalRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"S\n\x19StopPhotoIntervalResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult")\n\x11StartVideoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"L\n\x12StartVideoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"(\n\x10StopVideoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"K\n\x11StopVideoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"E\n\x1aStartVideoStreamingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x11\n\tstream_id\x18\x02 \x01(\x05"U\n\x1bStartVideoStreamingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"D\n\x19StopVideoStreamingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x11\n\tstream_id\x18\x02 \x01(\x05"T\n\x1aStopVideoStreamingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"M\n\x0eSetModeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12%\n\x04mode\x18\x02 \x01(\x0e\x32\x17.mavsdk.rpc.camera.Mode"I\n\x0fSetModeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"_\n\x11ListPhotosRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x34\n\x0cphotos_range\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.camera.PhotosRange"\x83\x01\n\x12ListPhotosResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12\x35\n\rcapture_infos\x18\x02 \x03(\x0b\x32\x1e.mavsdk.rpc.camera.CaptureInfo"\x1c\n\x1aSubscribeCameraListRequest"H\n\x12\x43\x61meraListResponse\x12\x32\n\x0b\x63\x61mera_list\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.CameraList"I\n\nModeUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12%\n\x04mode\x18\x02 \x01(\x0e\x32\x17.mavsdk.rpc.camera.Mode"\x16\n\x14SubscribeModeRequest"=\n\x0cModeResponse\x12-\n\x06update\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.ModeUpdate"h\n\x11VideoStreamUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12=\n\x11video_stream_info\x18\x02 \x01(\x0b\x32".mavsdk.rpc.camera.VideoStreamInfo"!\n\x1fSubscribeVideoStreamInfoRequest"O\n\x17VideoStreamInfoResponse\x12\x34\n\x06update\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.camera.VideoStreamUpdate"\x1d\n\x1bSubscribeCaptureInfoRequest"K\n\x13\x43\x61ptureInfoResponse\x12\x34\n\x0c\x63\x61pture_info\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.camera.CaptureInfo"\xa0\x05\n\x07Storage\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x10\n\x08video_on\x18\x02 \x01(\x08\x12\x19\n\x11photo_interval_on\x18\x03 \x01(\x08\x12\x18\n\x10used_storage_mib\x18\x04 \x01(\x02\x12\x1d\n\x15\x61vailable_storage_mib\x18\x05 \x01(\x02\x12\x19\n\x11total_storage_mib\x18\x06 \x01(\x02\x12\x18\n\x10recording_time_s\x18\x07 \x01(\x02\x12\x19\n\x11media_folder_name\x18\x08 \x01(\t\x12@\n\x0estorage_status\x18\t \x01(\x0e\x32(.mavsdk.rpc.camera.Storage.StorageStatus\x12\x12\n\nstorage_id\x18\n \x01(\r\x12<\n\x0cstorage_type\x18\x0b \x01(\x0e\x32&.mavsdk.rpc.camera.Storage.StorageType"\x91\x01\n\rStorageStatus\x12 \n\x1cSTORAGE_STATUS_NOT_AVAILABLE\x10\x00\x12\x1e\n\x1aSTORAGE_STATUS_UNFORMATTED\x10\x01\x12\x1c\n\x18STORAGE_STATUS_FORMATTED\x10\x02\x12 \n\x1cSTORAGE_STATUS_NOT_SUPPORTED\x10\x03"\xa0\x01\n\x0bStorageType\x12\x18\n\x14STORAGE_TYPE_UNKNOWN\x10\x00\x12\x1a\n\x16STORAGE_TYPE_USB_STICK\x10\x01\x12\x13\n\x0fSTORAGE_TYPE_SD\x10\x02\x12\x18\n\x14STORAGE_TYPE_MICROSD\x10\x03\x12\x13\n\x0fSTORAGE_TYPE_HD\x10\x07\x12\x17\n\x12STORAGE_TYPE_OTHER\x10\xfe\x01"R\n\rStorageUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12+\n\x07storage\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Storage"\x19\n\x17SubscribeStorageRequest"C\n\x0fStorageResponse\x12\x30\n\x06update\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.camera.StorageUpdate"c\n\x15\x43urrentSettingsUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x34\n\x10\x63urrent_settings\x18\x02 \x03(\x0b\x32\x1a.mavsdk.rpc.camera.Setting"!\n\x1fSubscribeCurrentSettingsRequest"S\n\x17\x43urrentSettingsResponse\x12\x38\n\x06update\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera.CurrentSettingsUpdate"p\n\x1cPossibleSettingOptionsUpdate\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12:\n\x0fsetting_options\x18\x02 \x03(\x0b\x32!.mavsdk.rpc.camera.SettingOptions"(\n&SubscribePossibleSettingOptionsRequest"a\n\x1ePossibleSettingOptionsResponse\x12?\n\x06update\x18\x01 \x01(\x0b\x32/.mavsdk.rpc.camera.PossibleSettingOptionsUpdate"V\n\x11SetSettingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12+\n\x07setting\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Setting"L\n\x12SetSettingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"&\n\x0eGetModeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"p\n\x0fGetModeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12%\n\x04mode\x18\x02 \x01(\x0e\x32\x17.mavsdk.rpc.camera.Mode"1\n\x19GetVideoStreamInfoRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"\x93\x01\n\x1aGetVideoStreamInfoResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12=\n\x11video_stream_info\x18\x02 \x01(\x0b\x32".mavsdk.rpc.camera.VideoStreamInfo")\n\x11GetStorageRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"y\n\x12GetStorageResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12+\n\x07storage\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Storage"1\n\x19GetCurrentSettingsRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"\x8a\x01\n\x1aGetCurrentSettingsResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12\x34\n\x10\x63urrent_settings\x18\x02 \x03(\x0b\x32\x1a.mavsdk.rpc.camera.Setting"8\n GetPossibleSettingOptionsRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"\x97\x01\n!GetPossibleSettingOptionsResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12:\n\x0fsetting_options\x18\x02 \x03(\x0b\x32!.mavsdk.rpc.camera.SettingOptions"V\n\x11GetSettingRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12+\n\x07setting\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Setting"y\n\x12GetSettingResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult\x12+\n\x07setting\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.camera.Setting"@\n\x14\x46ormatStorageRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\nstorage_id\x18\x02 \x01(\x05"O\n\x15\x46ormatStorageResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult",\n\x14ResetSettingsRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"O\n\x15ResetSettingsResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"*\n\x12ZoomInStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"M\n\x13ZoomInStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"+\n\x13ZoomOutStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"N\n\x14ZoomOutStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"\'\n\x0fZoomStopRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"J\n\x10ZoomStopResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"7\n\x10ZoomRangeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\r\n\x05range\x18\x02 \x01(\x02"K\n\x11ZoomRangeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"[\n\x11TrackPointRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x0f\n\x07point_x\x18\x02 \x01(\x02\x12\x0f\n\x07point_y\x18\x03 \x01(\x02\x12\x0e\n\x06radius\x18\x04 \x01(\x02"L\n\x12TrackPointResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"\x85\x01\n\x15TrackRectangleRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x12\n\ntop_left_x\x18\x02 \x01(\x02\x12\x12\n\ntop_left_y\x18\x03 \x01(\x02\x12\x16\n\x0e\x62ottom_right_x\x18\x04 \x01(\x02\x12\x16\n\x0e\x62ottom_right_y\x18\x05 \x01(\x02"P\n\x16TrackRectangleResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"(\n\x10TrackStopRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"K\n\x11TrackStopResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"+\n\x13\x46ocusInStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"N\n\x14\x46ocusInStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult",\n\x14\x46ocusOutStartRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"O\n\x15\x46ocusOutStartResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"(\n\x10\x46ocusStopRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05"K\n\x11\x46ocusStopResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"8\n\x11\x46ocusRangeRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\r\n\x05range\x18\x02 \x01(\x02"L\n\x12\x46ocusRangeResponse\x12\x36\n\rcamera_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.camera.CameraResult"\x96\x03\n\x0c\x43\x61meraResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.camera.CameraResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xb9\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x16\n\x12RESULT_IN_PROGRESS\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x10\n\x0cRESULT_ERROR\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x19\n\x15RESULT_WRONG_ARGUMENT\x10\x07\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x08\x12\x1f\n\x1bRESULT_PROTOCOL_UNSUPPORTED\x10\t\x12\x16\n\x12RESULT_UNAVAILABLE\x10\n\x12\x1c\n\x18RESULT_CAMERA_ID_INVALID\x10\x0b\x12\x1d\n\x19RESULT_ACTION_UNSUPPORTED\x10\x0c"q\n\x08Position\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x12\x1b\n\x13relative_altitude_m\x18\x04 \x01(\x02"8\n\nQuaternion\x12\t\n\x01w\x18\x01 \x01(\x02\x12\t\n\x01x\x18\x02 \x01(\x02\x12\t\n\x01y\x18\x03 \x01(\x02\x12\t\n\x01z\x18\x04 \x01(\x02"B\n\nEulerAngle\x12\x10\n\x08roll_deg\x18\x01 \x01(\x02\x12\x11\n\tpitch_deg\x18\x02 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x03 \x01(\x02"\x95\x02\n\x0b\x43\x61ptureInfo\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12-\n\x08position\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.camera.Position\x12:\n\x13\x61ttitude_quaternion\x18\x03 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.Quaternion\x12;\n\x14\x61ttitude_euler_angle\x18\x04 \x01(\x0b\x32\x1d.mavsdk.rpc.camera.EulerAngle\x12\x13\n\x0btime_utc_us\x18\x05 \x01(\x04\x12\x12\n\nis_success\x18\x06 \x01(\x08\x12\r\n\x05index\x18\x07 \x01(\x05\x12\x10\n\x08\x66ile_url\x18\x08 \x01(\t"\xeb\x01\n\x0bInformation\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nmodel_name\x18\x03 \x01(\t\x12\x17\n\x0f\x66ocal_length_mm\x18\x04 \x01(\x02\x12!\n\x19horizontal_sensor_size_mm\x18\x05 \x01(\x02\x12\x1f\n\x17vertical_sensor_size_mm\x18\x06 \x01(\x02\x12 \n\x18horizontal_resolution_px\x18\x07 \x01(\r\x12\x1e\n\x16vertical_resolution_px\x18\x08 \x01(\r"=\n\nCameraList\x12/\n\x07\x63\x61meras\x18\x01 \x03(\x0b\x32\x1e.mavsdk.rpc.camera.Information*8\n\x04Mode\x12\x10\n\x0cMODE_UNKNOWN\x10\x00\x12\x0e\n\nMODE_PHOTO\x10\x01\x12\x0e\n\nMODE_VIDEO\x10\x02*F\n\x0bPhotosRange\x12\x14\n\x10PHOTOS_RANGE_ALL\x10\x00\x12!\n\x1dPHOTOS_RANGE_SINCE_CONNECTION\x10\x01\x32\xdd\x1d\n\rCameraService\x12X\n\tTakePhoto\x12#.mavsdk.rpc.camera.TakePhotoRequest\x1a$.mavsdk.rpc.camera.TakePhotoResponse"\x00\x12s\n\x12StartPhotoInterval\x12,.mavsdk.rpc.camera.StartPhotoIntervalRequest\x1a-.mavsdk.rpc.camera.StartPhotoIntervalResponse"\x00\x12p\n\x11StopPhotoInterval\x12+.mavsdk.rpc.camera.StopPhotoIntervalRequest\x1a,.mavsdk.rpc.camera.StopPhotoIntervalResponse"\x00\x12[\n\nStartVideo\x12$.mavsdk.rpc.camera.StartVideoRequest\x1a%.mavsdk.rpc.camera.StartVideoResponse"\x00\x12X\n\tStopVideo\x12#.mavsdk.rpc.camera.StopVideoRequest\x1a$.mavsdk.rpc.camera.StopVideoResponse"\x00\x12z\n\x13StartVideoStreaming\x12-.mavsdk.rpc.camera.StartVideoStreamingRequest\x1a..mavsdk.rpc.camera.StartVideoStreamingResponse"\x04\x80\xb5\x18\x01\x12w\n\x12StopVideoStreaming\x12,.mavsdk.rpc.camera.StopVideoStreamingRequest\x1a-.mavsdk.rpc.camera.StopVideoStreamingResponse"\x04\x80\xb5\x18\x01\x12R\n\x07SetMode\x12!.mavsdk.rpc.camera.SetModeRequest\x1a".mavsdk.rpc.camera.SetModeResponse"\x00\x12[\n\nListPhotos\x12$.mavsdk.rpc.camera.ListPhotosRequest\x1a%.mavsdk.rpc.camera.ListPhotosResponse"\x00\x12o\n\x13SubscribeCameraList\x12-.mavsdk.rpc.camera.SubscribeCameraListRequest\x1a%.mavsdk.rpc.camera.CameraListResponse"\x00\x30\x01\x12\x61\n\rSubscribeMode\x12\'.mavsdk.rpc.camera.SubscribeModeRequest\x1a\x1f.mavsdk.rpc.camera.ModeResponse"\x04\x80\xb5\x18\x00\x30\x01\x12V\n\x07GetMode\x12!.mavsdk.rpc.camera.GetModeRequest\x1a".mavsdk.rpc.camera.GetModeResponse"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x18SubscribeVideoStreamInfo\x12\x32.mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest\x1a*.mavsdk.rpc.camera.VideoStreamInfoResponse"\x04\x80\xb5\x18\x00\x30\x01\x12w\n\x12GetVideoStreamInfo\x12,.mavsdk.rpc.camera.GetVideoStreamInfoRequest\x1a-.mavsdk.rpc.camera.GetVideoStreamInfoResponse"\x04\x80\xb5\x18\x01\x12v\n\x14SubscribeCaptureInfo\x12..mavsdk.rpc.camera.SubscribeCaptureInfoRequest\x1a&.mavsdk.rpc.camera.CaptureInfoResponse"\x04\x80\xb5\x18\x00\x30\x01\x12j\n\x10SubscribeStorage\x12*.mavsdk.rpc.camera.SubscribeStorageRequest\x1a".mavsdk.rpc.camera.StorageResponse"\x04\x80\xb5\x18\x00\x30\x01\x12_\n\nGetStorage\x12$.mavsdk.rpc.camera.GetStorageRequest\x1a%.mavsdk.rpc.camera.GetStorageResponse"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x18SubscribeCurrentSettings\x12\x32.mavsdk.rpc.camera.SubscribeCurrentSettingsRequest\x1a*.mavsdk.rpc.camera.CurrentSettingsResponse"\x04\x80\xb5\x18\x00\x30\x01\x12w\n\x12GetCurrentSettings\x12,.mavsdk.rpc.camera.GetCurrentSettingsRequest\x1a-.mavsdk.rpc.camera.GetCurrentSettingsResponse"\x04\x80\xb5\x18\x01\x12\x97\x01\n\x1fSubscribePossibleSettingOptions\x12\x39.mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest\x1a\x31.mavsdk.rpc.camera.PossibleSettingOptionsResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x8c\x01\n\x19GetPossibleSettingOptions\x12\x33.mavsdk.rpc.camera.GetPossibleSettingOptionsRequest\x1a\x34.mavsdk.rpc.camera.GetPossibleSettingOptionsResponse"\x04\x80\xb5\x18\x01\x12[\n\nSetSetting\x12$.mavsdk.rpc.camera.SetSettingRequest\x1a%.mavsdk.rpc.camera.SetSettingResponse"\x00\x12[\n\nGetSetting\x12$.mavsdk.rpc.camera.GetSettingRequest\x1a%.mavsdk.rpc.camera.GetSettingResponse"\x00\x12\x64\n\rFormatStorage\x12\'.mavsdk.rpc.camera.FormatStorageRequest\x1a(.mavsdk.rpc.camera.FormatStorageResponse"\x00\x12\x64\n\rResetSettings\x12\'.mavsdk.rpc.camera.ResetSettingsRequest\x1a(.mavsdk.rpc.camera.ResetSettingsResponse"\x00\x12^\n\x0bZoomInStart\x12%.mavsdk.rpc.camera.ZoomInStartRequest\x1a&.mavsdk.rpc.camera.ZoomInStartResponse"\x00\x12\x61\n\x0cZoomOutStart\x12&.mavsdk.rpc.camera.ZoomOutStartRequest\x1a\'.mavsdk.rpc.camera.ZoomOutStartResponse"\x00\x12U\n\x08ZoomStop\x12".mavsdk.rpc.camera.ZoomStopRequest\x1a#.mavsdk.rpc.camera.ZoomStopResponse"\x00\x12X\n\tZoomRange\x12#.mavsdk.rpc.camera.ZoomRangeRequest\x1a$.mavsdk.rpc.camera.ZoomRangeResponse"\x00\x12[\n\nTrackPoint\x12$.mavsdk.rpc.camera.TrackPointRequest\x1a%.mavsdk.rpc.camera.TrackPointResponse"\x00\x12g\n\x0eTrackRectangle\x12(.mavsdk.rpc.camera.TrackRectangleRequest\x1a).mavsdk.rpc.camera.TrackRectangleResponse"\x00\x12X\n\tTrackStop\x12#.mavsdk.rpc.camera.TrackStopRequest\x1a$.mavsdk.rpc.camera.TrackStopResponse"\x00\x12\x61\n\x0c\x46ocusInStart\x12&.mavsdk.rpc.camera.FocusInStartRequest\x1a\'.mavsdk.rpc.camera.FocusInStartResponse"\x00\x12\x64\n\rFocusOutStart\x12\'.mavsdk.rpc.camera.FocusOutStartRequest\x1a(.mavsdk.rpc.camera.FocusOutStartResponse"\x00\x12X\n\tFocusStop\x12#.mavsdk.rpc.camera.FocusStopRequest\x1a$.mavsdk.rpc.camera.FocusStopResponse"\x00\x12[\n\nFocusRange\x12$.mavsdk.rpc.camera.FocusRangeRequest\x1a%.mavsdk.rpc.camera.FocusRangeResponse"\x00\x42\x1f\n\x10io.mavsdk.cameraB\x0b\x43\x61meraProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'camera.camera_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "camera.camera_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\020io.mavsdk.cameraB\013CameraProto' - _globals['_CAMERASERVICE'].methods_by_name['StartVideoStreaming']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['StartVideoStreaming']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVICE'].methods_by_name['StopVideoStreaming']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['StopVideoStreaming']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVICE'].methods_by_name['SubscribeMode']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['SubscribeMode']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVICE'].methods_by_name['GetMode']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['GetMode']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVICE'].methods_by_name['SubscribeVideoStreamInfo']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['SubscribeVideoStreamInfo']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVICE'].methods_by_name['GetVideoStreamInfo']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['GetVideoStreamInfo']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVICE'].methods_by_name['SubscribeCaptureInfo']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['SubscribeCaptureInfo']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVICE'].methods_by_name['SubscribeStorage']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['SubscribeStorage']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVICE'].methods_by_name['GetStorage']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['GetStorage']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVICE'].methods_by_name['SubscribeCurrentSettings']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['SubscribeCurrentSettings']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVICE'].methods_by_name['GetCurrentSettings']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['GetCurrentSettings']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVICE'].methods_by_name['SubscribePossibleSettingOptions']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['SubscribePossibleSettingOptions']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVICE'].methods_by_name['GetPossibleSettingOptions']._loaded_options = None - _globals['_CAMERASERVICE'].methods_by_name['GetPossibleSettingOptions']._serialized_options = b'\200\265\030\001' - _globals['_MODE']._serialized_start=8664 - _globals['_MODE']._serialized_end=8720 - _globals['_PHOTOSRANGE']._serialized_start=8722 - _globals['_PHOTOSRANGE']._serialized_end=8792 - _globals['_OPTION']._serialized_start=64 - _globals['_OPTION']._serialized_end=119 - _globals['_SETTING']._serialized_start=121 - _globals['_SETTING']._serialized_end=240 - _globals['_SETTINGOPTIONS']._serialized_start=243 - _globals['_SETTINGOPTIONS']._serialized_end=392 - _globals['_VIDEOSTREAMSETTINGS']._serialized_start=395 - _globals['_VIDEOSTREAMSETTINGS']._serialized_end=592 - _globals['_VIDEOSTREAMINFO']._serialized_start=595 - _globals['_VIDEOSTREAMINFO']._serialized_end=1064 - _globals['_VIDEOSTREAMINFO_VIDEOSTREAMSTATUS']._serialized_start=835 - _globals['_VIDEOSTREAMINFO_VIDEOSTREAMSTATUS']._serialized_end=928 - _globals['_VIDEOSTREAMINFO_VIDEOSTREAMSPECTRUM']._serialized_start=931 - _globals['_VIDEOSTREAMINFO_VIDEOSTREAMSPECTRUM']._serialized_end=1064 - _globals['_TAKEPHOTOREQUEST']._serialized_start=1066 - _globals['_TAKEPHOTOREQUEST']._serialized_end=1106 - _globals['_TAKEPHOTORESPONSE']._serialized_start=1108 - _globals['_TAKEPHOTORESPONSE']._serialized_end=1183 - _globals['_STARTPHOTOINTERVALREQUEST']._serialized_start=1185 - _globals['_STARTPHOTOINTERVALREQUEST']._serialized_end=1254 - _globals['_STARTPHOTOINTERVALRESPONSE']._serialized_start=1256 - _globals['_STARTPHOTOINTERVALRESPONSE']._serialized_end=1340 - _globals['_STOPPHOTOINTERVALREQUEST']._serialized_start=1342 - _globals['_STOPPHOTOINTERVALREQUEST']._serialized_end=1390 - _globals['_STOPPHOTOINTERVALRESPONSE']._serialized_start=1392 - _globals['_STOPPHOTOINTERVALRESPONSE']._serialized_end=1475 - _globals['_STARTVIDEOREQUEST']._serialized_start=1477 - _globals['_STARTVIDEOREQUEST']._serialized_end=1518 - _globals['_STARTVIDEORESPONSE']._serialized_start=1520 - _globals['_STARTVIDEORESPONSE']._serialized_end=1596 - _globals['_STOPVIDEOREQUEST']._serialized_start=1598 - _globals['_STOPVIDEOREQUEST']._serialized_end=1638 - _globals['_STOPVIDEORESPONSE']._serialized_start=1640 - _globals['_STOPVIDEORESPONSE']._serialized_end=1715 - _globals['_STARTVIDEOSTREAMINGREQUEST']._serialized_start=1717 - _globals['_STARTVIDEOSTREAMINGREQUEST']._serialized_end=1786 - _globals['_STARTVIDEOSTREAMINGRESPONSE']._serialized_start=1788 - _globals['_STARTVIDEOSTREAMINGRESPONSE']._serialized_end=1873 - _globals['_STOPVIDEOSTREAMINGREQUEST']._serialized_start=1875 - _globals['_STOPVIDEOSTREAMINGREQUEST']._serialized_end=1943 - _globals['_STOPVIDEOSTREAMINGRESPONSE']._serialized_start=1945 - _globals['_STOPVIDEOSTREAMINGRESPONSE']._serialized_end=2029 - _globals['_SETMODEREQUEST']._serialized_start=2031 - _globals['_SETMODEREQUEST']._serialized_end=2108 - _globals['_SETMODERESPONSE']._serialized_start=2110 - _globals['_SETMODERESPONSE']._serialized_end=2183 - _globals['_LISTPHOTOSREQUEST']._serialized_start=2185 - _globals['_LISTPHOTOSREQUEST']._serialized_end=2280 - _globals['_LISTPHOTOSRESPONSE']._serialized_start=2283 - _globals['_LISTPHOTOSRESPONSE']._serialized_end=2414 - _globals['_SUBSCRIBECAMERALISTREQUEST']._serialized_start=2416 - _globals['_SUBSCRIBECAMERALISTREQUEST']._serialized_end=2444 - _globals['_CAMERALISTRESPONSE']._serialized_start=2446 - _globals['_CAMERALISTRESPONSE']._serialized_end=2518 - _globals['_MODEUPDATE']._serialized_start=2520 - _globals['_MODEUPDATE']._serialized_end=2593 - _globals['_SUBSCRIBEMODEREQUEST']._serialized_start=2595 - _globals['_SUBSCRIBEMODEREQUEST']._serialized_end=2617 - _globals['_MODERESPONSE']._serialized_start=2619 - _globals['_MODERESPONSE']._serialized_end=2680 - _globals['_VIDEOSTREAMUPDATE']._serialized_start=2682 - _globals['_VIDEOSTREAMUPDATE']._serialized_end=2786 - _globals['_SUBSCRIBEVIDEOSTREAMINFOREQUEST']._serialized_start=2788 - _globals['_SUBSCRIBEVIDEOSTREAMINFOREQUEST']._serialized_end=2821 - _globals['_VIDEOSTREAMINFORESPONSE']._serialized_start=2823 - _globals['_VIDEOSTREAMINFORESPONSE']._serialized_end=2902 - _globals['_SUBSCRIBECAPTUREINFOREQUEST']._serialized_start=2904 - _globals['_SUBSCRIBECAPTUREINFOREQUEST']._serialized_end=2933 - _globals['_CAPTUREINFORESPONSE']._serialized_start=2935 - _globals['_CAPTUREINFORESPONSE']._serialized_end=3010 - _globals['_STORAGE']._serialized_start=3013 - _globals['_STORAGE']._serialized_end=3685 - _globals['_STORAGE_STORAGESTATUS']._serialized_start=3377 - _globals['_STORAGE_STORAGESTATUS']._serialized_end=3522 - _globals['_STORAGE_STORAGETYPE']._serialized_start=3525 - _globals['_STORAGE_STORAGETYPE']._serialized_end=3685 - _globals['_STORAGEUPDATE']._serialized_start=3687 - _globals['_STORAGEUPDATE']._serialized_end=3769 - _globals['_SUBSCRIBESTORAGEREQUEST']._serialized_start=3771 - _globals['_SUBSCRIBESTORAGEREQUEST']._serialized_end=3796 - _globals['_STORAGERESPONSE']._serialized_start=3798 - _globals['_STORAGERESPONSE']._serialized_end=3865 - _globals['_CURRENTSETTINGSUPDATE']._serialized_start=3867 - _globals['_CURRENTSETTINGSUPDATE']._serialized_end=3966 - _globals['_SUBSCRIBECURRENTSETTINGSREQUEST']._serialized_start=3968 - _globals['_SUBSCRIBECURRENTSETTINGSREQUEST']._serialized_end=4001 - _globals['_CURRENTSETTINGSRESPONSE']._serialized_start=4003 - _globals['_CURRENTSETTINGSRESPONSE']._serialized_end=4086 - _globals['_POSSIBLESETTINGOPTIONSUPDATE']._serialized_start=4088 - _globals['_POSSIBLESETTINGOPTIONSUPDATE']._serialized_end=4200 - _globals['_SUBSCRIBEPOSSIBLESETTINGOPTIONSREQUEST']._serialized_start=4202 - _globals['_SUBSCRIBEPOSSIBLESETTINGOPTIONSREQUEST']._serialized_end=4242 - _globals['_POSSIBLESETTINGOPTIONSRESPONSE']._serialized_start=4244 - _globals['_POSSIBLESETTINGOPTIONSRESPONSE']._serialized_end=4341 - _globals['_SETSETTINGREQUEST']._serialized_start=4343 - _globals['_SETSETTINGREQUEST']._serialized_end=4429 - _globals['_SETSETTINGRESPONSE']._serialized_start=4431 - _globals['_SETSETTINGRESPONSE']._serialized_end=4507 - _globals['_GETMODEREQUEST']._serialized_start=4509 - _globals['_GETMODEREQUEST']._serialized_end=4547 - _globals['_GETMODERESPONSE']._serialized_start=4549 - _globals['_GETMODERESPONSE']._serialized_end=4661 - _globals['_GETVIDEOSTREAMINFOREQUEST']._serialized_start=4663 - _globals['_GETVIDEOSTREAMINFOREQUEST']._serialized_end=4712 - _globals['_GETVIDEOSTREAMINFORESPONSE']._serialized_start=4715 - _globals['_GETVIDEOSTREAMINFORESPONSE']._serialized_end=4862 - _globals['_GETSTORAGEREQUEST']._serialized_start=4864 - _globals['_GETSTORAGEREQUEST']._serialized_end=4905 - _globals['_GETSTORAGERESPONSE']._serialized_start=4907 - _globals['_GETSTORAGERESPONSE']._serialized_end=5028 - _globals['_GETCURRENTSETTINGSREQUEST']._serialized_start=5030 - _globals['_GETCURRENTSETTINGSREQUEST']._serialized_end=5079 - _globals['_GETCURRENTSETTINGSRESPONSE']._serialized_start=5082 - _globals['_GETCURRENTSETTINGSRESPONSE']._serialized_end=5220 - _globals['_GETPOSSIBLESETTINGOPTIONSREQUEST']._serialized_start=5222 - _globals['_GETPOSSIBLESETTINGOPTIONSREQUEST']._serialized_end=5278 - _globals['_GETPOSSIBLESETTINGOPTIONSRESPONSE']._serialized_start=5281 - _globals['_GETPOSSIBLESETTINGOPTIONSRESPONSE']._serialized_end=5432 - _globals['_GETSETTINGREQUEST']._serialized_start=5434 - _globals['_GETSETTINGREQUEST']._serialized_end=5520 - _globals['_GETSETTINGRESPONSE']._serialized_start=5522 - _globals['_GETSETTINGRESPONSE']._serialized_end=5643 - _globals['_FORMATSTORAGEREQUEST']._serialized_start=5645 - _globals['_FORMATSTORAGEREQUEST']._serialized_end=5709 - _globals['_FORMATSTORAGERESPONSE']._serialized_start=5711 - _globals['_FORMATSTORAGERESPONSE']._serialized_end=5790 - _globals['_RESETSETTINGSREQUEST']._serialized_start=5792 - _globals['_RESETSETTINGSREQUEST']._serialized_end=5836 - _globals['_RESETSETTINGSRESPONSE']._serialized_start=5838 - _globals['_RESETSETTINGSRESPONSE']._serialized_end=5917 - _globals['_ZOOMINSTARTREQUEST']._serialized_start=5919 - _globals['_ZOOMINSTARTREQUEST']._serialized_end=5961 - _globals['_ZOOMINSTARTRESPONSE']._serialized_start=5963 - _globals['_ZOOMINSTARTRESPONSE']._serialized_end=6040 - _globals['_ZOOMOUTSTARTREQUEST']._serialized_start=6042 - _globals['_ZOOMOUTSTARTREQUEST']._serialized_end=6085 - _globals['_ZOOMOUTSTARTRESPONSE']._serialized_start=6087 - _globals['_ZOOMOUTSTARTRESPONSE']._serialized_end=6165 - _globals['_ZOOMSTOPREQUEST']._serialized_start=6167 - _globals['_ZOOMSTOPREQUEST']._serialized_end=6206 - _globals['_ZOOMSTOPRESPONSE']._serialized_start=6208 - _globals['_ZOOMSTOPRESPONSE']._serialized_end=6282 - _globals['_ZOOMRANGEREQUEST']._serialized_start=6284 - _globals['_ZOOMRANGEREQUEST']._serialized_end=6339 - _globals['_ZOOMRANGERESPONSE']._serialized_start=6341 - _globals['_ZOOMRANGERESPONSE']._serialized_end=6416 - _globals['_TRACKPOINTREQUEST']._serialized_start=6418 - _globals['_TRACKPOINTREQUEST']._serialized_end=6509 - _globals['_TRACKPOINTRESPONSE']._serialized_start=6511 - _globals['_TRACKPOINTRESPONSE']._serialized_end=6587 - _globals['_TRACKRECTANGLEREQUEST']._serialized_start=6590 - _globals['_TRACKRECTANGLEREQUEST']._serialized_end=6723 - _globals['_TRACKRECTANGLERESPONSE']._serialized_start=6725 - _globals['_TRACKRECTANGLERESPONSE']._serialized_end=6805 - _globals['_TRACKSTOPREQUEST']._serialized_start=6807 - _globals['_TRACKSTOPREQUEST']._serialized_end=6847 - _globals['_TRACKSTOPRESPONSE']._serialized_start=6849 - _globals['_TRACKSTOPRESPONSE']._serialized_end=6924 - _globals['_FOCUSINSTARTREQUEST']._serialized_start=6926 - _globals['_FOCUSINSTARTREQUEST']._serialized_end=6969 - _globals['_FOCUSINSTARTRESPONSE']._serialized_start=6971 - _globals['_FOCUSINSTARTRESPONSE']._serialized_end=7049 - _globals['_FOCUSOUTSTARTREQUEST']._serialized_start=7051 - _globals['_FOCUSOUTSTARTREQUEST']._serialized_end=7095 - _globals['_FOCUSOUTSTARTRESPONSE']._serialized_start=7097 - _globals['_FOCUSOUTSTARTRESPONSE']._serialized_end=7176 - _globals['_FOCUSSTOPREQUEST']._serialized_start=7178 - _globals['_FOCUSSTOPREQUEST']._serialized_end=7218 - _globals['_FOCUSSTOPRESPONSE']._serialized_start=7220 - _globals['_FOCUSSTOPRESPONSE']._serialized_end=7295 - _globals['_FOCUSRANGEREQUEST']._serialized_start=7297 - _globals['_FOCUSRANGEREQUEST']._serialized_end=7353 - _globals['_FOCUSRANGERESPONSE']._serialized_start=7355 - _globals['_FOCUSRANGERESPONSE']._serialized_end=7431 - _globals['_CAMERARESULT']._serialized_start=7434 - _globals['_CAMERARESULT']._serialized_end=7840 - _globals['_CAMERARESULT_RESULT']._serialized_start=7527 - _globals['_CAMERARESULT_RESULT']._serialized_end=7840 - _globals['_POSITION']._serialized_start=7842 - _globals['_POSITION']._serialized_end=7955 - _globals['_QUATERNION']._serialized_start=7957 - _globals['_QUATERNION']._serialized_end=8013 - _globals['_EULERANGLE']._serialized_start=8015 - _globals['_EULERANGLE']._serialized_end=8081 - _globals['_CAPTUREINFO']._serialized_start=8084 - _globals['_CAPTUREINFO']._serialized_end=8361 - _globals['_INFORMATION']._serialized_start=8364 - _globals['_INFORMATION']._serialized_end=8599 - _globals['_CAMERALIST']._serialized_start=8601 - _globals['_CAMERALIST']._serialized_end=8662 - _globals['_CAMERASERVICE']._serialized_start=8795 - _globals['_CAMERASERVICE']._serialized_end=12600 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\020io.mavsdk.cameraB\013CameraProto" + _globals["_CAMERASERVICE"].methods_by_name[ + "StartVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "StartVideoStreaming" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVICE"].methods_by_name[ + "StopVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "StopVideoStreaming" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVICE"].methods_by_name["SubscribeMode"]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeMode" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVICE"].methods_by_name["GetMode"]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "GetMode" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeVideoStreamInfo" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeVideoStreamInfo" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVICE"].methods_by_name[ + "GetVideoStreamInfo" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "GetVideoStreamInfo" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeCaptureInfo" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeCaptureInfo" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeStorage" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeStorage" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVICE"].methods_by_name["GetStorage"]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "GetStorage" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeCurrentSettings" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribeCurrentSettings" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVICE"].methods_by_name[ + "GetCurrentSettings" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "GetCurrentSettings" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribePossibleSettingOptions" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "SubscribePossibleSettingOptions" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVICE"].methods_by_name[ + "GetPossibleSettingOptions" + ]._loaded_options = None + _globals["_CAMERASERVICE"].methods_by_name[ + "GetPossibleSettingOptions" + ]._serialized_options = b"\200\265\030\001" + _globals["_MODE"]._serialized_start = 8664 + _globals["_MODE"]._serialized_end = 8720 + _globals["_PHOTOSRANGE"]._serialized_start = 8722 + _globals["_PHOTOSRANGE"]._serialized_end = 8792 + _globals["_OPTION"]._serialized_start = 64 + _globals["_OPTION"]._serialized_end = 119 + _globals["_SETTING"]._serialized_start = 121 + _globals["_SETTING"]._serialized_end = 240 + _globals["_SETTINGOPTIONS"]._serialized_start = 243 + _globals["_SETTINGOPTIONS"]._serialized_end = 392 + _globals["_VIDEOSTREAMSETTINGS"]._serialized_start = 395 + _globals["_VIDEOSTREAMSETTINGS"]._serialized_end = 592 + _globals["_VIDEOSTREAMINFO"]._serialized_start = 595 + _globals["_VIDEOSTREAMINFO"]._serialized_end = 1064 + _globals["_VIDEOSTREAMINFO_VIDEOSTREAMSTATUS"]._serialized_start = 835 + _globals["_VIDEOSTREAMINFO_VIDEOSTREAMSTATUS"]._serialized_end = 928 + _globals["_VIDEOSTREAMINFO_VIDEOSTREAMSPECTRUM"]._serialized_start = 931 + _globals["_VIDEOSTREAMINFO_VIDEOSTREAMSPECTRUM"]._serialized_end = 1064 + _globals["_TAKEPHOTOREQUEST"]._serialized_start = 1066 + _globals["_TAKEPHOTOREQUEST"]._serialized_end = 1106 + _globals["_TAKEPHOTORESPONSE"]._serialized_start = 1108 + _globals["_TAKEPHOTORESPONSE"]._serialized_end = 1183 + _globals["_STARTPHOTOINTERVALREQUEST"]._serialized_start = 1185 + _globals["_STARTPHOTOINTERVALREQUEST"]._serialized_end = 1254 + _globals["_STARTPHOTOINTERVALRESPONSE"]._serialized_start = 1256 + _globals["_STARTPHOTOINTERVALRESPONSE"]._serialized_end = 1340 + _globals["_STOPPHOTOINTERVALREQUEST"]._serialized_start = 1342 + _globals["_STOPPHOTOINTERVALREQUEST"]._serialized_end = 1390 + _globals["_STOPPHOTOINTERVALRESPONSE"]._serialized_start = 1392 + _globals["_STOPPHOTOINTERVALRESPONSE"]._serialized_end = 1475 + _globals["_STARTVIDEOREQUEST"]._serialized_start = 1477 + _globals["_STARTVIDEOREQUEST"]._serialized_end = 1518 + _globals["_STARTVIDEORESPONSE"]._serialized_start = 1520 + _globals["_STARTVIDEORESPONSE"]._serialized_end = 1596 + _globals["_STOPVIDEOREQUEST"]._serialized_start = 1598 + _globals["_STOPVIDEOREQUEST"]._serialized_end = 1638 + _globals["_STOPVIDEORESPONSE"]._serialized_start = 1640 + _globals["_STOPVIDEORESPONSE"]._serialized_end = 1715 + _globals["_STARTVIDEOSTREAMINGREQUEST"]._serialized_start = 1717 + _globals["_STARTVIDEOSTREAMINGREQUEST"]._serialized_end = 1786 + _globals["_STARTVIDEOSTREAMINGRESPONSE"]._serialized_start = 1788 + _globals["_STARTVIDEOSTREAMINGRESPONSE"]._serialized_end = 1873 + _globals["_STOPVIDEOSTREAMINGREQUEST"]._serialized_start = 1875 + _globals["_STOPVIDEOSTREAMINGREQUEST"]._serialized_end = 1943 + _globals["_STOPVIDEOSTREAMINGRESPONSE"]._serialized_start = 1945 + _globals["_STOPVIDEOSTREAMINGRESPONSE"]._serialized_end = 2029 + _globals["_SETMODEREQUEST"]._serialized_start = 2031 + _globals["_SETMODEREQUEST"]._serialized_end = 2108 + _globals["_SETMODERESPONSE"]._serialized_start = 2110 + _globals["_SETMODERESPONSE"]._serialized_end = 2183 + _globals["_LISTPHOTOSREQUEST"]._serialized_start = 2185 + _globals["_LISTPHOTOSREQUEST"]._serialized_end = 2280 + _globals["_LISTPHOTOSRESPONSE"]._serialized_start = 2283 + _globals["_LISTPHOTOSRESPONSE"]._serialized_end = 2414 + _globals["_SUBSCRIBECAMERALISTREQUEST"]._serialized_start = 2416 + _globals["_SUBSCRIBECAMERALISTREQUEST"]._serialized_end = 2444 + _globals["_CAMERALISTRESPONSE"]._serialized_start = 2446 + _globals["_CAMERALISTRESPONSE"]._serialized_end = 2518 + _globals["_MODEUPDATE"]._serialized_start = 2520 + _globals["_MODEUPDATE"]._serialized_end = 2593 + _globals["_SUBSCRIBEMODEREQUEST"]._serialized_start = 2595 + _globals["_SUBSCRIBEMODEREQUEST"]._serialized_end = 2617 + _globals["_MODERESPONSE"]._serialized_start = 2619 + _globals["_MODERESPONSE"]._serialized_end = 2680 + _globals["_VIDEOSTREAMUPDATE"]._serialized_start = 2682 + _globals["_VIDEOSTREAMUPDATE"]._serialized_end = 2786 + _globals["_SUBSCRIBEVIDEOSTREAMINFOREQUEST"]._serialized_start = 2788 + _globals["_SUBSCRIBEVIDEOSTREAMINFOREQUEST"]._serialized_end = 2821 + _globals["_VIDEOSTREAMINFORESPONSE"]._serialized_start = 2823 + _globals["_VIDEOSTREAMINFORESPONSE"]._serialized_end = 2902 + _globals["_SUBSCRIBECAPTUREINFOREQUEST"]._serialized_start = 2904 + _globals["_SUBSCRIBECAPTUREINFOREQUEST"]._serialized_end = 2933 + _globals["_CAPTUREINFORESPONSE"]._serialized_start = 2935 + _globals["_CAPTUREINFORESPONSE"]._serialized_end = 3010 + _globals["_STORAGE"]._serialized_start = 3013 + _globals["_STORAGE"]._serialized_end = 3685 + _globals["_STORAGE_STORAGESTATUS"]._serialized_start = 3377 + _globals["_STORAGE_STORAGESTATUS"]._serialized_end = 3522 + _globals["_STORAGE_STORAGETYPE"]._serialized_start = 3525 + _globals["_STORAGE_STORAGETYPE"]._serialized_end = 3685 + _globals["_STORAGEUPDATE"]._serialized_start = 3687 + _globals["_STORAGEUPDATE"]._serialized_end = 3769 + _globals["_SUBSCRIBESTORAGEREQUEST"]._serialized_start = 3771 + _globals["_SUBSCRIBESTORAGEREQUEST"]._serialized_end = 3796 + _globals["_STORAGERESPONSE"]._serialized_start = 3798 + _globals["_STORAGERESPONSE"]._serialized_end = 3865 + _globals["_CURRENTSETTINGSUPDATE"]._serialized_start = 3867 + _globals["_CURRENTSETTINGSUPDATE"]._serialized_end = 3966 + _globals["_SUBSCRIBECURRENTSETTINGSREQUEST"]._serialized_start = 3968 + _globals["_SUBSCRIBECURRENTSETTINGSREQUEST"]._serialized_end = 4001 + _globals["_CURRENTSETTINGSRESPONSE"]._serialized_start = 4003 + _globals["_CURRENTSETTINGSRESPONSE"]._serialized_end = 4086 + _globals["_POSSIBLESETTINGOPTIONSUPDATE"]._serialized_start = 4088 + _globals["_POSSIBLESETTINGOPTIONSUPDATE"]._serialized_end = 4200 + _globals["_SUBSCRIBEPOSSIBLESETTINGOPTIONSREQUEST"]._serialized_start = 4202 + _globals["_SUBSCRIBEPOSSIBLESETTINGOPTIONSREQUEST"]._serialized_end = 4242 + _globals["_POSSIBLESETTINGOPTIONSRESPONSE"]._serialized_start = 4244 + _globals["_POSSIBLESETTINGOPTIONSRESPONSE"]._serialized_end = 4341 + _globals["_SETSETTINGREQUEST"]._serialized_start = 4343 + _globals["_SETSETTINGREQUEST"]._serialized_end = 4429 + _globals["_SETSETTINGRESPONSE"]._serialized_start = 4431 + _globals["_SETSETTINGRESPONSE"]._serialized_end = 4507 + _globals["_GETMODEREQUEST"]._serialized_start = 4509 + _globals["_GETMODEREQUEST"]._serialized_end = 4547 + _globals["_GETMODERESPONSE"]._serialized_start = 4549 + _globals["_GETMODERESPONSE"]._serialized_end = 4661 + _globals["_GETVIDEOSTREAMINFOREQUEST"]._serialized_start = 4663 + _globals["_GETVIDEOSTREAMINFOREQUEST"]._serialized_end = 4712 + _globals["_GETVIDEOSTREAMINFORESPONSE"]._serialized_start = 4715 + _globals["_GETVIDEOSTREAMINFORESPONSE"]._serialized_end = 4862 + _globals["_GETSTORAGEREQUEST"]._serialized_start = 4864 + _globals["_GETSTORAGEREQUEST"]._serialized_end = 4905 + _globals["_GETSTORAGERESPONSE"]._serialized_start = 4907 + _globals["_GETSTORAGERESPONSE"]._serialized_end = 5028 + _globals["_GETCURRENTSETTINGSREQUEST"]._serialized_start = 5030 + _globals["_GETCURRENTSETTINGSREQUEST"]._serialized_end = 5079 + _globals["_GETCURRENTSETTINGSRESPONSE"]._serialized_start = 5082 + _globals["_GETCURRENTSETTINGSRESPONSE"]._serialized_end = 5220 + _globals["_GETPOSSIBLESETTINGOPTIONSREQUEST"]._serialized_start = 5222 + _globals["_GETPOSSIBLESETTINGOPTIONSREQUEST"]._serialized_end = 5278 + _globals["_GETPOSSIBLESETTINGOPTIONSRESPONSE"]._serialized_start = 5281 + _globals["_GETPOSSIBLESETTINGOPTIONSRESPONSE"]._serialized_end = 5432 + _globals["_GETSETTINGREQUEST"]._serialized_start = 5434 + _globals["_GETSETTINGREQUEST"]._serialized_end = 5520 + _globals["_GETSETTINGRESPONSE"]._serialized_start = 5522 + _globals["_GETSETTINGRESPONSE"]._serialized_end = 5643 + _globals["_FORMATSTORAGEREQUEST"]._serialized_start = 5645 + _globals["_FORMATSTORAGEREQUEST"]._serialized_end = 5709 + _globals["_FORMATSTORAGERESPONSE"]._serialized_start = 5711 + _globals["_FORMATSTORAGERESPONSE"]._serialized_end = 5790 + _globals["_RESETSETTINGSREQUEST"]._serialized_start = 5792 + _globals["_RESETSETTINGSREQUEST"]._serialized_end = 5836 + _globals["_RESETSETTINGSRESPONSE"]._serialized_start = 5838 + _globals["_RESETSETTINGSRESPONSE"]._serialized_end = 5917 + _globals["_ZOOMINSTARTREQUEST"]._serialized_start = 5919 + _globals["_ZOOMINSTARTREQUEST"]._serialized_end = 5961 + _globals["_ZOOMINSTARTRESPONSE"]._serialized_start = 5963 + _globals["_ZOOMINSTARTRESPONSE"]._serialized_end = 6040 + _globals["_ZOOMOUTSTARTREQUEST"]._serialized_start = 6042 + _globals["_ZOOMOUTSTARTREQUEST"]._serialized_end = 6085 + _globals["_ZOOMOUTSTARTRESPONSE"]._serialized_start = 6087 + _globals["_ZOOMOUTSTARTRESPONSE"]._serialized_end = 6165 + _globals["_ZOOMSTOPREQUEST"]._serialized_start = 6167 + _globals["_ZOOMSTOPREQUEST"]._serialized_end = 6206 + _globals["_ZOOMSTOPRESPONSE"]._serialized_start = 6208 + _globals["_ZOOMSTOPRESPONSE"]._serialized_end = 6282 + _globals["_ZOOMRANGEREQUEST"]._serialized_start = 6284 + _globals["_ZOOMRANGEREQUEST"]._serialized_end = 6339 + _globals["_ZOOMRANGERESPONSE"]._serialized_start = 6341 + _globals["_ZOOMRANGERESPONSE"]._serialized_end = 6416 + _globals["_TRACKPOINTREQUEST"]._serialized_start = 6418 + _globals["_TRACKPOINTREQUEST"]._serialized_end = 6509 + _globals["_TRACKPOINTRESPONSE"]._serialized_start = 6511 + _globals["_TRACKPOINTRESPONSE"]._serialized_end = 6587 + _globals["_TRACKRECTANGLEREQUEST"]._serialized_start = 6590 + _globals["_TRACKRECTANGLEREQUEST"]._serialized_end = 6723 + _globals["_TRACKRECTANGLERESPONSE"]._serialized_start = 6725 + _globals["_TRACKRECTANGLERESPONSE"]._serialized_end = 6805 + _globals["_TRACKSTOPREQUEST"]._serialized_start = 6807 + _globals["_TRACKSTOPREQUEST"]._serialized_end = 6847 + _globals["_TRACKSTOPRESPONSE"]._serialized_start = 6849 + _globals["_TRACKSTOPRESPONSE"]._serialized_end = 6924 + _globals["_FOCUSINSTARTREQUEST"]._serialized_start = 6926 + _globals["_FOCUSINSTARTREQUEST"]._serialized_end = 6969 + _globals["_FOCUSINSTARTRESPONSE"]._serialized_start = 6971 + _globals["_FOCUSINSTARTRESPONSE"]._serialized_end = 7049 + _globals["_FOCUSOUTSTARTREQUEST"]._serialized_start = 7051 + _globals["_FOCUSOUTSTARTREQUEST"]._serialized_end = 7095 + _globals["_FOCUSOUTSTARTRESPONSE"]._serialized_start = 7097 + _globals["_FOCUSOUTSTARTRESPONSE"]._serialized_end = 7176 + _globals["_FOCUSSTOPREQUEST"]._serialized_start = 7178 + _globals["_FOCUSSTOPREQUEST"]._serialized_end = 7218 + _globals["_FOCUSSTOPRESPONSE"]._serialized_start = 7220 + _globals["_FOCUSSTOPRESPONSE"]._serialized_end = 7295 + _globals["_FOCUSRANGEREQUEST"]._serialized_start = 7297 + _globals["_FOCUSRANGEREQUEST"]._serialized_end = 7353 + _globals["_FOCUSRANGERESPONSE"]._serialized_start = 7355 + _globals["_FOCUSRANGERESPONSE"]._serialized_end = 7431 + _globals["_CAMERARESULT"]._serialized_start = 7434 + _globals["_CAMERARESULT"]._serialized_end = 7840 + _globals["_CAMERARESULT_RESULT"]._serialized_start = 7527 + _globals["_CAMERARESULT_RESULT"]._serialized_end = 7840 + _globals["_POSITION"]._serialized_start = 7842 + _globals["_POSITION"]._serialized_end = 7955 + _globals["_QUATERNION"]._serialized_start = 7957 + _globals["_QUATERNION"]._serialized_end = 8013 + _globals["_EULERANGLE"]._serialized_start = 8015 + _globals["_EULERANGLE"]._serialized_end = 8081 + _globals["_CAPTUREINFO"]._serialized_start = 8084 + _globals["_CAPTUREINFO"]._serialized_end = 8361 + _globals["_INFORMATION"]._serialized_start = 8364 + _globals["_INFORMATION"]._serialized_end = 8599 + _globals["_CAMERALIST"]._serialized_start = 8601 + _globals["_CAMERALIST"]._serialized_end = 8662 + _globals["_CAMERASERVICE"]._serialized_start = 8795 + _globals["_CAMERASERVICE"]._serialized_end = 12600 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/camera_pb2_grpc.py b/mavsdk/camera_pb2_grpc.py index 48219ac8..c9b52695 100644 --- a/mavsdk/camera_pb2_grpc.py +++ b/mavsdk/camera_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import camera_pb2 as camera_dot_camera__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in camera/camera_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in camera/camera_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -43,185 +47,221 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.TakePhoto = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/TakePhoto', - request_serializer=camera_dot_camera__pb2.TakePhotoRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.TakePhotoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/TakePhoto", + request_serializer=camera_dot_camera__pb2.TakePhotoRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.TakePhotoResponse.FromString, + _registered_method=True, + ) self.StartPhotoInterval = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/StartPhotoInterval', - request_serializer=camera_dot_camera__pb2.StartPhotoIntervalRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StartPhotoIntervalResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/StartPhotoInterval", + request_serializer=camera_dot_camera__pb2.StartPhotoIntervalRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StartPhotoIntervalResponse.FromString, + _registered_method=True, + ) self.StopPhotoInterval = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/StopPhotoInterval', - request_serializer=camera_dot_camera__pb2.StopPhotoIntervalRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StopPhotoIntervalResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/StopPhotoInterval", + request_serializer=camera_dot_camera__pb2.StopPhotoIntervalRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StopPhotoIntervalResponse.FromString, + _registered_method=True, + ) self.StartVideo = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/StartVideo', - request_serializer=camera_dot_camera__pb2.StartVideoRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StartVideoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/StartVideo", + request_serializer=camera_dot_camera__pb2.StartVideoRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StartVideoResponse.FromString, + _registered_method=True, + ) self.StopVideo = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/StopVideo', - request_serializer=camera_dot_camera__pb2.StopVideoRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StopVideoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/StopVideo", + request_serializer=camera_dot_camera__pb2.StopVideoRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StopVideoResponse.FromString, + _registered_method=True, + ) self.StartVideoStreaming = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/StartVideoStreaming', - request_serializer=camera_dot_camera__pb2.StartVideoStreamingRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StartVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/StartVideoStreaming", + request_serializer=camera_dot_camera__pb2.StartVideoStreamingRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StartVideoStreamingResponse.FromString, + _registered_method=True, + ) self.StopVideoStreaming = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/StopVideoStreaming', - request_serializer=camera_dot_camera__pb2.StopVideoStreamingRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StopVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/StopVideoStreaming", + request_serializer=camera_dot_camera__pb2.StopVideoStreamingRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StopVideoStreamingResponse.FromString, + _registered_method=True, + ) self.SetMode = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/SetMode', - request_serializer=camera_dot_camera__pb2.SetModeRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.SetModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SetMode", + request_serializer=camera_dot_camera__pb2.SetModeRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.SetModeResponse.FromString, + _registered_method=True, + ) self.ListPhotos = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/ListPhotos', - request_serializer=camera_dot_camera__pb2.ListPhotosRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ListPhotosResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/ListPhotos", + request_serializer=camera_dot_camera__pb2.ListPhotosRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ListPhotosResponse.FromString, + _registered_method=True, + ) self.SubscribeCameraList = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribeCameraList', - request_serializer=camera_dot_camera__pb2.SubscribeCameraListRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.CameraListResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribeCameraList", + request_serializer=camera_dot_camera__pb2.SubscribeCameraListRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.CameraListResponse.FromString, + _registered_method=True, + ) self.SubscribeMode = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribeMode', - request_serializer=camera_dot_camera__pb2.SubscribeModeRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribeMode", + request_serializer=camera_dot_camera__pb2.SubscribeModeRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ModeResponse.FromString, + _registered_method=True, + ) self.GetMode = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/GetMode', - request_serializer=camera_dot_camera__pb2.GetModeRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.GetModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/GetMode", + request_serializer=camera_dot_camera__pb2.GetModeRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.GetModeResponse.FromString, + _registered_method=True, + ) self.SubscribeVideoStreamInfo = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribeVideoStreamInfo', - request_serializer=camera_dot_camera__pb2.SubscribeVideoStreamInfoRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.VideoStreamInfoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribeVideoStreamInfo", + request_serializer=camera_dot_camera__pb2.SubscribeVideoStreamInfoRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.VideoStreamInfoResponse.FromString, + _registered_method=True, + ) self.GetVideoStreamInfo = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/GetVideoStreamInfo', - request_serializer=camera_dot_camera__pb2.GetVideoStreamInfoRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.GetVideoStreamInfoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/GetVideoStreamInfo", + request_serializer=camera_dot_camera__pb2.GetVideoStreamInfoRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.GetVideoStreamInfoResponse.FromString, + _registered_method=True, + ) self.SubscribeCaptureInfo = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribeCaptureInfo', - request_serializer=camera_dot_camera__pb2.SubscribeCaptureInfoRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.CaptureInfoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribeCaptureInfo", + request_serializer=camera_dot_camera__pb2.SubscribeCaptureInfoRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.CaptureInfoResponse.FromString, + _registered_method=True, + ) self.SubscribeStorage = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribeStorage', - request_serializer=camera_dot_camera__pb2.SubscribeStorageRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.StorageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribeStorage", + request_serializer=camera_dot_camera__pb2.SubscribeStorageRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.StorageResponse.FromString, + _registered_method=True, + ) self.GetStorage = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/GetStorage', - request_serializer=camera_dot_camera__pb2.GetStorageRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.GetStorageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/GetStorage", + request_serializer=camera_dot_camera__pb2.GetStorageRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.GetStorageResponse.FromString, + _registered_method=True, + ) self.SubscribeCurrentSettings = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribeCurrentSettings', - request_serializer=camera_dot_camera__pb2.SubscribeCurrentSettingsRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.CurrentSettingsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribeCurrentSettings", + request_serializer=camera_dot_camera__pb2.SubscribeCurrentSettingsRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.CurrentSettingsResponse.FromString, + _registered_method=True, + ) self.GetCurrentSettings = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/GetCurrentSettings', - request_serializer=camera_dot_camera__pb2.GetCurrentSettingsRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.GetCurrentSettingsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/GetCurrentSettings", + request_serializer=camera_dot_camera__pb2.GetCurrentSettingsRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.GetCurrentSettingsResponse.FromString, + _registered_method=True, + ) self.SubscribePossibleSettingOptions = channel.unary_stream( - '/mavsdk.rpc.camera.CameraService/SubscribePossibleSettingOptions', - request_serializer=camera_dot_camera__pb2.SubscribePossibleSettingOptionsRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.PossibleSettingOptionsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SubscribePossibleSettingOptions", + request_serializer=camera_dot_camera__pb2.SubscribePossibleSettingOptionsRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.PossibleSettingOptionsResponse.FromString, + _registered_method=True, + ) self.GetPossibleSettingOptions = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/GetPossibleSettingOptions', - request_serializer=camera_dot_camera__pb2.GetPossibleSettingOptionsRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.GetPossibleSettingOptionsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/GetPossibleSettingOptions", + request_serializer=camera_dot_camera__pb2.GetPossibleSettingOptionsRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.GetPossibleSettingOptionsResponse.FromString, + _registered_method=True, + ) self.SetSetting = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/SetSetting', - request_serializer=camera_dot_camera__pb2.SetSettingRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.SetSettingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/SetSetting", + request_serializer=camera_dot_camera__pb2.SetSettingRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.SetSettingResponse.FromString, + _registered_method=True, + ) self.GetSetting = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/GetSetting', - request_serializer=camera_dot_camera__pb2.GetSettingRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.GetSettingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/GetSetting", + request_serializer=camera_dot_camera__pb2.GetSettingRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.GetSettingResponse.FromString, + _registered_method=True, + ) self.FormatStorage = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/FormatStorage', - request_serializer=camera_dot_camera__pb2.FormatStorageRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.FormatStorageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/FormatStorage", + request_serializer=camera_dot_camera__pb2.FormatStorageRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.FormatStorageResponse.FromString, + _registered_method=True, + ) self.ResetSettings = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/ResetSettings', - request_serializer=camera_dot_camera__pb2.ResetSettingsRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ResetSettingsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/ResetSettings", + request_serializer=camera_dot_camera__pb2.ResetSettingsRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ResetSettingsResponse.FromString, + _registered_method=True, + ) self.ZoomInStart = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/ZoomInStart', - request_serializer=camera_dot_camera__pb2.ZoomInStartRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ZoomInStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/ZoomInStart", + request_serializer=camera_dot_camera__pb2.ZoomInStartRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ZoomInStartResponse.FromString, + _registered_method=True, + ) self.ZoomOutStart = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/ZoomOutStart', - request_serializer=camera_dot_camera__pb2.ZoomOutStartRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ZoomOutStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/ZoomOutStart", + request_serializer=camera_dot_camera__pb2.ZoomOutStartRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ZoomOutStartResponse.FromString, + _registered_method=True, + ) self.ZoomStop = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/ZoomStop', - request_serializer=camera_dot_camera__pb2.ZoomStopRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ZoomStopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/ZoomStop", + request_serializer=camera_dot_camera__pb2.ZoomStopRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ZoomStopResponse.FromString, + _registered_method=True, + ) self.ZoomRange = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/ZoomRange', - request_serializer=camera_dot_camera__pb2.ZoomRangeRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.ZoomRangeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/ZoomRange", + request_serializer=camera_dot_camera__pb2.ZoomRangeRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.ZoomRangeResponse.FromString, + _registered_method=True, + ) self.TrackPoint = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/TrackPoint', - request_serializer=camera_dot_camera__pb2.TrackPointRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.TrackPointResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/TrackPoint", + request_serializer=camera_dot_camera__pb2.TrackPointRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.TrackPointResponse.FromString, + _registered_method=True, + ) self.TrackRectangle = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/TrackRectangle', - request_serializer=camera_dot_camera__pb2.TrackRectangleRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.TrackRectangleResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/TrackRectangle", + request_serializer=camera_dot_camera__pb2.TrackRectangleRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.TrackRectangleResponse.FromString, + _registered_method=True, + ) self.TrackStop = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/TrackStop', - request_serializer=camera_dot_camera__pb2.TrackStopRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.TrackStopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/TrackStop", + request_serializer=camera_dot_camera__pb2.TrackStopRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.TrackStopResponse.FromString, + _registered_method=True, + ) self.FocusInStart = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/FocusInStart', - request_serializer=camera_dot_camera__pb2.FocusInStartRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.FocusInStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/FocusInStart", + request_serializer=camera_dot_camera__pb2.FocusInStartRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.FocusInStartResponse.FromString, + _registered_method=True, + ) self.FocusOutStart = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/FocusOutStart', - request_serializer=camera_dot_camera__pb2.FocusOutStartRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.FocusOutStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/FocusOutStart", + request_serializer=camera_dot_camera__pb2.FocusOutStartRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.FocusOutStartResponse.FromString, + _registered_method=True, + ) self.FocusStop = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/FocusStop', - request_serializer=camera_dot_camera__pb2.FocusStopRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.FocusStopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/FocusStop", + request_serializer=camera_dot_camera__pb2.FocusStopRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.FocusStopResponse.FromString, + _registered_method=True, + ) self.FocusRange = channel.unary_unary( - '/mavsdk.rpc.camera.CameraService/FocusRange', - request_serializer=camera_dot_camera__pb2.FocusRangeRequest.SerializeToString, - response_deserializer=camera_dot_camera__pb2.FocusRangeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera.CameraService/FocusRange", + request_serializer=camera_dot_camera__pb2.FocusRangeRequest.SerializeToString, + response_deserializer=camera_dot_camera__pb2.FocusRangeResponse.FromString, + _registered_method=True, + ) class CameraServiceServicer(object): @@ -240,64 +280,64 @@ def TakePhoto(self, request, context): Take one photo. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StartPhotoInterval(self, request, context): """ Start photo timelapse with a given interval. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StopPhotoInterval(self, request, context): """ Stop a running photo timelapse. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StartVideo(self, request, context): """ Start a video recording. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StopVideo(self, request, context): """ Stop a running video recording. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StartVideoStreaming(self, request, context): """ Start video streaming. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StopVideoStreaming(self, request, context): """ Stop current video streaming. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetMode(self, request, context): """ Set camera mode. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ListPhotos(self, request, context): """ @@ -308,8 +348,8 @@ def ListPhotos(self, request, context): images over time. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCameraList(self, request, context): """ @@ -319,96 +359,96 @@ def SubscribeCameraList(self, request, context): Based on the camera ID, we can then address a specific camera. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeMode(self, request, context): """ Subscribe to camera mode updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetMode(self, request, context): """ Get camera mode. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeVideoStreamInfo(self, request, context): """ Subscribe to video stream info updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetVideoStreamInfo(self, request, context): """ Get video stream info. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCaptureInfo(self, request, context): """ Subscribe to capture info updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStorage(self, request, context): """ Subscribe to camera's storage status updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetStorage(self, request, context): """ Get camera's storage status. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCurrentSettings(self, request, context): """ Get the list of current camera settings. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetCurrentSettings(self, request, context): """ Get current settings. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribePossibleSettingOptions(self, request, context): """ Get the list of settings that can be changed. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetPossibleSettingOptions(self, request, context): """ Get possible setting options. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetSetting(self, request, context): """ @@ -417,8 +457,8 @@ def SetSetting(self, request, context): Only setting_id of setting and option_id of option needs to be set. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetSetting(self, request, context): """ @@ -427,8 +467,8 @@ def GetSetting(self, request, context): Only setting_id of setting needs to be set. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def FormatStorage(self, request, context): """ @@ -437,8 +477,8 @@ def FormatStorage(self, request, context): This will delete all content of the camera storage! """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ResetSettings(self, request, context): """ @@ -447,288 +487,291 @@ def ResetSettings(self, request, context): This will reset all camera settings to default value """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ZoomInStart(self, request, context): """ Start zooming in. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ZoomOutStart(self, request, context): """ Start zooming out. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ZoomStop(self, request, context): """ Stop zooming. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ZoomRange(self, request, context): """ Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def TrackPoint(self, request, context): """ Track point. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def TrackRectangle(self, request, context): """ Track rectangle. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def TrackStop(self, request, context): """ Stop tracking. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def FocusInStart(self, request, context): """ Start focusing in. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def FocusOutStart(self, request, context): """ Start focusing out. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def FocusStop(self, request, context): """ Stop focus. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def FocusRange(self, request, context): """ Focus with range value of full range (value between 0.0 and 100.0). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_CameraServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'TakePhoto': grpc.unary_unary_rpc_method_handler( - servicer.TakePhoto, - request_deserializer=camera_dot_camera__pb2.TakePhotoRequest.FromString, - response_serializer=camera_dot_camera__pb2.TakePhotoResponse.SerializeToString, - ), - 'StartPhotoInterval': grpc.unary_unary_rpc_method_handler( - servicer.StartPhotoInterval, - request_deserializer=camera_dot_camera__pb2.StartPhotoIntervalRequest.FromString, - response_serializer=camera_dot_camera__pb2.StartPhotoIntervalResponse.SerializeToString, - ), - 'StopPhotoInterval': grpc.unary_unary_rpc_method_handler( - servicer.StopPhotoInterval, - request_deserializer=camera_dot_camera__pb2.StopPhotoIntervalRequest.FromString, - response_serializer=camera_dot_camera__pb2.StopPhotoIntervalResponse.SerializeToString, - ), - 'StartVideo': grpc.unary_unary_rpc_method_handler( - servicer.StartVideo, - request_deserializer=camera_dot_camera__pb2.StartVideoRequest.FromString, - response_serializer=camera_dot_camera__pb2.StartVideoResponse.SerializeToString, - ), - 'StopVideo': grpc.unary_unary_rpc_method_handler( - servicer.StopVideo, - request_deserializer=camera_dot_camera__pb2.StopVideoRequest.FromString, - response_serializer=camera_dot_camera__pb2.StopVideoResponse.SerializeToString, - ), - 'StartVideoStreaming': grpc.unary_unary_rpc_method_handler( - servicer.StartVideoStreaming, - request_deserializer=camera_dot_camera__pb2.StartVideoStreamingRequest.FromString, - response_serializer=camera_dot_camera__pb2.StartVideoStreamingResponse.SerializeToString, - ), - 'StopVideoStreaming': grpc.unary_unary_rpc_method_handler( - servicer.StopVideoStreaming, - request_deserializer=camera_dot_camera__pb2.StopVideoStreamingRequest.FromString, - response_serializer=camera_dot_camera__pb2.StopVideoStreamingResponse.SerializeToString, - ), - 'SetMode': grpc.unary_unary_rpc_method_handler( - servicer.SetMode, - request_deserializer=camera_dot_camera__pb2.SetModeRequest.FromString, - response_serializer=camera_dot_camera__pb2.SetModeResponse.SerializeToString, - ), - 'ListPhotos': grpc.unary_unary_rpc_method_handler( - servicer.ListPhotos, - request_deserializer=camera_dot_camera__pb2.ListPhotosRequest.FromString, - response_serializer=camera_dot_camera__pb2.ListPhotosResponse.SerializeToString, - ), - 'SubscribeCameraList': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCameraList, - request_deserializer=camera_dot_camera__pb2.SubscribeCameraListRequest.FromString, - response_serializer=camera_dot_camera__pb2.CameraListResponse.SerializeToString, - ), - 'SubscribeMode': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeMode, - request_deserializer=camera_dot_camera__pb2.SubscribeModeRequest.FromString, - response_serializer=camera_dot_camera__pb2.ModeResponse.SerializeToString, - ), - 'GetMode': grpc.unary_unary_rpc_method_handler( - servicer.GetMode, - request_deserializer=camera_dot_camera__pb2.GetModeRequest.FromString, - response_serializer=camera_dot_camera__pb2.GetModeResponse.SerializeToString, - ), - 'SubscribeVideoStreamInfo': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeVideoStreamInfo, - request_deserializer=camera_dot_camera__pb2.SubscribeVideoStreamInfoRequest.FromString, - response_serializer=camera_dot_camera__pb2.VideoStreamInfoResponse.SerializeToString, - ), - 'GetVideoStreamInfo': grpc.unary_unary_rpc_method_handler( - servicer.GetVideoStreamInfo, - request_deserializer=camera_dot_camera__pb2.GetVideoStreamInfoRequest.FromString, - response_serializer=camera_dot_camera__pb2.GetVideoStreamInfoResponse.SerializeToString, - ), - 'SubscribeCaptureInfo': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCaptureInfo, - request_deserializer=camera_dot_camera__pb2.SubscribeCaptureInfoRequest.FromString, - response_serializer=camera_dot_camera__pb2.CaptureInfoResponse.SerializeToString, - ), - 'SubscribeStorage': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStorage, - request_deserializer=camera_dot_camera__pb2.SubscribeStorageRequest.FromString, - response_serializer=camera_dot_camera__pb2.StorageResponse.SerializeToString, - ), - 'GetStorage': grpc.unary_unary_rpc_method_handler( - servicer.GetStorage, - request_deserializer=camera_dot_camera__pb2.GetStorageRequest.FromString, - response_serializer=camera_dot_camera__pb2.GetStorageResponse.SerializeToString, - ), - 'SubscribeCurrentSettings': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCurrentSettings, - request_deserializer=camera_dot_camera__pb2.SubscribeCurrentSettingsRequest.FromString, - response_serializer=camera_dot_camera__pb2.CurrentSettingsResponse.SerializeToString, - ), - 'GetCurrentSettings': grpc.unary_unary_rpc_method_handler( - servicer.GetCurrentSettings, - request_deserializer=camera_dot_camera__pb2.GetCurrentSettingsRequest.FromString, - response_serializer=camera_dot_camera__pb2.GetCurrentSettingsResponse.SerializeToString, - ), - 'SubscribePossibleSettingOptions': grpc.unary_stream_rpc_method_handler( - servicer.SubscribePossibleSettingOptions, - request_deserializer=camera_dot_camera__pb2.SubscribePossibleSettingOptionsRequest.FromString, - response_serializer=camera_dot_camera__pb2.PossibleSettingOptionsResponse.SerializeToString, - ), - 'GetPossibleSettingOptions': grpc.unary_unary_rpc_method_handler( - servicer.GetPossibleSettingOptions, - request_deserializer=camera_dot_camera__pb2.GetPossibleSettingOptionsRequest.FromString, - response_serializer=camera_dot_camera__pb2.GetPossibleSettingOptionsResponse.SerializeToString, - ), - 'SetSetting': grpc.unary_unary_rpc_method_handler( - servicer.SetSetting, - request_deserializer=camera_dot_camera__pb2.SetSettingRequest.FromString, - response_serializer=camera_dot_camera__pb2.SetSettingResponse.SerializeToString, - ), - 'GetSetting': grpc.unary_unary_rpc_method_handler( - servicer.GetSetting, - request_deserializer=camera_dot_camera__pb2.GetSettingRequest.FromString, - response_serializer=camera_dot_camera__pb2.GetSettingResponse.SerializeToString, - ), - 'FormatStorage': grpc.unary_unary_rpc_method_handler( - servicer.FormatStorage, - request_deserializer=camera_dot_camera__pb2.FormatStorageRequest.FromString, - response_serializer=camera_dot_camera__pb2.FormatStorageResponse.SerializeToString, - ), - 'ResetSettings': grpc.unary_unary_rpc_method_handler( - servicer.ResetSettings, - request_deserializer=camera_dot_camera__pb2.ResetSettingsRequest.FromString, - response_serializer=camera_dot_camera__pb2.ResetSettingsResponse.SerializeToString, - ), - 'ZoomInStart': grpc.unary_unary_rpc_method_handler( - servicer.ZoomInStart, - request_deserializer=camera_dot_camera__pb2.ZoomInStartRequest.FromString, - response_serializer=camera_dot_camera__pb2.ZoomInStartResponse.SerializeToString, - ), - 'ZoomOutStart': grpc.unary_unary_rpc_method_handler( - servicer.ZoomOutStart, - request_deserializer=camera_dot_camera__pb2.ZoomOutStartRequest.FromString, - response_serializer=camera_dot_camera__pb2.ZoomOutStartResponse.SerializeToString, - ), - 'ZoomStop': grpc.unary_unary_rpc_method_handler( - servicer.ZoomStop, - request_deserializer=camera_dot_camera__pb2.ZoomStopRequest.FromString, - response_serializer=camera_dot_camera__pb2.ZoomStopResponse.SerializeToString, - ), - 'ZoomRange': grpc.unary_unary_rpc_method_handler( - servicer.ZoomRange, - request_deserializer=camera_dot_camera__pb2.ZoomRangeRequest.FromString, - response_serializer=camera_dot_camera__pb2.ZoomRangeResponse.SerializeToString, - ), - 'TrackPoint': grpc.unary_unary_rpc_method_handler( - servicer.TrackPoint, - request_deserializer=camera_dot_camera__pb2.TrackPointRequest.FromString, - response_serializer=camera_dot_camera__pb2.TrackPointResponse.SerializeToString, - ), - 'TrackRectangle': grpc.unary_unary_rpc_method_handler( - servicer.TrackRectangle, - request_deserializer=camera_dot_camera__pb2.TrackRectangleRequest.FromString, - response_serializer=camera_dot_camera__pb2.TrackRectangleResponse.SerializeToString, - ), - 'TrackStop': grpc.unary_unary_rpc_method_handler( - servicer.TrackStop, - request_deserializer=camera_dot_camera__pb2.TrackStopRequest.FromString, - response_serializer=camera_dot_camera__pb2.TrackStopResponse.SerializeToString, - ), - 'FocusInStart': grpc.unary_unary_rpc_method_handler( - servicer.FocusInStart, - request_deserializer=camera_dot_camera__pb2.FocusInStartRequest.FromString, - response_serializer=camera_dot_camera__pb2.FocusInStartResponse.SerializeToString, - ), - 'FocusOutStart': grpc.unary_unary_rpc_method_handler( - servicer.FocusOutStart, - request_deserializer=camera_dot_camera__pb2.FocusOutStartRequest.FromString, - response_serializer=camera_dot_camera__pb2.FocusOutStartResponse.SerializeToString, - ), - 'FocusStop': grpc.unary_unary_rpc_method_handler( - servicer.FocusStop, - request_deserializer=camera_dot_camera__pb2.FocusStopRequest.FromString, - response_serializer=camera_dot_camera__pb2.FocusStopResponse.SerializeToString, - ), - 'FocusRange': grpc.unary_unary_rpc_method_handler( - servicer.FocusRange, - request_deserializer=camera_dot_camera__pb2.FocusRangeRequest.FromString, - response_serializer=camera_dot_camera__pb2.FocusRangeResponse.SerializeToString, - ), + "TakePhoto": grpc.unary_unary_rpc_method_handler( + servicer.TakePhoto, + request_deserializer=camera_dot_camera__pb2.TakePhotoRequest.FromString, + response_serializer=camera_dot_camera__pb2.TakePhotoResponse.SerializeToString, + ), + "StartPhotoInterval": grpc.unary_unary_rpc_method_handler( + servicer.StartPhotoInterval, + request_deserializer=camera_dot_camera__pb2.StartPhotoIntervalRequest.FromString, + response_serializer=camera_dot_camera__pb2.StartPhotoIntervalResponse.SerializeToString, + ), + "StopPhotoInterval": grpc.unary_unary_rpc_method_handler( + servicer.StopPhotoInterval, + request_deserializer=camera_dot_camera__pb2.StopPhotoIntervalRequest.FromString, + response_serializer=camera_dot_camera__pb2.StopPhotoIntervalResponse.SerializeToString, + ), + "StartVideo": grpc.unary_unary_rpc_method_handler( + servicer.StartVideo, + request_deserializer=camera_dot_camera__pb2.StartVideoRequest.FromString, + response_serializer=camera_dot_camera__pb2.StartVideoResponse.SerializeToString, + ), + "StopVideo": grpc.unary_unary_rpc_method_handler( + servicer.StopVideo, + request_deserializer=camera_dot_camera__pb2.StopVideoRequest.FromString, + response_serializer=camera_dot_camera__pb2.StopVideoResponse.SerializeToString, + ), + "StartVideoStreaming": grpc.unary_unary_rpc_method_handler( + servicer.StartVideoStreaming, + request_deserializer=camera_dot_camera__pb2.StartVideoStreamingRequest.FromString, + response_serializer=camera_dot_camera__pb2.StartVideoStreamingResponse.SerializeToString, + ), + "StopVideoStreaming": grpc.unary_unary_rpc_method_handler( + servicer.StopVideoStreaming, + request_deserializer=camera_dot_camera__pb2.StopVideoStreamingRequest.FromString, + response_serializer=camera_dot_camera__pb2.StopVideoStreamingResponse.SerializeToString, + ), + "SetMode": grpc.unary_unary_rpc_method_handler( + servicer.SetMode, + request_deserializer=camera_dot_camera__pb2.SetModeRequest.FromString, + response_serializer=camera_dot_camera__pb2.SetModeResponse.SerializeToString, + ), + "ListPhotos": grpc.unary_unary_rpc_method_handler( + servicer.ListPhotos, + request_deserializer=camera_dot_camera__pb2.ListPhotosRequest.FromString, + response_serializer=camera_dot_camera__pb2.ListPhotosResponse.SerializeToString, + ), + "SubscribeCameraList": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCameraList, + request_deserializer=camera_dot_camera__pb2.SubscribeCameraListRequest.FromString, + response_serializer=camera_dot_camera__pb2.CameraListResponse.SerializeToString, + ), + "SubscribeMode": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeMode, + request_deserializer=camera_dot_camera__pb2.SubscribeModeRequest.FromString, + response_serializer=camera_dot_camera__pb2.ModeResponse.SerializeToString, + ), + "GetMode": grpc.unary_unary_rpc_method_handler( + servicer.GetMode, + request_deserializer=camera_dot_camera__pb2.GetModeRequest.FromString, + response_serializer=camera_dot_camera__pb2.GetModeResponse.SerializeToString, + ), + "SubscribeVideoStreamInfo": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeVideoStreamInfo, + request_deserializer=camera_dot_camera__pb2.SubscribeVideoStreamInfoRequest.FromString, + response_serializer=camera_dot_camera__pb2.VideoStreamInfoResponse.SerializeToString, + ), + "GetVideoStreamInfo": grpc.unary_unary_rpc_method_handler( + servicer.GetVideoStreamInfo, + request_deserializer=camera_dot_camera__pb2.GetVideoStreamInfoRequest.FromString, + response_serializer=camera_dot_camera__pb2.GetVideoStreamInfoResponse.SerializeToString, + ), + "SubscribeCaptureInfo": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCaptureInfo, + request_deserializer=camera_dot_camera__pb2.SubscribeCaptureInfoRequest.FromString, + response_serializer=camera_dot_camera__pb2.CaptureInfoResponse.SerializeToString, + ), + "SubscribeStorage": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStorage, + request_deserializer=camera_dot_camera__pb2.SubscribeStorageRequest.FromString, + response_serializer=camera_dot_camera__pb2.StorageResponse.SerializeToString, + ), + "GetStorage": grpc.unary_unary_rpc_method_handler( + servicer.GetStorage, + request_deserializer=camera_dot_camera__pb2.GetStorageRequest.FromString, + response_serializer=camera_dot_camera__pb2.GetStorageResponse.SerializeToString, + ), + "SubscribeCurrentSettings": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCurrentSettings, + request_deserializer=camera_dot_camera__pb2.SubscribeCurrentSettingsRequest.FromString, + response_serializer=camera_dot_camera__pb2.CurrentSettingsResponse.SerializeToString, + ), + "GetCurrentSettings": grpc.unary_unary_rpc_method_handler( + servicer.GetCurrentSettings, + request_deserializer=camera_dot_camera__pb2.GetCurrentSettingsRequest.FromString, + response_serializer=camera_dot_camera__pb2.GetCurrentSettingsResponse.SerializeToString, + ), + "SubscribePossibleSettingOptions": grpc.unary_stream_rpc_method_handler( + servicer.SubscribePossibleSettingOptions, + request_deserializer=camera_dot_camera__pb2.SubscribePossibleSettingOptionsRequest.FromString, + response_serializer=camera_dot_camera__pb2.PossibleSettingOptionsResponse.SerializeToString, + ), + "GetPossibleSettingOptions": grpc.unary_unary_rpc_method_handler( + servicer.GetPossibleSettingOptions, + request_deserializer=camera_dot_camera__pb2.GetPossibleSettingOptionsRequest.FromString, + response_serializer=camera_dot_camera__pb2.GetPossibleSettingOptionsResponse.SerializeToString, + ), + "SetSetting": grpc.unary_unary_rpc_method_handler( + servicer.SetSetting, + request_deserializer=camera_dot_camera__pb2.SetSettingRequest.FromString, + response_serializer=camera_dot_camera__pb2.SetSettingResponse.SerializeToString, + ), + "GetSetting": grpc.unary_unary_rpc_method_handler( + servicer.GetSetting, + request_deserializer=camera_dot_camera__pb2.GetSettingRequest.FromString, + response_serializer=camera_dot_camera__pb2.GetSettingResponse.SerializeToString, + ), + "FormatStorage": grpc.unary_unary_rpc_method_handler( + servicer.FormatStorage, + request_deserializer=camera_dot_camera__pb2.FormatStorageRequest.FromString, + response_serializer=camera_dot_camera__pb2.FormatStorageResponse.SerializeToString, + ), + "ResetSettings": grpc.unary_unary_rpc_method_handler( + servicer.ResetSettings, + request_deserializer=camera_dot_camera__pb2.ResetSettingsRequest.FromString, + response_serializer=camera_dot_camera__pb2.ResetSettingsResponse.SerializeToString, + ), + "ZoomInStart": grpc.unary_unary_rpc_method_handler( + servicer.ZoomInStart, + request_deserializer=camera_dot_camera__pb2.ZoomInStartRequest.FromString, + response_serializer=camera_dot_camera__pb2.ZoomInStartResponse.SerializeToString, + ), + "ZoomOutStart": grpc.unary_unary_rpc_method_handler( + servicer.ZoomOutStart, + request_deserializer=camera_dot_camera__pb2.ZoomOutStartRequest.FromString, + response_serializer=camera_dot_camera__pb2.ZoomOutStartResponse.SerializeToString, + ), + "ZoomStop": grpc.unary_unary_rpc_method_handler( + servicer.ZoomStop, + request_deserializer=camera_dot_camera__pb2.ZoomStopRequest.FromString, + response_serializer=camera_dot_camera__pb2.ZoomStopResponse.SerializeToString, + ), + "ZoomRange": grpc.unary_unary_rpc_method_handler( + servicer.ZoomRange, + request_deserializer=camera_dot_camera__pb2.ZoomRangeRequest.FromString, + response_serializer=camera_dot_camera__pb2.ZoomRangeResponse.SerializeToString, + ), + "TrackPoint": grpc.unary_unary_rpc_method_handler( + servicer.TrackPoint, + request_deserializer=camera_dot_camera__pb2.TrackPointRequest.FromString, + response_serializer=camera_dot_camera__pb2.TrackPointResponse.SerializeToString, + ), + "TrackRectangle": grpc.unary_unary_rpc_method_handler( + servicer.TrackRectangle, + request_deserializer=camera_dot_camera__pb2.TrackRectangleRequest.FromString, + response_serializer=camera_dot_camera__pb2.TrackRectangleResponse.SerializeToString, + ), + "TrackStop": grpc.unary_unary_rpc_method_handler( + servicer.TrackStop, + request_deserializer=camera_dot_camera__pb2.TrackStopRequest.FromString, + response_serializer=camera_dot_camera__pb2.TrackStopResponse.SerializeToString, + ), + "FocusInStart": grpc.unary_unary_rpc_method_handler( + servicer.FocusInStart, + request_deserializer=camera_dot_camera__pb2.FocusInStartRequest.FromString, + response_serializer=camera_dot_camera__pb2.FocusInStartResponse.SerializeToString, + ), + "FocusOutStart": grpc.unary_unary_rpc_method_handler( + servicer.FocusOutStart, + request_deserializer=camera_dot_camera__pb2.FocusOutStartRequest.FromString, + response_serializer=camera_dot_camera__pb2.FocusOutStartResponse.SerializeToString, + ), + "FocusStop": grpc.unary_unary_rpc_method_handler( + servicer.FocusStop, + request_deserializer=camera_dot_camera__pb2.FocusStopRequest.FromString, + response_serializer=camera_dot_camera__pb2.FocusStopResponse.SerializeToString, + ), + "FocusRange": grpc.unary_unary_rpc_method_handler( + servicer.FocusRange, + request_deserializer=camera_dot_camera__pb2.FocusRangeRequest.FromString, + response_serializer=camera_dot_camera__pb2.FocusRangeResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.camera.CameraService', rpc_method_handlers) + "mavsdk.rpc.camera.CameraService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.camera.CameraService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.camera.CameraService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class CameraService(object): """ Can be used to manage cameras that implement the MAVLink @@ -741,20 +784,22 @@ class CameraService(object): """ @staticmethod - def TakePhoto(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TakePhoto( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/TakePhoto', + "/mavsdk.rpc.camera.CameraService/TakePhoto", camera_dot_camera__pb2.TakePhotoRequest.SerializeToString, camera_dot_camera__pb2.TakePhotoResponse.FromString, options, @@ -765,23 +810,26 @@ def TakePhoto(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StartPhotoInterval(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartPhotoInterval( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/StartPhotoInterval', + "/mavsdk.rpc.camera.CameraService/StartPhotoInterval", camera_dot_camera__pb2.StartPhotoIntervalRequest.SerializeToString, camera_dot_camera__pb2.StartPhotoIntervalResponse.FromString, options, @@ -792,23 +840,26 @@ def StartPhotoInterval(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StopPhotoInterval(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StopPhotoInterval( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/StopPhotoInterval', + "/mavsdk.rpc.camera.CameraService/StopPhotoInterval", camera_dot_camera__pb2.StopPhotoIntervalRequest.SerializeToString, camera_dot_camera__pb2.StopPhotoIntervalResponse.FromString, options, @@ -819,23 +870,26 @@ def StopPhotoInterval(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StartVideo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartVideo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/StartVideo', + "/mavsdk.rpc.camera.CameraService/StartVideo", camera_dot_camera__pb2.StartVideoRequest.SerializeToString, camera_dot_camera__pb2.StartVideoResponse.FromString, options, @@ -846,23 +900,26 @@ def StartVideo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StopVideo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StopVideo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/StopVideo', + "/mavsdk.rpc.camera.CameraService/StopVideo", camera_dot_camera__pb2.StopVideoRequest.SerializeToString, camera_dot_camera__pb2.StopVideoResponse.FromString, options, @@ -873,23 +930,26 @@ def StopVideo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StartVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/StartVideoStreaming', + "/mavsdk.rpc.camera.CameraService/StartVideoStreaming", camera_dot_camera__pb2.StartVideoStreamingRequest.SerializeToString, camera_dot_camera__pb2.StartVideoStreamingResponse.FromString, options, @@ -900,23 +960,26 @@ def StartVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StopVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StopVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/StopVideoStreaming', + "/mavsdk.rpc.camera.CameraService/StopVideoStreaming", camera_dot_camera__pb2.StopVideoStreamingRequest.SerializeToString, camera_dot_camera__pb2.StopVideoStreamingResponse.FromString, options, @@ -927,23 +990,26 @@ def StopVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/SetMode', + "/mavsdk.rpc.camera.CameraService/SetMode", camera_dot_camera__pb2.SetModeRequest.SerializeToString, camera_dot_camera__pb2.SetModeResponse.FromString, options, @@ -954,23 +1020,26 @@ def SetMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ListPhotos(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ListPhotos( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/ListPhotos', + "/mavsdk.rpc.camera.CameraService/ListPhotos", camera_dot_camera__pb2.ListPhotosRequest.SerializeToString, camera_dot_camera__pb2.ListPhotosResponse.FromString, options, @@ -981,23 +1050,26 @@ def ListPhotos(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCameraList(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCameraList( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribeCameraList', + "/mavsdk.rpc.camera.CameraService/SubscribeCameraList", camera_dot_camera__pb2.SubscribeCameraListRequest.SerializeToString, camera_dot_camera__pb2.CameraListResponse.FromString, options, @@ -1008,23 +1080,26 @@ def SubscribeCameraList(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribeMode', + "/mavsdk.rpc.camera.CameraService/SubscribeMode", camera_dot_camera__pb2.SubscribeModeRequest.SerializeToString, camera_dot_camera__pb2.ModeResponse.FromString, options, @@ -1035,23 +1110,26 @@ def SubscribeMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/GetMode', + "/mavsdk.rpc.camera.CameraService/GetMode", camera_dot_camera__pb2.GetModeRequest.SerializeToString, camera_dot_camera__pb2.GetModeResponse.FromString, options, @@ -1062,23 +1140,26 @@ def GetMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeVideoStreamInfo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeVideoStreamInfo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribeVideoStreamInfo', + "/mavsdk.rpc.camera.CameraService/SubscribeVideoStreamInfo", camera_dot_camera__pb2.SubscribeVideoStreamInfoRequest.SerializeToString, camera_dot_camera__pb2.VideoStreamInfoResponse.FromString, options, @@ -1089,23 +1170,26 @@ def SubscribeVideoStreamInfo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetVideoStreamInfo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetVideoStreamInfo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/GetVideoStreamInfo', + "/mavsdk.rpc.camera.CameraService/GetVideoStreamInfo", camera_dot_camera__pb2.GetVideoStreamInfoRequest.SerializeToString, camera_dot_camera__pb2.GetVideoStreamInfoResponse.FromString, options, @@ -1116,23 +1200,26 @@ def GetVideoStreamInfo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCaptureInfo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCaptureInfo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribeCaptureInfo', + "/mavsdk.rpc.camera.CameraService/SubscribeCaptureInfo", camera_dot_camera__pb2.SubscribeCaptureInfoRequest.SerializeToString, camera_dot_camera__pb2.CaptureInfoResponse.FromString, options, @@ -1143,23 +1230,26 @@ def SubscribeCaptureInfo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStorage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStorage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribeStorage', + "/mavsdk.rpc.camera.CameraService/SubscribeStorage", camera_dot_camera__pb2.SubscribeStorageRequest.SerializeToString, camera_dot_camera__pb2.StorageResponse.FromString, options, @@ -1170,23 +1260,26 @@ def SubscribeStorage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetStorage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetStorage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/GetStorage', + "/mavsdk.rpc.camera.CameraService/GetStorage", camera_dot_camera__pb2.GetStorageRequest.SerializeToString, camera_dot_camera__pb2.GetStorageResponse.FromString, options, @@ -1197,23 +1290,26 @@ def GetStorage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCurrentSettings(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCurrentSettings( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribeCurrentSettings', + "/mavsdk.rpc.camera.CameraService/SubscribeCurrentSettings", camera_dot_camera__pb2.SubscribeCurrentSettingsRequest.SerializeToString, camera_dot_camera__pb2.CurrentSettingsResponse.FromString, options, @@ -1224,23 +1320,26 @@ def SubscribeCurrentSettings(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetCurrentSettings(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetCurrentSettings( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/GetCurrentSettings', + "/mavsdk.rpc.camera.CameraService/GetCurrentSettings", camera_dot_camera__pb2.GetCurrentSettingsRequest.SerializeToString, camera_dot_camera__pb2.GetCurrentSettingsResponse.FromString, options, @@ -1251,23 +1350,26 @@ def GetCurrentSettings(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribePossibleSettingOptions(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribePossibleSettingOptions( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera.CameraService/SubscribePossibleSettingOptions', + "/mavsdk.rpc.camera.CameraService/SubscribePossibleSettingOptions", camera_dot_camera__pb2.SubscribePossibleSettingOptionsRequest.SerializeToString, camera_dot_camera__pb2.PossibleSettingOptionsResponse.FromString, options, @@ -1278,23 +1380,26 @@ def SubscribePossibleSettingOptions(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetPossibleSettingOptions(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetPossibleSettingOptions( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/GetPossibleSettingOptions', + "/mavsdk.rpc.camera.CameraService/GetPossibleSettingOptions", camera_dot_camera__pb2.GetPossibleSettingOptionsRequest.SerializeToString, camera_dot_camera__pb2.GetPossibleSettingOptionsResponse.FromString, options, @@ -1305,23 +1410,26 @@ def GetPossibleSettingOptions(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetSetting(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetSetting( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/SetSetting', + "/mavsdk.rpc.camera.CameraService/SetSetting", camera_dot_camera__pb2.SetSettingRequest.SerializeToString, camera_dot_camera__pb2.SetSettingResponse.FromString, options, @@ -1332,23 +1440,26 @@ def SetSetting(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetSetting(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetSetting( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/GetSetting', + "/mavsdk.rpc.camera.CameraService/GetSetting", camera_dot_camera__pb2.GetSettingRequest.SerializeToString, camera_dot_camera__pb2.GetSettingResponse.FromString, options, @@ -1359,23 +1470,26 @@ def GetSetting(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def FormatStorage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def FormatStorage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/FormatStorage', + "/mavsdk.rpc.camera.CameraService/FormatStorage", camera_dot_camera__pb2.FormatStorageRequest.SerializeToString, camera_dot_camera__pb2.FormatStorageResponse.FromString, options, @@ -1386,23 +1500,26 @@ def FormatStorage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ResetSettings(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ResetSettings( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/ResetSettings', + "/mavsdk.rpc.camera.CameraService/ResetSettings", camera_dot_camera__pb2.ResetSettingsRequest.SerializeToString, camera_dot_camera__pb2.ResetSettingsResponse.FromString, options, @@ -1413,23 +1530,26 @@ def ResetSettings(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ZoomInStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ZoomInStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/ZoomInStart', + "/mavsdk.rpc.camera.CameraService/ZoomInStart", camera_dot_camera__pb2.ZoomInStartRequest.SerializeToString, camera_dot_camera__pb2.ZoomInStartResponse.FromString, options, @@ -1440,23 +1560,26 @@ def ZoomInStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ZoomOutStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ZoomOutStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/ZoomOutStart', + "/mavsdk.rpc.camera.CameraService/ZoomOutStart", camera_dot_camera__pb2.ZoomOutStartRequest.SerializeToString, camera_dot_camera__pb2.ZoomOutStartResponse.FromString, options, @@ -1467,23 +1590,26 @@ def ZoomOutStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ZoomStop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ZoomStop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/ZoomStop', + "/mavsdk.rpc.camera.CameraService/ZoomStop", camera_dot_camera__pb2.ZoomStopRequest.SerializeToString, camera_dot_camera__pb2.ZoomStopResponse.FromString, options, @@ -1494,23 +1620,26 @@ def ZoomStop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ZoomRange(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ZoomRange( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/ZoomRange', + "/mavsdk.rpc.camera.CameraService/ZoomRange", camera_dot_camera__pb2.ZoomRangeRequest.SerializeToString, camera_dot_camera__pb2.ZoomRangeResponse.FromString, options, @@ -1521,23 +1650,26 @@ def ZoomRange(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def TrackPoint(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TrackPoint( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/TrackPoint', + "/mavsdk.rpc.camera.CameraService/TrackPoint", camera_dot_camera__pb2.TrackPointRequest.SerializeToString, camera_dot_camera__pb2.TrackPointResponse.FromString, options, @@ -1548,23 +1680,26 @@ def TrackPoint(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def TrackRectangle(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TrackRectangle( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/TrackRectangle', + "/mavsdk.rpc.camera.CameraService/TrackRectangle", camera_dot_camera__pb2.TrackRectangleRequest.SerializeToString, camera_dot_camera__pb2.TrackRectangleResponse.FromString, options, @@ -1575,23 +1710,26 @@ def TrackRectangle(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def TrackStop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TrackStop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/TrackStop', + "/mavsdk.rpc.camera.CameraService/TrackStop", camera_dot_camera__pb2.TrackStopRequest.SerializeToString, camera_dot_camera__pb2.TrackStopResponse.FromString, options, @@ -1602,23 +1740,26 @@ def TrackStop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def FocusInStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def FocusInStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/FocusInStart', + "/mavsdk.rpc.camera.CameraService/FocusInStart", camera_dot_camera__pb2.FocusInStartRequest.SerializeToString, camera_dot_camera__pb2.FocusInStartResponse.FromString, options, @@ -1629,23 +1770,26 @@ def FocusInStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def FocusOutStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def FocusOutStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/FocusOutStart', + "/mavsdk.rpc.camera.CameraService/FocusOutStart", camera_dot_camera__pb2.FocusOutStartRequest.SerializeToString, camera_dot_camera__pb2.FocusOutStartResponse.FromString, options, @@ -1656,23 +1800,26 @@ def FocusOutStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def FocusStop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def FocusStop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/FocusStop', + "/mavsdk.rpc.camera.CameraService/FocusStop", camera_dot_camera__pb2.FocusStopRequest.SerializeToString, camera_dot_camera__pb2.FocusStopResponse.FromString, options, @@ -1683,23 +1830,26 @@ def FocusStop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def FocusRange(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def FocusRange( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera.CameraService/FocusRange', + "/mavsdk.rpc.camera.CameraService/FocusRange", camera_dot_camera__pb2.FocusRangeRequest.SerializeToString, camera_dot_camera__pb2.FocusRangeResponse.FromString, options, @@ -1710,4 +1860,5 @@ def FocusRange(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/camera_server.py b/mavsdk/camera_server.py index 2f26d0ab..10434163 100644 --- a/mavsdk/camera_server.py +++ b/mavsdk/camera_server.py @@ -8,25 +8,24 @@ class CameraFeedback(Enum): """ - Possible feedback results for camera respond command. + Possible feedback results for camera respond command. - Values - ------ - UNKNOWN - Unknown + Values + ------ + UNKNOWN + Unknown - OK - Ok + OK + Ok - BUSY - Busy + BUSY + Busy - FAILED - Failed + FAILED + Failed - """ + """ - UNKNOWN = 0 OK = 1 BUSY = 2 @@ -44,7 +43,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_server_pb2.CAMERA_FEEDBACK_UNKNOWN: return CameraFeedback.UNKNOWN if rpc_enum_value == camera_server_pb2.CAMERA_FEEDBACK_OK: @@ -60,22 +59,21 @@ def __str__(self): class Mode(Enum): """ - Camera mode type. + Camera mode type. - Values - ------ - UNKNOWN - Unknown mode + Values + ------ + UNKNOWN + Unknown mode - PHOTO - Photo mode + PHOTO + Photo mode - VIDEO - Video mode + VIDEO + Video mode - """ + """ - UNKNOWN = 0 PHOTO = 1 VIDEO = 2 @@ -90,7 +88,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_server_pb2.MODE_UNKNOWN: return Mode.UNKNOWN if rpc_enum_value == camera_server_pb2.MODE_PHOTO: @@ -104,69 +102,68 @@ def __str__(self): class Information: """ - Type to represent a camera information. - - Parameters - ---------- - vendor_name : std::string - Name of the camera vendor + Type to represent a camera information. - model_name : std::string - Name of the camera model + Parameters + ---------- + vendor_name : std::string + Name of the camera vendor - firmware_version : std::string - Camera firmware version in major[.minor[.patch[.dev]]] format + model_name : std::string + Name of the camera model - focal_length_mm : float - Focal length + firmware_version : std::string + Camera firmware version in major[.minor[.patch[.dev]]] format - horizontal_sensor_size_mm : float - Horizontal sensor size + focal_length_mm : float + Focal length - vertical_sensor_size_mm : float - Vertical sensor size + horizontal_sensor_size_mm : float + Horizontal sensor size - horizontal_resolution_px : uint32_t - Horizontal image resolution in pixels + vertical_sensor_size_mm : float + Vertical sensor size - vertical_resolution_px : uint32_t - Vertical image resolution in pixels + horizontal_resolution_px : uint32_t + Horizontal image resolution in pixels - lens_id : uint32_t - Lens ID + vertical_resolution_px : uint32_t + Vertical image resolution in pixels - definition_file_version : uint32_t - Camera definition file version (iteration) + lens_id : uint32_t + Lens ID - definition_file_uri : std::string - Camera definition URI (http or mavlink ftp) + definition_file_version : uint32_t + Camera definition file version (iteration) - image_in_video_mode_supported : bool - Camera supports taking images while in video mode + definition_file_uri : std::string + Camera definition URI (http or mavlink ftp) - video_in_image_mode_supported : bool - Camera supports recording video while in image mode + image_in_video_mode_supported : bool + Camera supports taking images while in video mode - """ + video_in_image_mode_supported : bool + Camera supports recording video while in image mode - + """ def __init__( - self, - vendor_name, - model_name, - firmware_version, - focal_length_mm, - horizontal_sensor_size_mm, - vertical_sensor_size_mm, - horizontal_resolution_px, - vertical_resolution_px, - lens_id, - definition_file_version, - definition_file_uri, - image_in_video_mode_supported, - video_in_image_mode_supported): - """ Initializes the Information object """ + self, + vendor_name, + model_name, + firmware_version, + focal_length_mm, + horizontal_sensor_size_mm, + vertical_sensor_size_mm, + horizontal_resolution_px, + vertical_resolution_px, + lens_id, + definition_file_version, + definition_file_uri, + image_in_video_mode_supported, + video_in_image_mode_supported, + ): + """Initializes the Information object""" self.vendor_name = vendor_name self.model_name = model_name self.firmware_version = firmware_version @@ -182,31 +179,44 @@ def __init__( self.video_in_image_mode_supported = video_in_image_mode_supported def __eq__(self, to_compare): - """ Checks if two Information are the same """ + """Checks if two Information are the same""" try: # Try to compare - this likely fails when it is compared to a non # Information object - return \ - (self.vendor_name == to_compare.vendor_name) and \ - (self.model_name == to_compare.model_name) and \ - (self.firmware_version == to_compare.firmware_version) and \ - (self.focal_length_mm == to_compare.focal_length_mm) and \ - (self.horizontal_sensor_size_mm == to_compare.horizontal_sensor_size_mm) and \ - (self.vertical_sensor_size_mm == to_compare.vertical_sensor_size_mm) and \ - (self.horizontal_resolution_px == to_compare.horizontal_resolution_px) and \ - (self.vertical_resolution_px == to_compare.vertical_resolution_px) and \ - (self.lens_id == to_compare.lens_id) and \ - (self.definition_file_version == to_compare.definition_file_version) and \ - (self.definition_file_uri == to_compare.definition_file_uri) and \ - (self.image_in_video_mode_supported == to_compare.image_in_video_mode_supported) and \ - (self.video_in_image_mode_supported == to_compare.video_in_image_mode_supported) + return ( + (self.vendor_name == to_compare.vendor_name) + and (self.model_name == to_compare.model_name) + and (self.firmware_version == to_compare.firmware_version) + and (self.focal_length_mm == to_compare.focal_length_mm) + and ( + self.horizontal_sensor_size_mm + == to_compare.horizontal_sensor_size_mm + ) + and (self.vertical_sensor_size_mm == to_compare.vertical_sensor_size_mm) + and ( + self.horizontal_resolution_px == to_compare.horizontal_resolution_px + ) + and (self.vertical_resolution_px == to_compare.vertical_resolution_px) + and (self.lens_id == to_compare.lens_id) + and (self.definition_file_version == to_compare.definition_file_version) + and (self.definition_file_uri == to_compare.definition_file_uri) + and ( + self.image_in_video_mode_supported + == to_compare.image_in_video_mode_supported + ) + and ( + self.video_in_image_mode_supported + == to_compare.video_in_image_mode_supported + ) + ) except AttributeError: return False def __str__(self): - """ Information in string representation """ - struct_repr = ", ".join([ + """Information in string representation""" + struct_repr = ", ".join( + [ "vendor_name: " + str(self.vendor_name), "model_name: " + str(self.model_name), "firmware_version: " + str(self.firmware_version), @@ -218,470 +228,315 @@ def __str__(self): "lens_id: " + str(self.lens_id), "definition_file_version: " + str(self.definition_file_version), "definition_file_uri: " + str(self.definition_file_uri), - "image_in_video_mode_supported: " + str(self.image_in_video_mode_supported), - "video_in_image_mode_supported: " + str(self.video_in_image_mode_supported) - ]) + "image_in_video_mode_supported: " + + str(self.image_in_video_mode_supported), + "video_in_image_mode_supported: " + + str(self.video_in_image_mode_supported), + ] + ) return f"Information: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcInformation): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Information( - - rpcInformation.vendor_name, - - - rpcInformation.model_name, - - - rpcInformation.firmware_version, - - - rpcInformation.focal_length_mm, - - - rpcInformation.horizontal_sensor_size_mm, - - - rpcInformation.vertical_sensor_size_mm, - - - rpcInformation.horizontal_resolution_px, - - - rpcInformation.vertical_resolution_px, - - - rpcInformation.lens_id, - - - rpcInformation.definition_file_version, - - - rpcInformation.definition_file_uri, - - - rpcInformation.image_in_video_mode_supported, - - - rpcInformation.video_in_image_mode_supported - ) + rpcInformation.vendor_name, + rpcInformation.model_name, + rpcInformation.firmware_version, + rpcInformation.focal_length_mm, + rpcInformation.horizontal_sensor_size_mm, + rpcInformation.vertical_sensor_size_mm, + rpcInformation.horizontal_resolution_px, + rpcInformation.vertical_resolution_px, + rpcInformation.lens_id, + rpcInformation.definition_file_version, + rpcInformation.definition_file_uri, + rpcInformation.image_in_video_mode_supported, + rpcInformation.video_in_image_mode_supported, + ) def translate_to_rpc(self, rpcInformation): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcInformation.vendor_name = self.vendor_name - - - - - + rpcInformation.model_name = self.model_name - - - - - + rpcInformation.firmware_version = self.firmware_version - - - - - + rpcInformation.focal_length_mm = self.focal_length_mm - - - - - + rpcInformation.horizontal_sensor_size_mm = self.horizontal_sensor_size_mm - - - - - + rpcInformation.vertical_sensor_size_mm = self.vertical_sensor_size_mm - - - - - + rpcInformation.horizontal_resolution_px = self.horizontal_resolution_px - - - - - + rpcInformation.vertical_resolution_px = self.vertical_resolution_px - - - - - + rpcInformation.lens_id = self.lens_id - - - - - + rpcInformation.definition_file_version = self.definition_file_version - - - - - + rpcInformation.definition_file_uri = self.definition_file_uri - - - - - - rpcInformation.image_in_video_mode_supported = self.image_in_video_mode_supported - - - - - - rpcInformation.video_in_image_mode_supported = self.video_in_image_mode_supported - - - + + rpcInformation.image_in_video_mode_supported = ( + self.image_in_video_mode_supported + ) + + rpcInformation.video_in_image_mode_supported = ( + self.video_in_image_mode_supported + ) class VideoStreaming: """ - Type to represent video streaming settings - - Parameters - ---------- - has_rtsp_server : bool - True if the capture was successful + Type to represent video streaming settings - rtsp_uri : std::string - RTSP URI (e.g. rtsp://192.168.1.42:8554/live) + Parameters + ---------- + has_rtsp_server : bool + True if the capture was successful - """ + rtsp_uri : std::string + RTSP URI (e.g. rtsp://192.168.1.42:8554/live) - + """ - def __init__( - self, - has_rtsp_server, - rtsp_uri): - """ Initializes the VideoStreaming object """ + def __init__(self, has_rtsp_server, rtsp_uri): + """Initializes the VideoStreaming object""" self.has_rtsp_server = has_rtsp_server self.rtsp_uri = rtsp_uri def __eq__(self, to_compare): - """ Checks if two VideoStreaming are the same """ + """Checks if two VideoStreaming are the same""" try: # Try to compare - this likely fails when it is compared to a non # VideoStreaming object - return \ - (self.has_rtsp_server == to_compare.has_rtsp_server) and \ - (self.rtsp_uri == to_compare.rtsp_uri) + return (self.has_rtsp_server == to_compare.has_rtsp_server) and ( + self.rtsp_uri == to_compare.rtsp_uri + ) except AttributeError: return False def __str__(self): - """ VideoStreaming in string representation """ - struct_repr = ", ".join([ + """VideoStreaming in string representation""" + struct_repr = ", ".join( + [ "has_rtsp_server: " + str(self.has_rtsp_server), - "rtsp_uri: " + str(self.rtsp_uri) - ]) + "rtsp_uri: " + str(self.rtsp_uri), + ] + ) return f"VideoStreaming: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVideoStreaming): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VideoStreaming( - - rpcVideoStreaming.has_rtsp_server, - - - rpcVideoStreaming.rtsp_uri - ) + rpcVideoStreaming.has_rtsp_server, rpcVideoStreaming.rtsp_uri + ) def translate_to_rpc(self, rpcVideoStreaming): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVideoStreaming.has_rtsp_server = self.has_rtsp_server - - - - - + rpcVideoStreaming.rtsp_uri = self.rtsp_uri - - - class Position: """ - Position type in global coordinates. - - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Position type in global coordinates. - longitude_deg : double - Longitude in degrees (range: -180 to +180) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + longitude_deg : double + Longitude in degrees (range: -180 to +180) - relative_altitude_m : float - Altitude relative to takeoff altitude in metres + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - """ + relative_altitude_m : float + Altitude relative to takeoff altitude in metres - + """ def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m, - relative_altitude_m): - """ Initializes the Position object """ + self, latitude_deg, longitude_deg, absolute_altitude_m, relative_altitude_m + ): + """Initializes the Position object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m def __eq__(self, to_compare): - """ Checks if two Position are the same """ + """Checks if two Position are the same""" try: # Try to compare - this likely fails when it is compared to a non # Position object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.relative_altitude_m == to_compare.relative_altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.relative_altitude_m == to_compare.relative_altitude_m) + ) except AttributeError: return False def __str__(self): - """ Position in string representation """ - struct_repr = ", ".join([ + """Position in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), "absolute_altitude_m: " + str(self.absolute_altitude_m), - "relative_altitude_m: " + str(self.relative_altitude_m) - ]) + "relative_altitude_m: " + str(self.relative_altitude_m), + ] + ) return f"Position: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPosition): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Position( - - rpcPosition.latitude_deg, - - - rpcPosition.longitude_deg, - - - rpcPosition.absolute_altitude_m, - - - rpcPosition.relative_altitude_m - ) + rpcPosition.latitude_deg, + rpcPosition.longitude_deg, + rpcPosition.absolute_altitude_m, + rpcPosition.relative_altitude_m, + ) def translate_to_rpc(self, rpcPosition): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPosition.latitude_deg = self.latitude_deg - - - - - + rpcPosition.longitude_deg = self.longitude_deg - - - - - + rpcPosition.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcPosition.relative_altitude_m = self.relative_altitude_m - - - class Quaternion: """ - Quaternion type. - - All rotations and axis systems follow the right-hand rule. - The Hamilton quaternion product definition is used. - A zero-rotation quaternion is represented by (1,0,0,0). - The quaternion could also be written as w + xi + yj + zk. + Quaternion type. - For more info see: https://en.wikipedia.org/wiki/Quaternion + All rotations and axis systems follow the right-hand rule. + The Hamilton quaternion product definition is used. + A zero-rotation quaternion is represented by (1,0,0,0). + The quaternion could also be written as w + xi + yj + zk. - Parameters - ---------- - w : float - Quaternion entry 0, also denoted as a + For more info see: https://en.wikipedia.org/wiki/Quaternion - x : float - Quaternion entry 1, also denoted as b + Parameters + ---------- + w : float + Quaternion entry 0, also denoted as a - y : float - Quaternion entry 2, also denoted as c + x : float + Quaternion entry 1, also denoted as b - z : float - Quaternion entry 3, also denoted as d + y : float + Quaternion entry 2, also denoted as c - """ + z : float + Quaternion entry 3, also denoted as d - + """ - def __init__( - self, - w, - x, - y, - z): - """ Initializes the Quaternion object """ + def __init__(self, w, x, y, z): + """Initializes the Quaternion object""" self.w = w self.x = x self.y = y self.z = z def __eq__(self, to_compare): - """ Checks if two Quaternion are the same """ + """Checks if two Quaternion are the same""" try: # Try to compare - this likely fails when it is compared to a non # Quaternion object - return \ - (self.w == to_compare.w) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) + return ( + (self.w == to_compare.w) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + ) except AttributeError: return False def __str__(self): - """ Quaternion in string representation """ - struct_repr = ", ".join([ + """Quaternion in string representation""" + struct_repr = ", ".join( + [ "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), - "z: " + str(self.z) - ]) + "z: " + str(self.z), + ] + ) return f"Quaternion: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcQuaternion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Quaternion( - - rpcQuaternion.w, - - - rpcQuaternion.x, - - - rpcQuaternion.y, - - - rpcQuaternion.z - ) + rpcQuaternion.w, rpcQuaternion.x, rpcQuaternion.y, rpcQuaternion.z + ) def translate_to_rpc(self, rpcQuaternion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcQuaternion.w = self.w - - - - - + rpcQuaternion.x = self.x - - - - - + rpcQuaternion.y = self.y - - - - - + rpcQuaternion.z = self.z - - - class CaptureInfo: """ - Information about a picture just captured. - - Parameters - ---------- - position : Position - Location where the picture was taken + Information about a picture just captured. - attitude_quaternion : Quaternion - Attitude of the camera when the picture was taken (quaternion) + Parameters + ---------- + position : Position + Location where the picture was taken - time_utc_us : uint64_t - Timestamp in UTC (since UNIX epoch) in microseconds + attitude_quaternion : Quaternion + Attitude of the camera when the picture was taken (quaternion) - is_success : bool - True if the capture was successful + time_utc_us : uint64_t + Timestamp in UTC (since UNIX epoch) in microseconds - index : int32_t - Index from TakePhotoResponse + is_success : bool + True if the capture was successful - file_url : std::string - Download URL of this image + index : int32_t + Index from TakePhotoResponse - """ + file_url : std::string + Download URL of this image - + """ def __init__( - self, - position, - attitude_quaternion, - time_utc_us, - is_success, - index, - file_url): - """ Initializes the CaptureInfo object """ + self, position, attitude_quaternion, time_utc_us, is_success, index, file_url + ): + """Initializes the CaptureInfo object""" self.position = position self.attitude_quaternion = attitude_quaternion self.time_utc_us = time_utc_us @@ -690,151 +545,114 @@ def __init__( self.file_url = file_url def __eq__(self, to_compare): - """ Checks if two CaptureInfo are the same """ + """Checks if two CaptureInfo are the same""" try: # Try to compare - this likely fails when it is compared to a non # CaptureInfo object - return \ - (self.position == to_compare.position) and \ - (self.attitude_quaternion == to_compare.attitude_quaternion) and \ - (self.time_utc_us == to_compare.time_utc_us) and \ - (self.is_success == to_compare.is_success) and \ - (self.index == to_compare.index) and \ - (self.file_url == to_compare.file_url) + return ( + (self.position == to_compare.position) + and (self.attitude_quaternion == to_compare.attitude_quaternion) + and (self.time_utc_us == to_compare.time_utc_us) + and (self.is_success == to_compare.is_success) + and (self.index == to_compare.index) + and (self.file_url == to_compare.file_url) + ) except AttributeError: return False def __str__(self): - """ CaptureInfo in string representation """ - struct_repr = ", ".join([ + """CaptureInfo in string representation""" + struct_repr = ", ".join( + [ "position: " + str(self.position), "attitude_quaternion: " + str(self.attitude_quaternion), "time_utc_us: " + str(self.time_utc_us), "is_success: " + str(self.is_success), "index: " + str(self.index), - "file_url: " + str(self.file_url) - ]) + "file_url: " + str(self.file_url), + ] + ) return f"CaptureInfo: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCaptureInfo): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CaptureInfo( - - Position.translate_from_rpc(rpcCaptureInfo.position), - - - Quaternion.translate_from_rpc(rpcCaptureInfo.attitude_quaternion), - - - rpcCaptureInfo.time_utc_us, - - - rpcCaptureInfo.is_success, - - - rpcCaptureInfo.index, - - - rpcCaptureInfo.file_url - ) + Position.translate_from_rpc(rpcCaptureInfo.position), + Quaternion.translate_from_rpc(rpcCaptureInfo.attitude_quaternion), + rpcCaptureInfo.time_utc_us, + rpcCaptureInfo.is_success, + rpcCaptureInfo.index, + rpcCaptureInfo.file_url, + ) def translate_to_rpc(self, rpcCaptureInfo): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - self.position.translate_to_rpc(rpcCaptureInfo.position) - - - - - + self.attitude_quaternion.translate_to_rpc(rpcCaptureInfo.attitude_quaternion) - - - - - + rpcCaptureInfo.time_utc_us = self.time_utc_us - - - - - + rpcCaptureInfo.is_success = self.is_success - - - - - + rpcCaptureInfo.index = self.index - - - - - + rpcCaptureInfo.file_url = self.file_url - - - class CameraServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Command executed successfully + SUCCESS + Command executed successfully - IN_PROGRESS - Command in progress + IN_PROGRESS + Command in progress - BUSY - Camera is busy and rejected command + BUSY + Camera is busy and rejected command - DENIED - Camera denied the command + DENIED + Camera denied the command - ERROR - An error has occurred while executing the command + ERROR + An error has occurred while executing the command - TIMEOUT - Command timed out + TIMEOUT + Command timed out - WRONG_ARGUMENT - Command has wrong argument(s) + WRONG_ARGUMENT + Command has wrong argument(s) - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 IN_PROGRESS = 2 @@ -867,12 +685,15 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_UNKNOWN: return CameraServerResult.Result.UNKNOWN if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_SUCCESS: return CameraServerResult.Result.SUCCESS - if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_IN_PROGRESS: + if ( + rpc_enum_value + == camera_server_pb2.CameraServerResult.RESULT_IN_PROGRESS + ): return CameraServerResult.Result.IN_PROGRESS if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_BUSY: return CameraServerResult.Result.BUSY @@ -882,128 +703,110 @@ def translate_from_rpc(rpc_enum_value): return CameraServerResult.Result.ERROR if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_TIMEOUT: return CameraServerResult.Result.TIMEOUT - if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_WRONG_ARGUMENT: + if ( + rpc_enum_value + == camera_server_pb2.CameraServerResult.RESULT_WRONG_ARGUMENT + ): return CameraServerResult.Result.WRONG_ARGUMENT if rpc_enum_value == camera_server_pb2.CameraServerResult.RESULT_NO_SYSTEM: return CameraServerResult.Result.NO_SYSTEM def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the CameraServerResult object """ + def __init__(self, result, result_str): + """Initializes the CameraServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two CameraServerResult are the same """ + """Checks if two CameraServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # CameraServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ CameraServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """CameraServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"CameraServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCameraServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CameraServerResult( - - CameraServerResult.Result.translate_from_rpc(rpcCameraServerResult.result), - - - rpcCameraServerResult.result_str - ) + CameraServerResult.Result.translate_from_rpc(rpcCameraServerResult.result), + rpcCameraServerResult.result_str, + ) def translate_to_rpc(self, rpcCameraServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCameraServerResult.result = self.result.translate_to_rpc() - - - - - + rpcCameraServerResult.result_str = self.result_str - - - class StorageInformation: """ - Information about the camera storage. + Information about the camera storage. - Parameters - ---------- - used_storage_mib : float - Used storage (in MiB) + Parameters + ---------- + used_storage_mib : float + Used storage (in MiB) - available_storage_mib : float - Available storage (in MiB) + available_storage_mib : float + Available storage (in MiB) - total_storage_mib : float - Total storage (in MiB) + total_storage_mib : float + Total storage (in MiB) - storage_status : StorageStatus - Storage status + storage_status : StorageStatus + Storage status - storage_id : uint32_t - Storage ID starting at 1 + storage_id : uint32_t + Storage ID starting at 1 - storage_type : StorageType - Storage type + storage_type : StorageType + Storage type - read_speed_mib_s : float - Read speed [MiB/s] + read_speed_mib_s : float + Read speed [MiB/s] - write_speed_mib_s : float - Write speed [MiB/s] + write_speed_mib_s : float + Write speed [MiB/s] - """ + """ - - class StorageStatus(Enum): """ - Storage status type. + Storage status type. - Values - ------ - NOT_AVAILABLE - Storage not available + Values + ------ + NOT_AVAILABLE + Storage not available - UNFORMATTED - Storage is not formatted (i.e. has no recognized file system) + UNFORMATTED + Storage is not formatted (i.e. has no recognized file system) - FORMATTED - Storage is formatted (i.e. has recognized a file system) + FORMATTED + Storage is formatted (i.e. has recognized a file system) - NOT_SUPPORTED - Storage status is not supported + NOT_SUPPORTED + Storage status is not supported - """ + """ - NOT_AVAILABLE = 0 UNFORMATTED = 1 FORMATTED = 2 @@ -1021,47 +824,57 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_STATUS_NOT_AVAILABLE: + """Parses a gRPC response""" + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_STATUS_NOT_AVAILABLE + ): return StorageInformation.StorageStatus.NOT_AVAILABLE - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_STATUS_UNFORMATTED: + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_STATUS_UNFORMATTED + ): return StorageInformation.StorageStatus.UNFORMATTED - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_STATUS_FORMATTED: + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_STATUS_FORMATTED + ): return StorageInformation.StorageStatus.FORMATTED - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_STATUS_NOT_SUPPORTED: + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_STATUS_NOT_SUPPORTED + ): return StorageInformation.StorageStatus.NOT_SUPPORTED def __str__(self): return self.name - - + class StorageType(Enum): """ - Storage type. + Storage type. - Values - ------ - UNKNOWN - Storage type unknown + Values + ------ + UNKNOWN + Storage type unknown - USB_STICK - Storage type USB stick + USB_STICK + Storage type USB stick - SD - Storage type SD card + SD + Storage type SD card - MICROSD - Storage type MicroSD card + MICROSD + Storage type MicroSD card - HD - Storage type HD mass storage + HD + Storage type HD mass storage - OTHER - Storage type other, not listed + OTHER + Storage type other, not listed - """ + """ - UNKNOWN = 0 USB_STICK = 1 SD = 2 @@ -1085,35 +898,47 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_TYPE_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_TYPE_UNKNOWN + ): return StorageInformation.StorageType.UNKNOWN - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_TYPE_USB_STICK: + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_TYPE_USB_STICK + ): return StorageInformation.StorageType.USB_STICK if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_TYPE_SD: return StorageInformation.StorageType.SD - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_TYPE_MICROSD: + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_TYPE_MICROSD + ): return StorageInformation.StorageType.MICROSD if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_TYPE_HD: return StorageInformation.StorageType.HD - if rpc_enum_value == camera_server_pb2.StorageInformation.STORAGE_TYPE_OTHER: + if ( + rpc_enum_value + == camera_server_pb2.StorageInformation.STORAGE_TYPE_OTHER + ): return StorageInformation.StorageType.OTHER def __str__(self): return self.name - def __init__( - self, - used_storage_mib, - available_storage_mib, - total_storage_mib, - storage_status, - storage_id, - storage_type, - read_speed_mib_s, - write_speed_mib_s): - """ Initializes the StorageInformation object """ + self, + used_storage_mib, + available_storage_mib, + total_storage_mib, + storage_status, + storage_id, + storage_type, + read_speed_mib_s, + write_speed_mib_s, + ): + """Initializes the StorageInformation object""" self.used_storage_mib = used_storage_mib self.available_storage_mib = available_storage_mib self.total_storage_mib = total_storage_mib @@ -1124,26 +949,28 @@ def __init__( self.write_speed_mib_s = write_speed_mib_s def __eq__(self, to_compare): - """ Checks if two StorageInformation are the same """ + """Checks if two StorageInformation are the same""" try: # Try to compare - this likely fails when it is compared to a non # StorageInformation object - return \ - (self.used_storage_mib == to_compare.used_storage_mib) and \ - (self.available_storage_mib == to_compare.available_storage_mib) and \ - (self.total_storage_mib == to_compare.total_storage_mib) and \ - (self.storage_status == to_compare.storage_status) and \ - (self.storage_id == to_compare.storage_id) and \ - (self.storage_type == to_compare.storage_type) and \ - (self.read_speed_mib_s == to_compare.read_speed_mib_s) and \ - (self.write_speed_mib_s == to_compare.write_speed_mib_s) + return ( + (self.used_storage_mib == to_compare.used_storage_mib) + and (self.available_storage_mib == to_compare.available_storage_mib) + and (self.total_storage_mib == to_compare.total_storage_mib) + and (self.storage_status == to_compare.storage_status) + and (self.storage_id == to_compare.storage_id) + and (self.storage_type == to_compare.storage_type) + and (self.read_speed_mib_s == to_compare.read_speed_mib_s) + and (self.write_speed_mib_s == to_compare.write_speed_mib_s) + ) except AttributeError: return False def __str__(self): - """ StorageInformation in string representation """ - struct_repr = ", ".join([ + """StorageInformation in string representation""" + struct_repr = ", ".join( + [ "used_storage_mib: " + str(self.used_storage_mib), "available_storage_mib: " + str(self.available_storage_mib), "total_storage_mib: " + str(self.total_storage_mib), @@ -1151,143 +978,96 @@ def __str__(self): "storage_id: " + str(self.storage_id), "storage_type: " + str(self.storage_type), "read_speed_mib_s: " + str(self.read_speed_mib_s), - "write_speed_mib_s: " + str(self.write_speed_mib_s) - ]) + "write_speed_mib_s: " + str(self.write_speed_mib_s), + ] + ) return f"StorageInformation: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStorageInformation): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return StorageInformation( - - rpcStorageInformation.used_storage_mib, - - - rpcStorageInformation.available_storage_mib, - - - rpcStorageInformation.total_storage_mib, - - - StorageInformation.StorageStatus.translate_from_rpc(rpcStorageInformation.storage_status), - - - rpcStorageInformation.storage_id, - - - StorageInformation.StorageType.translate_from_rpc(rpcStorageInformation.storage_type), - - - rpcStorageInformation.read_speed_mib_s, - - - rpcStorageInformation.write_speed_mib_s - ) + rpcStorageInformation.used_storage_mib, + rpcStorageInformation.available_storage_mib, + rpcStorageInformation.total_storage_mib, + StorageInformation.StorageStatus.translate_from_rpc( + rpcStorageInformation.storage_status + ), + rpcStorageInformation.storage_id, + StorageInformation.StorageType.translate_from_rpc( + rpcStorageInformation.storage_type + ), + rpcStorageInformation.read_speed_mib_s, + rpcStorageInformation.write_speed_mib_s, + ) def translate_to_rpc(self, rpcStorageInformation): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStorageInformation.used_storage_mib = self.used_storage_mib - - - - - + rpcStorageInformation.available_storage_mib = self.available_storage_mib - - - - - + rpcStorageInformation.total_storage_mib = self.total_storage_mib - - - - - + rpcStorageInformation.storage_status = self.storage_status.translate_to_rpc() - - - - - + rpcStorageInformation.storage_id = self.storage_id - - - - - + rpcStorageInformation.storage_type = self.storage_type.translate_to_rpc() - - - - - + rpcStorageInformation.read_speed_mib_s = self.read_speed_mib_s - - - - - + rpcStorageInformation.write_speed_mib_s = self.write_speed_mib_s - - - class CaptureStatus: """ - Capture status + Capture status - Parameters - ---------- - image_interval_s : float - Image capture interval (in s) + Parameters + ---------- + image_interval_s : float + Image capture interval (in s) - recording_time_s : float - Elapsed time since recording started (in s) + recording_time_s : float + Elapsed time since recording started (in s) - available_capacity_mib : float - Available storage capacity. (in MiB) + available_capacity_mib : float + Available storage capacity. (in MiB) - image_status : ImageStatus - Current status of image capturing + image_status : ImageStatus + Current status of image capturing - video_status : VideoStatus - Current status of video capturing + video_status : VideoStatus + Current status of video capturing - image_count : int32_t - Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT) + image_count : int32_t + Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT) - """ + """ - - class ImageStatus(Enum): """ - The image status + The image status - Values - ------ - IDLE - idle + Values + ------ + IDLE + idle - CAPTURE_IN_PROGRESS - capture in progress + CAPTURE_IN_PROGRESS + capture in progress - INTERVAL_IDLE - interval set but idle + INTERVAL_IDLE + interval set but idle - INTERVAL_IN_PROGRESS - interval set and capture in progress) + INTERVAL_IN_PROGRESS + interval set and capture in progress) - """ + """ - IDLE = 0 CAPTURE_IN_PROGRESS = 1 INTERVAL_IDLE = 2 @@ -1305,35 +1085,42 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_server_pb2.CaptureStatus.IMAGE_STATUS_IDLE: return CaptureStatus.ImageStatus.IDLE - if rpc_enum_value == camera_server_pb2.CaptureStatus.IMAGE_STATUS_CAPTURE_IN_PROGRESS: + if ( + rpc_enum_value + == camera_server_pb2.CaptureStatus.IMAGE_STATUS_CAPTURE_IN_PROGRESS + ): return CaptureStatus.ImageStatus.CAPTURE_IN_PROGRESS - if rpc_enum_value == camera_server_pb2.CaptureStatus.IMAGE_STATUS_INTERVAL_IDLE: + if ( + rpc_enum_value + == camera_server_pb2.CaptureStatus.IMAGE_STATUS_INTERVAL_IDLE + ): return CaptureStatus.ImageStatus.INTERVAL_IDLE - if rpc_enum_value == camera_server_pb2.CaptureStatus.IMAGE_STATUS_INTERVAL_IN_PROGRESS: + if ( + rpc_enum_value + == camera_server_pb2.CaptureStatus.IMAGE_STATUS_INTERVAL_IN_PROGRESS + ): return CaptureStatus.ImageStatus.INTERVAL_IN_PROGRESS def __str__(self): return self.name - - + class VideoStatus(Enum): """ - The video status + The video status - Values - ------ - IDLE - idle + Values + ------ + IDLE + idle - CAPTURE_IN_PROGRESS - capture in progress + CAPTURE_IN_PROGRESS + capture in progress - """ + """ - IDLE = 0 CAPTURE_IN_PROGRESS = 1 @@ -1345,25 +1132,28 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == camera_server_pb2.CaptureStatus.VIDEO_STATUS_IDLE: return CaptureStatus.VideoStatus.IDLE - if rpc_enum_value == camera_server_pb2.CaptureStatus.VIDEO_STATUS_CAPTURE_IN_PROGRESS: + if ( + rpc_enum_value + == camera_server_pb2.CaptureStatus.VIDEO_STATUS_CAPTURE_IN_PROGRESS + ): return CaptureStatus.VideoStatus.CAPTURE_IN_PROGRESS def __str__(self): return self.name - def __init__( - self, - image_interval_s, - recording_time_s, - available_capacity_mib, - image_status, - video_status, - image_count): - """ Initializes the CaptureStatus object """ + self, + image_interval_s, + recording_time_s, + available_capacity_mib, + image_status, + video_status, + image_count, + ): + """Initializes the CaptureStatus object""" self.image_interval_s = image_interval_s self.recording_time_s = recording_time_s self.available_capacity_mib = available_capacity_mib @@ -1372,298 +1162,216 @@ def __init__( self.image_count = image_count def __eq__(self, to_compare): - """ Checks if two CaptureStatus are the same """ + """Checks if two CaptureStatus are the same""" try: # Try to compare - this likely fails when it is compared to a non # CaptureStatus object - return \ - (self.image_interval_s == to_compare.image_interval_s) and \ - (self.recording_time_s == to_compare.recording_time_s) and \ - (self.available_capacity_mib == to_compare.available_capacity_mib) and \ - (self.image_status == to_compare.image_status) and \ - (self.video_status == to_compare.video_status) and \ - (self.image_count == to_compare.image_count) + return ( + (self.image_interval_s == to_compare.image_interval_s) + and (self.recording_time_s == to_compare.recording_time_s) + and (self.available_capacity_mib == to_compare.available_capacity_mib) + and (self.image_status == to_compare.image_status) + and (self.video_status == to_compare.video_status) + and (self.image_count == to_compare.image_count) + ) except AttributeError: return False def __str__(self): - """ CaptureStatus in string representation """ - struct_repr = ", ".join([ + """CaptureStatus in string representation""" + struct_repr = ", ".join( + [ "image_interval_s: " + str(self.image_interval_s), "recording_time_s: " + str(self.recording_time_s), "available_capacity_mib: " + str(self.available_capacity_mib), "image_status: " + str(self.image_status), "video_status: " + str(self.video_status), - "image_count: " + str(self.image_count) - ]) + "image_count: " + str(self.image_count), + ] + ) return f"CaptureStatus: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCaptureStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return CaptureStatus( - - rpcCaptureStatus.image_interval_s, - - - rpcCaptureStatus.recording_time_s, - - - rpcCaptureStatus.available_capacity_mib, - - - CaptureStatus.ImageStatus.translate_from_rpc(rpcCaptureStatus.image_status), - - - CaptureStatus.VideoStatus.translate_from_rpc(rpcCaptureStatus.video_status), - - - rpcCaptureStatus.image_count - ) + rpcCaptureStatus.image_interval_s, + rpcCaptureStatus.recording_time_s, + rpcCaptureStatus.available_capacity_mib, + CaptureStatus.ImageStatus.translate_from_rpc(rpcCaptureStatus.image_status), + CaptureStatus.VideoStatus.translate_from_rpc(rpcCaptureStatus.video_status), + rpcCaptureStatus.image_count, + ) def translate_to_rpc(self, rpcCaptureStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCaptureStatus.image_interval_s = self.image_interval_s - - - - - + rpcCaptureStatus.recording_time_s = self.recording_time_s - - - - - + rpcCaptureStatus.available_capacity_mib = self.available_capacity_mib - - - - - + rpcCaptureStatus.image_status = self.image_status.translate_to_rpc() - - - - - + rpcCaptureStatus.video_status = self.video_status.translate_to_rpc() - - - - - + rpcCaptureStatus.image_count = self.image_count - - - class TrackPoint: """ - Point description type + Point description type - Parameters - ---------- - point_x : float - Point to track x value (normalized 0..1, 0 is left, 1 is right). + Parameters + ---------- + point_x : float + Point to track x value (normalized 0..1, 0 is left, 1 is right). - point_y : float - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + point_y : float + Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - radius : float - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + radius : float + Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - """ - - + """ - def __init__( - self, - point_x, - point_y, - radius): - """ Initializes the TrackPoint object """ + def __init__(self, point_x, point_y, radius): + """Initializes the TrackPoint object""" self.point_x = point_x self.point_y = point_y self.radius = radius def __eq__(self, to_compare): - """ Checks if two TrackPoint are the same """ + """Checks if two TrackPoint are the same""" try: # Try to compare - this likely fails when it is compared to a non # TrackPoint object - return \ - (self.point_x == to_compare.point_x) and \ - (self.point_y == to_compare.point_y) and \ - (self.radius == to_compare.radius) + return ( + (self.point_x == to_compare.point_x) + and (self.point_y == to_compare.point_y) + and (self.radius == to_compare.radius) + ) except AttributeError: return False def __str__(self): - """ TrackPoint in string representation """ - struct_repr = ", ".join([ + """TrackPoint in string representation""" + struct_repr = ", ".join( + [ "point_x: " + str(self.point_x), "point_y: " + str(self.point_y), - "radius: " + str(self.radius) - ]) + "radius: " + str(self.radius), + ] + ) return f"TrackPoint: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTrackPoint): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TrackPoint( - - rpcTrackPoint.point_x, - - - rpcTrackPoint.point_y, - - - rpcTrackPoint.radius - ) + rpcTrackPoint.point_x, rpcTrackPoint.point_y, rpcTrackPoint.radius + ) def translate_to_rpc(self, rpcTrackPoint): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTrackPoint.point_x = self.point_x - - - - - + rpcTrackPoint.point_y = self.point_y - - - - - + rpcTrackPoint.radius = self.radius - - - class TrackRectangle: """ - Rectangle description type - - Parameters - ---------- - top_left_corner_x : float - Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + Rectangle description type - top_left_corner_y : float - Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + Parameters + ---------- + top_left_corner_x : float + Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - bottom_right_corner_x : float - Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + top_left_corner_y : float + Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - bottom_right_corner_y : float - Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + bottom_right_corner_x : float + Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - """ + bottom_right_corner_y : float + Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - + """ def __init__( - self, - top_left_corner_x, - top_left_corner_y, - bottom_right_corner_x, - bottom_right_corner_y): - """ Initializes the TrackRectangle object """ + self, + top_left_corner_x, + top_left_corner_y, + bottom_right_corner_x, + bottom_right_corner_y, + ): + """Initializes the TrackRectangle object""" self.top_left_corner_x = top_left_corner_x self.top_left_corner_y = top_left_corner_y self.bottom_right_corner_x = bottom_right_corner_x self.bottom_right_corner_y = bottom_right_corner_y def __eq__(self, to_compare): - """ Checks if two TrackRectangle are the same """ + """Checks if two TrackRectangle are the same""" try: # Try to compare - this likely fails when it is compared to a non # TrackRectangle object - return \ - (self.top_left_corner_x == to_compare.top_left_corner_x) and \ - (self.top_left_corner_y == to_compare.top_left_corner_y) and \ - (self.bottom_right_corner_x == to_compare.bottom_right_corner_x) and \ - (self.bottom_right_corner_y == to_compare.bottom_right_corner_y) + return ( + (self.top_left_corner_x == to_compare.top_left_corner_x) + and (self.top_left_corner_y == to_compare.top_left_corner_y) + and (self.bottom_right_corner_x == to_compare.bottom_right_corner_x) + and (self.bottom_right_corner_y == to_compare.bottom_right_corner_y) + ) except AttributeError: return False def __str__(self): - """ TrackRectangle in string representation """ - struct_repr = ", ".join([ + """TrackRectangle in string representation""" + struct_repr = ", ".join( + [ "top_left_corner_x: " + str(self.top_left_corner_x), "top_left_corner_y: " + str(self.top_left_corner_y), "bottom_right_corner_x: " + str(self.bottom_right_corner_x), - "bottom_right_corner_y: " + str(self.bottom_right_corner_y) - ]) + "bottom_right_corner_y: " + str(self.bottom_right_corner_y), + ] + ) return f"TrackRectangle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTrackRectangle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TrackRectangle( - - rpcTrackRectangle.top_left_corner_x, - - - rpcTrackRectangle.top_left_corner_y, - - - rpcTrackRectangle.bottom_right_corner_x, - - - rpcTrackRectangle.bottom_right_corner_y - ) + rpcTrackRectangle.top_left_corner_x, + rpcTrackRectangle.top_left_corner_y, + rpcTrackRectangle.bottom_right_corner_x, + rpcTrackRectangle.bottom_right_corner_y, + ) def translate_to_rpc(self, rpcTrackRectangle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTrackRectangle.top_left_corner_x = self.top_left_corner_x - - - - - + rpcTrackRectangle.top_left_corner_y = self.top_left_corner_y - - - - - + rpcTrackRectangle.bottom_right_corner_x = self.bottom_right_corner_x - - - - - - rpcTrackRectangle.bottom_right_corner_y = self.bottom_right_corner_y - - - + rpcTrackRectangle.bottom_right_corner_y = self.bottom_right_corner_y class CameraServerError(Exception): - """ Raised when a CameraServerResult is a fail code """ + """Raised when a CameraServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -1676,117 +1384,107 @@ def __str__(self): class CameraServer(AsyncBase): """ - Provides handling of camera interface + Provides handling of camera interface - Generated by dcsdkgen - MAVSDK CameraServer API + Generated by dcsdkgen - MAVSDK CameraServer API """ # Plugin name name = "CameraServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = camera_server_pb2_grpc.CameraServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return CameraServerResult.translate_from_rpc(response.camera_server_result) - async def set_information(self, information): """ - Sets the camera information. This must be called as soon as the camera server is created. + Sets the camera information. This must be called as soon as the camera server is created. - Parameters - ---------- - information : Information - information about the camera + Parameters + ---------- + information : Information + information about the camera - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.SetInformationRequest() - + information.translate_to_rpc(request.information) - - + response = await self._stub.SetInformation(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "set_information()", information) - async def set_video_streaming(self, video_streaming): """ - Sets video streaming settings. + Sets video streaming settings. - Parameters - ---------- - video_streaming : VideoStreaming - information about the video stream + Parameters + ---------- + video_streaming : VideoStreaming + information about the video stream - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.SetVideoStreamingRequest() - + video_streaming.translate_to_rpc(request.video_streaming) - - + response = await self._stub.SetVideoStreaming(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "set_video_streaming()", video_streaming) - async def set_in_progress(self, in_progress): """ - Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. + Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. - Parameters - ---------- - in_progress : bool - true if capture is in progress or false for idle. + Parameters + ---------- + in_progress : bool + true if capture is in progress or false for idle. - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.SetInProgressRequest() request.in_progress = in_progress response = await self._stub.SetInProgress(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "set_in_progress()", in_progress) - async def take_photo(self): """ - Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. + Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. + + Yields + ------- + index : int32_t + - Yields - ------- - index : int32_t - - """ request = camera_server_pb2.SubscribeTakePhotoRequest() @@ -1794,59 +1492,53 @@ async def take_photo(self): try: async for response in take_photo_stream: - - - yield response.index finally: take_photo_stream.cancel() async def respond_take_photo(self, take_photo_feedback, capture_info): """ - Respond to an image capture request from SubscribeTakePhoto. + Respond to an image capture request from SubscribeTakePhoto. - Parameters - ---------- - take_photo_feedback : CameraFeedback - the feedback + Parameters + ---------- + take_photo_feedback : CameraFeedback + the feedback - capture_info : CaptureInfo - the capture information + capture_info : CaptureInfo + the capture information - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondTakePhotoRequest() - + request.take_photo_feedback = take_photo_feedback.translate_to_rpc() - - - + capture_info.translate_to_rpc(request.capture_info) - - + response = await self._stub.RespondTakePhoto(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_take_photo()", take_photo_feedback, capture_info) - + raise CameraServerError( + result, "respond_take_photo()", take_photo_feedback, capture_info + ) async def start_video(self): """ - Subscribe to start video requests. Each request received should respond to using RespondStartVideo + Subscribe to start video requests. Each request received should respond to using RespondStartVideo + + Yields + ------- + stream_id : int32_t + video stream id - Yields - ------- - stream_id : int32_t - video stream id - """ request = camera_server_pb2.SubscribeStartVideoRequest() @@ -1854,52 +1546,48 @@ async def start_video(self): try: async for response in start_video_stream: - - - yield response.stream_id finally: start_video_stream.cancel() async def respond_start_video(self, start_video_feedback): """ - Subscribe to stop video requests. Each request received should respond using StopVideoResponse + Subscribe to stop video requests. Each request received should respond using StopVideoResponse - Parameters - ---------- - start_video_feedback : CameraFeedback - the feedback + Parameters + ---------- + start_video_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondStartVideoRequest() - + request.start_video_feedback = start_video_feedback.translate_to_rpc() - - + response = await self._stub.RespondStartVideo(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_start_video()", start_video_feedback) - + raise CameraServerError( + result, "respond_start_video()", start_video_feedback + ) async def stop_video(self): """ - Subscribe to stop video requests. Each request received should response to using RespondStopVideo + Subscribe to stop video requests. Each request received should response to using RespondStopVideo + + Yields + ------- + stream_id : int32_t + video stream id - Yields - ------- - stream_id : int32_t - video stream id - """ request = camera_server_pb2.SubscribeStopVideoRequest() @@ -1907,52 +1595,46 @@ async def stop_video(self): try: async for response in stop_video_stream: - - - yield response.stream_id finally: stop_video_stream.cancel() async def respond_stop_video(self, stop_video_feedback): """ - Respond to stop video request from SubscribeStopVideo. + Respond to stop video request from SubscribeStopVideo. - Parameters - ---------- - stop_video_feedback : CameraFeedback - the feedback + Parameters + ---------- + stop_video_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondStopVideoRequest() - + request.stop_video_feedback = stop_video_feedback.translate_to_rpc() - - + response = await self._stub.RespondStopVideo(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "respond_stop_video()", stop_video_feedback) - async def start_video_streaming(self): """ - Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming + Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming + + Yields + ------- + stream_id : int32_t + video stream id - Yields - ------- - stream_id : int32_t - video stream id - """ request = camera_server_pb2.SubscribeStartVideoStreamingRequest() @@ -1960,52 +1642,52 @@ async def start_video_streaming(self): try: async for response in start_video_streaming_stream: - - - yield response.stream_id finally: start_video_streaming_stream.cancel() async def respond_start_video_streaming(self, start_video_streaming_feedback): """ - Respond to start video streaming from SubscribeStartVideoStreaming. + Respond to start video streaming from SubscribeStartVideoStreaming. - Parameters - ---------- - start_video_streaming_feedback : CameraFeedback - the feedback + Parameters + ---------- + start_video_streaming_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondStartVideoStreamingRequest() - - request.start_video_streaming_feedback = start_video_streaming_feedback.translate_to_rpc() - - + + request.start_video_streaming_feedback = ( + start_video_streaming_feedback.translate_to_rpc() + ) + response = await self._stub.RespondStartVideoStreaming(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_start_video_streaming()", start_video_streaming_feedback) - + raise CameraServerError( + result, + "respond_start_video_streaming()", + start_video_streaming_feedback, + ) async def stop_video_streaming(self): """ - Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming + Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming + + Yields + ------- + stream_id : int32_t + video stream id - Yields - ------- - stream_id : int32_t - video stream id - """ request = camera_server_pb2.SubscribeStopVideoStreamingRequest() @@ -2013,51 +1695,49 @@ async def stop_video_streaming(self): try: async for response in stop_video_streaming_stream: - - - yield response.stream_id finally: stop_video_streaming_stream.cancel() async def respond_stop_video_streaming(self, stop_video_streaming_feedback): """ - Respond to stop video streaming from SubscribeStopVideoStreaming. + Respond to stop video streaming from SubscribeStopVideoStreaming. - Parameters - ---------- - stop_video_streaming_feedback : CameraFeedback - the feedback + Parameters + ---------- + stop_video_streaming_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondStopVideoStreamingRequest() - - request.stop_video_streaming_feedback = stop_video_streaming_feedback.translate_to_rpc() - - + + request.stop_video_streaming_feedback = ( + stop_video_streaming_feedback.translate_to_rpc() + ) + response = await self._stub.RespondStopVideoStreaming(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_stop_video_streaming()", stop_video_streaming_feedback) - + raise CameraServerError( + result, "respond_stop_video_streaming()", stop_video_streaming_feedback + ) async def set_mode(self): """ - Subscribe to set camera mode requests. Each request received should response to using RespondSetMode + Subscribe to set camera mode requests. Each request received should response to using RespondSetMode + + Yields + ------- + mode : Mode + - Yields - ------- - mode : Mode - - """ request = camera_server_pb2.SubscribeSetModeRequest() @@ -2065,51 +1745,45 @@ async def set_mode(self): try: async for response in set_mode_stream: - - - yield Mode.translate_from_rpc(response.mode) finally: set_mode_stream.cancel() async def respond_set_mode(self, set_mode_feedback): """ - Respond to set camera mode from SubscribeSetMode. + Respond to set camera mode from SubscribeSetMode. - Parameters - ---------- - set_mode_feedback : CameraFeedback - the feedback + Parameters + ---------- + set_mode_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondSetModeRequest() - + request.set_mode_feedback = set_mode_feedback.translate_to_rpc() - - + response = await self._stub.RespondSetMode(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "respond_set_mode()", set_mode_feedback) - async def storage_information(self): """ - Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation + Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation + + Yields + ------- + storage_id : int32_t + - Yields - ------- - storage_id : int32_t - - """ request = camera_server_pb2.SubscribeStorageInformationRequest() @@ -2117,59 +1791,60 @@ async def storage_information(self): try: async for response in storage_information_stream: - - - yield response.storage_id finally: storage_information_stream.cancel() - async def respond_storage_information(self, storage_information_feedback, storage_information): + async def respond_storage_information( + self, storage_information_feedback, storage_information + ): """ - Respond to camera storage information from SubscribeStorageInformation. + Respond to camera storage information from SubscribeStorageInformation. - Parameters - ---------- - storage_information_feedback : CameraFeedback - the feedback + Parameters + ---------- + storage_information_feedback : CameraFeedback + the feedback - storage_information : StorageInformation - the storage information + storage_information : StorageInformation + the storage information - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondStorageInformationRequest() - - request.storage_information_feedback = storage_information_feedback.translate_to_rpc() - - - + + request.storage_information_feedback = ( + storage_information_feedback.translate_to_rpc() + ) + storage_information.translate_to_rpc(request.storage_information) - - + response = await self._stub.RespondStorageInformation(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_storage_information()", storage_information_feedback, storage_information) - + raise CameraServerError( + result, + "respond_storage_information()", + storage_information_feedback, + storage_information, + ) async def capture_status(self): """ - Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus + Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus + + Yields + ------- + reserved : int32_t + reserved, just make protoc-gen-mavsdk working - Yields - ------- - reserved : int32_t - reserved, just make protoc-gen-mavsdk working - """ request = camera_server_pb2.SubscribeCaptureStatusRequest() @@ -2177,59 +1852,56 @@ async def capture_status(self): try: async for response in capture_status_stream: - - - yield response.reserved finally: capture_status_stream.cancel() async def respond_capture_status(self, capture_status_feedback, capture_status): """ - Respond to camera capture status from SubscribeCaptureStatus. + Respond to camera capture status from SubscribeCaptureStatus. - Parameters - ---------- - capture_status_feedback : CameraFeedback - the feedback + Parameters + ---------- + capture_status_feedback : CameraFeedback + the feedback - capture_status : CaptureStatus - the capture status + capture_status : CaptureStatus + the capture status - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondCaptureStatusRequest() - + request.capture_status_feedback = capture_status_feedback.translate_to_rpc() - - - + capture_status.translate_to_rpc(request.capture_status) - - + response = await self._stub.RespondCaptureStatus(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_capture_status()", capture_status_feedback, capture_status) - + raise CameraServerError( + result, + "respond_capture_status()", + capture_status_feedback, + capture_status, + ) async def format_storage(self): """ - Subscribe to format storage requests. Each request received should response to using RespondFormatStorage + Subscribe to format storage requests. Each request received should response to using RespondFormatStorage + + Yields + ------- + storage_id : int32_t + the storage id to format - Yields - ------- - storage_id : int32_t - the storage id to format - """ request = camera_server_pb2.SubscribeFormatStorageRequest() @@ -2237,52 +1909,48 @@ async def format_storage(self): try: async for response in format_storage_stream: - - - yield response.storage_id finally: format_storage_stream.cancel() async def respond_format_storage(self, format_storage_feedback): """ - Respond to format storage from SubscribeFormatStorage. + Respond to format storage from SubscribeFormatStorage. - Parameters - ---------- - format_storage_feedback : CameraFeedback - the feedback + Parameters + ---------- + format_storage_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondFormatStorageRequest() - + request.format_storage_feedback = format_storage_feedback.translate_to_rpc() - - + response = await self._stub.RespondFormatStorage(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_format_storage()", format_storage_feedback) - + raise CameraServerError( + result, "respond_format_storage()", format_storage_feedback + ) async def reset_settings(self): """ - Subscribe to reset settings requests. Each request received should response to using RespondResetSettings + Subscribe to reset settings requests. Each request received should response to using RespondResetSettings + + Yields + ------- + reserved : int32_t + reserved, just make protoc-gen-mavsdk working - Yields - ------- - reserved : int32_t - reserved, just make protoc-gen-mavsdk working - """ request = camera_server_pb2.SubscribeResetSettingsRequest() @@ -2290,52 +1958,48 @@ async def reset_settings(self): try: async for response in reset_settings_stream: - - - yield response.reserved finally: reset_settings_stream.cancel() async def respond_reset_settings(self, reset_settings_feedback): """ - Respond to reset settings from SubscribeResetSettings. + Respond to reset settings from SubscribeResetSettings. - Parameters - ---------- - reset_settings_feedback : CameraFeedback - the feedback + Parameters + ---------- + reset_settings_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondResetSettingsRequest() - + request.reset_settings_feedback = reset_settings_feedback.translate_to_rpc() - - + response = await self._stub.RespondResetSettings(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_reset_settings()", reset_settings_feedback) - + raise CameraServerError( + result, "respond_reset_settings()", reset_settings_feedback + ) async def zoom_in_start(self): """ - Subscribe to zoom in start command + Subscribe to zoom in start command + + Yields + ------- + reserved : int32_t + reserved, just make protoc-gen-mavsdk working - Yields - ------- - reserved : int32_t - reserved, just make protoc-gen-mavsdk working - """ request = camera_server_pb2.SubscribeZoomInStartRequest() @@ -2343,52 +2007,48 @@ async def zoom_in_start(self): try: async for response in zoom_in_start_stream: - - - yield response.reserved finally: zoom_in_start_stream.cancel() async def respond_zoom_in_start(self, zoom_in_start_feedback): """ - Respond to zoom in start. + Respond to zoom in start. - Parameters - ---------- - zoom_in_start_feedback : CameraFeedback - the feedback + Parameters + ---------- + zoom_in_start_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondZoomInStartRequest() - + request.zoom_in_start_feedback = zoom_in_start_feedback.translate_to_rpc() - - + response = await self._stub.RespondZoomInStart(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_zoom_in_start()", zoom_in_start_feedback) - + raise CameraServerError( + result, "respond_zoom_in_start()", zoom_in_start_feedback + ) async def zoom_out_start(self): """ - Subscribe to zoom out start command + Subscribe to zoom out start command + + Yields + ------- + reserved : int32_t + reserved, just make protoc-gen-mavsdk working - Yields - ------- - reserved : int32_t - reserved, just make protoc-gen-mavsdk working - """ request = camera_server_pb2.SubscribeZoomOutStartRequest() @@ -2396,52 +2056,48 @@ async def zoom_out_start(self): try: async for response in zoom_out_start_stream: - - - yield response.reserved finally: zoom_out_start_stream.cancel() async def respond_zoom_out_start(self, zoom_out_start_feedback): """ - Respond to zoom out start. + Respond to zoom out start. - Parameters - ---------- - zoom_out_start_feedback : CameraFeedback - the feedback + Parameters + ---------- + zoom_out_start_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondZoomOutStartRequest() - + request.zoom_out_start_feedback = zoom_out_start_feedback.translate_to_rpc() - - + response = await self._stub.RespondZoomOutStart(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_zoom_out_start()", zoom_out_start_feedback) - + raise CameraServerError( + result, "respond_zoom_out_start()", zoom_out_start_feedback + ) async def zoom_stop(self): """ - Subscribe to zoom stop command + Subscribe to zoom stop command + + Yields + ------- + reserved : int32_t + reserved, just make protoc-gen-mavsdk working - Yields - ------- - reserved : int32_t - reserved, just make protoc-gen-mavsdk working - """ request = camera_server_pb2.SubscribeZoomStopRequest() @@ -2449,52 +2105,46 @@ async def zoom_stop(self): try: async for response in zoom_stop_stream: - - - yield response.reserved finally: zoom_stop_stream.cancel() async def respond_zoom_stop(self, zoom_stop_feedback): """ - Respond to zoom stop. + Respond to zoom stop. - Parameters - ---------- - zoom_stop_feedback : CameraFeedback - the feedback + Parameters + ---------- + zoom_stop_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondZoomStopRequest() - + request.zoom_stop_feedback = zoom_stop_feedback.translate_to_rpc() - - + response = await self._stub.RespondZoomStop(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "respond_zoom_stop()", zoom_stop_feedback) - async def zoom_range(self): """ - Subscribe to zoom range command + Subscribe to zoom range command + + Yields + ------- + factor : float + The zoom factor, starting at 1x. - Yields - ------- - factor : float - The zoom factor, starting at 1x. - """ request = camera_server_pb2.SubscribeZoomRangeRequest() @@ -2502,133 +2152,120 @@ async def zoom_range(self): try: async for response in zoom_range_stream: - - - yield response.factor finally: zoom_range_stream.cancel() async def respond_zoom_range(self, zoom_range_feedback): """ - Respond to zoom range. + Respond to zoom range. - Parameters - ---------- - zoom_range_feedback : CameraFeedback - the feedback + Parameters + ---------- + zoom_range_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondZoomRangeRequest() - + request.zoom_range_feedback = zoom_range_feedback.translate_to_rpc() - - + response = await self._stub.RespondZoomRange(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: raise CameraServerError(result, "respond_zoom_range()", zoom_range_feedback) - async def set_tracking_rectangle_status(self, tracked_rectangle): """ - Set/update the current rectangle tracking status. + Set/update the current rectangle tracking status. + + Parameters + ---------- + tracked_rectangle : TrackRectangle + The tracked rectangle - Parameters - ---------- - tracked_rectangle : TrackRectangle - The tracked rectangle - """ request = camera_server_pb2.SetTrackingRectangleStatusRequest() - + tracked_rectangle.translate_to_rpc(request.tracked_rectangle) - - - response = await self._stub.SetTrackingRectangleStatus(request) - + response = await self._stub.SetTrackingRectangleStatus(request) async def set_tracking_off_status(self): """ - Set the current tracking status to off. + Set the current tracking status to off. + - """ request = camera_server_pb2.SetTrackingOffStatusRequest() response = await self._stub.SetTrackingOffStatus(request) - - async def tracking_point_command(self): """ - Subscribe to incoming tracking point command. + Subscribe to incoming tracking point command. + + Yields + ------- + track_point : TrackPoint + The point to track if a point is to be tracked - Yields - ------- - track_point : TrackPoint - The point to track if a point is to be tracked - """ request = camera_server_pb2.SubscribeTrackingPointCommandRequest() - tracking_point_command_stream = self._stub.SubscribeTrackingPointCommand(request) + tracking_point_command_stream = self._stub.SubscribeTrackingPointCommand( + request + ) try: async for response in tracking_point_command_stream: - - - yield TrackPoint.translate_from_rpc(response.track_point) finally: tracking_point_command_stream.cancel() async def tracking_rectangle_command(self): """ - Subscribe to incoming tracking rectangle command. + Subscribe to incoming tracking rectangle command. + + Yields + ------- + track_rectangle : TrackRectangle + The point to track if a point is to be tracked - Yields - ------- - track_rectangle : TrackRectangle - The point to track if a point is to be tracked - """ request = camera_server_pb2.SubscribeTrackingRectangleCommandRequest() - tracking_rectangle_command_stream = self._stub.SubscribeTrackingRectangleCommand(request) + tracking_rectangle_command_stream = ( + self._stub.SubscribeTrackingRectangleCommand(request) + ) try: async for response in tracking_rectangle_command_stream: - - - yield TrackRectangle.translate_from_rpc(response.track_rectangle) finally: tracking_rectangle_command_stream.cancel() async def tracking_off_command(self): """ - Subscribe to incoming tracking off command. + Subscribe to incoming tracking off command. + + Yields + ------- + dummy : int32_t + Unused - Yields - ------- - dummy : int32_t - Unused - """ request = camera_server_pb2.SubscribeTrackingOffCommandRequest() @@ -2636,96 +2273,90 @@ async def tracking_off_command(self): try: async for response in tracking_off_command_stream: - - - yield response.dummy finally: tracking_off_command_stream.cancel() async def respond_tracking_point_command(self, stop_video_feedback): """ - Respond to an incoming tracking point command. + Respond to an incoming tracking point command. - Parameters - ---------- - stop_video_feedback : CameraFeedback - the feedback + Parameters + ---------- + stop_video_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondTrackingPointCommandRequest() - + request.stop_video_feedback = stop_video_feedback.translate_to_rpc() - - + response = await self._stub.RespondTrackingPointCommand(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_tracking_point_command()", stop_video_feedback) - + raise CameraServerError( + result, "respond_tracking_point_command()", stop_video_feedback + ) async def respond_tracking_rectangle_command(self, stop_video_feedback): """ - Respond to an incoming tracking rectangle command. + Respond to an incoming tracking rectangle command. - Parameters - ---------- - stop_video_feedback : CameraFeedback - the feedback + Parameters + ---------- + stop_video_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondTrackingRectangleCommandRequest() - + request.stop_video_feedback = stop_video_feedback.translate_to_rpc() - - + response = await self._stub.RespondTrackingRectangleCommand(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_tracking_rectangle_command()", stop_video_feedback) - + raise CameraServerError( + result, "respond_tracking_rectangle_command()", stop_video_feedback + ) async def respond_tracking_off_command(self, stop_video_feedback): """ - Respond to an incoming tracking off command. + Respond to an incoming tracking off command. - Parameters - ---------- - stop_video_feedback : CameraFeedback - the feedback + Parameters + ---------- + stop_video_feedback : CameraFeedback + the feedback - Raises - ------ - CameraServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + CameraServerError + If the request fails. The error contains the reason for the failure. """ request = camera_server_pb2.RespondTrackingOffCommandRequest() - + request.stop_video_feedback = stop_video_feedback.translate_to_rpc() - - + response = await self._stub.RespondTrackingOffCommand(request) - result = self._extract_result(response) if result.result != CameraServerResult.Result.SUCCESS: - raise CameraServerError(result, "respond_tracking_off_command()", stop_video_feedback) - \ No newline at end of file + raise CameraServerError( + result, "respond_tracking_off_command()", stop_video_feedback + ) diff --git a/mavsdk/camera_server_pb2.py b/mavsdk/camera_server_pb2.py index 1fa0e587..d07ef6d1 100644 --- a/mavsdk/camera_server_pb2.py +++ b/mavsdk/camera_server_pb2.py @@ -4,18 +4,15 @@ # source: camera_server/camera_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'camera_server/camera_server.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "camera_server/camera_server.proto" ) # @@protoc_insertion_point(imports) @@ -25,286 +22,448 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n!camera_server/camera_server.proto\x12\x18mavsdk.rpc.camera_server\x1a\x14mavsdk_options.proto\"S\n\x15SetInformationRequest\x12:\n\x0binformation\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.camera_server.Information\"d\n\x16SetInformationResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"]\n\x18SetVideoStreamingRequest\x12\x41\n\x0fvideo_streaming\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera_server.VideoStreaming\"g\n\x19SetVideoStreamingResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"+\n\x14SetInProgressRequest\x12\x13\n\x0bin_progress\x18\x01 \x01(\x08\"c\n\x15SetInProgressResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1b\n\x19SubscribeTakePhotoRequest\"\"\n\x11TakePhotoResponse\x12\r\n\x05index\x18\x01 \x01(\x05\"\x9d\x01\n\x17RespondTakePhotoRequest\x12\x45\n\x13take_photo_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\x12;\n\x0c\x63\x61pture_info\x18\x02 \x01(\x0b\x32%.mavsdk.rpc.camera_server.CaptureInfo\"f\n\x18RespondTakePhotoResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1c\n\x1aSubscribeStartVideoRequest\"\'\n\x12StartVideoResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05\"b\n\x18RespondStartVideoRequest\x12\x46\n\x14start_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"g\n\x19RespondStartVideoResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1b\n\x19SubscribeStopVideoRequest\"&\n\x11StopVideoResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05\"`\n\x17RespondStopVideoRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"f\n\x18RespondStopVideoResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"%\n#SubscribeStartVideoStreamingRequest\"0\n\x1bStartVideoStreamingResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05\"u\n!RespondStartVideoStreamingRequest\x12P\n\x1estart_video_streaming_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"p\n\"RespondStartVideoStreamingResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"$\n\"SubscribeStopVideoStreamingRequest\"/\n\x1aStopVideoStreamingResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05\"s\n RespondStopVideoStreamingRequest\x12O\n\x1dstop_video_streaming_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"o\n!RespondStopVideoStreamingResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x19\n\x17SubscribeSetModeRequest\"?\n\x0fSetModeResponse\x12,\n\x04mode\x18\x01 \x01(\x0e\x32\x1e.mavsdk.rpc.camera_server.Mode\"\\\n\x15RespondSetModeRequest\x12\x43\n\x11set_mode_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"d\n\x16RespondSetModeResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"$\n\"SubscribeStorageInformationRequest\"0\n\x1aStorageInformationResponse\x12\x12\n\nstorage_id\x18\x01 \x01(\x05\"\xbd\x01\n RespondStorageInformationRequest\x12N\n\x1cstorage_information_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\x12I\n\x13storage_information\x18\x02 \x01(\x0b\x32,.mavsdk.rpc.camera_server.StorageInformation\"o\n!RespondStorageInformationResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1f\n\x1dSubscribeCaptureStatusRequest\")\n\x15\x43\x61ptureStatusResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05\"\xa9\x01\n\x1bRespondCaptureStatusRequest\x12I\n\x17\x63\x61pture_status_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\x12?\n\x0e\x63\x61pture_status\x18\x02 \x01(\x0b\x32\'.mavsdk.rpc.camera_server.CaptureStatus\"j\n\x1cRespondCaptureStatusResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1f\n\x1dSubscribeFormatStorageRequest\"+\n\x15\x46ormatStorageResponse\x12\x12\n\nstorage_id\x18\x01 \x01(\x05\"h\n\x1bRespondFormatStorageRequest\x12I\n\x17\x66ormat_storage_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"j\n\x1cRespondFormatStorageResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1f\n\x1dSubscribeResetSettingsRequest\")\n\x15ResetSettingsResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05\"h\n\x1bRespondResetSettingsRequest\x12I\n\x17reset_settings_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"j\n\x1cRespondResetSettingsResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1d\n\x1bSubscribeZoomInStartRequest\"\'\n\x13ZoomInStartResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05\"e\n\x19RespondZoomInStartRequest\x12H\n\x16zoom_in_start_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"h\n\x1aRespondZoomInStartResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1e\n\x1cSubscribeZoomOutStartRequest\"(\n\x14ZoomOutStartResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05\"g\n\x1aRespondZoomOutStartRequest\x12I\n\x17zoom_out_start_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"i\n\x1bRespondZoomOutStartResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1a\n\x18SubscribeZoomStopRequest\"$\n\x10ZoomStopResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05\"^\n\x16RespondZoomStopRequest\x12\x44\n\x12zoom_stop_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"e\n\x17RespondZoomStopResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x1b\n\x19SubscribeZoomRangeRequest\"#\n\x11ZoomRangeResponse\x12\x0e\n\x06\x66\x61\x63tor\x18\x01 \x01(\x02\"`\n\x17RespondZoomRangeRequest\x12\x45\n\x13zoom_range_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"f\n\x18RespondZoomRangeResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"\x8c\x03\n\x0bInformation\x12\x13\n\x0bvendor_name\x18\x01 \x01(\t\x12\x12\n\nmodel_name\x18\x02 \x01(\t\x12\x18\n\x10\x66irmware_version\x18\x03 \x01(\t\x12\x17\n\x0f\x66ocal_length_mm\x18\x04 \x01(\x02\x12!\n\x19horizontal_sensor_size_mm\x18\x05 \x01(\x02\x12\x1f\n\x17vertical_sensor_size_mm\x18\x06 \x01(\x02\x12 \n\x18horizontal_resolution_px\x18\x07 \x01(\r\x12\x1e\n\x16vertical_resolution_px\x18\x08 \x01(\r\x12\x0f\n\x07lens_id\x18\t \x01(\r\x12\x1f\n\x17\x64\x65\x66inition_file_version\x18\n \x01(\r\x12\x1b\n\x13\x64\x65\x66inition_file_uri\x18\x0b \x01(\t\x12%\n\x1dimage_in_video_mode_supported\x18\x0c \x01(\x08\x12%\n\x1dvideo_in_image_mode_supported\x18\r \x01(\x08\";\n\x0eVideoStreaming\x12\x17\n\x0fhas_rtsp_server\x18\x01 \x01(\x08\x12\x10\n\x08rtsp_uri\x18\x02 \x01(\t\"q\n\x08Position\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x12\x1b\n\x13relative_altitude_m\x18\x04 \x01(\x02\"8\n\nQuaternion\x12\t\n\x01w\x18\x01 \x01(\x02\x12\t\n\x01x\x18\x02 \x01(\x02\x12\t\n\x01y\x18\x03 \x01(\x02\x12\t\n\x01z\x18\x04 \x01(\x02\"\xd0\x01\n\x0b\x43\x61ptureInfo\x12\x34\n\x08position\x18\x01 \x01(\x0b\x32\".mavsdk.rpc.camera_server.Position\x12\x41\n\x13\x61ttitude_quaternion\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.camera_server.Quaternion\x12\x13\n\x0btime_utc_us\x18\x03 \x01(\x04\x12\x12\n\nis_success\x18\x04 \x01(\x08\x12\r\n\x05index\x18\x05 \x01(\x05\x12\x10\n\x08\x66ile_url\x18\x06 \x01(\t\"\xb3\x02\n\x12\x43\x61meraServerResult\x12\x43\n\x06result\x18\x01 \x01(\x0e\x32\x33.mavsdk.rpc.camera_server.CameraServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xc3\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x16\n\x12RESULT_IN_PROGRESS\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x10\n\x0cRESULT_ERROR\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x19\n\x15RESULT_WRONG_ARGUMENT\x10\x07\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x08\"\x8c\x05\n\x12StorageInformation\x12\x18\n\x10used_storage_mib\x18\x01 \x01(\x02\x12\x1d\n\x15\x61vailable_storage_mib\x18\x02 \x01(\x02\x12\x19\n\x11total_storage_mib\x18\x03 \x01(\x02\x12R\n\x0estorage_status\x18\x04 \x01(\x0e\x32:.mavsdk.rpc.camera_server.StorageInformation.StorageStatus\x12\x12\n\nstorage_id\x18\x05 \x01(\r\x12N\n\x0cstorage_type\x18\x06 \x01(\x0e\x32\x38.mavsdk.rpc.camera_server.StorageInformation.StorageType\x12\x18\n\x10read_speed_mib_s\x18\x07 \x01(\x02\x12\x19\n\x11write_speed_mib_s\x18\x08 \x01(\x02\"\x91\x01\n\rStorageStatus\x12 \n\x1cSTORAGE_STATUS_NOT_AVAILABLE\x10\x00\x12\x1e\n\x1aSTORAGE_STATUS_UNFORMATTED\x10\x01\x12\x1c\n\x18STORAGE_STATUS_FORMATTED\x10\x02\x12 \n\x1cSTORAGE_STATUS_NOT_SUPPORTED\x10\x03\"\xa0\x01\n\x0bStorageType\x12\x18\n\x14STORAGE_TYPE_UNKNOWN\x10\x00\x12\x1a\n\x16STORAGE_TYPE_USB_STICK\x10\x01\x12\x13\n\x0fSTORAGE_TYPE_SD\x10\x02\x12\x18\n\x14STORAGE_TYPE_MICROSD\x10\x03\x12\x13\n\x0fSTORAGE_TYPE_HD\x10\x07\x12\x17\n\x12STORAGE_TYPE_OTHER\x10\xfe\x01\"\xee\x03\n\rCaptureStatus\x12\x18\n\x10image_interval_s\x18\x01 \x01(\x02\x12\x18\n\x10recording_time_s\x18\x02 \x01(\x02\x12\x1e\n\x16\x61vailable_capacity_mib\x18\x03 \x01(\x02\x12I\n\x0cimage_status\x18\x04 \x01(\x0e\x32\x33.mavsdk.rpc.camera_server.CaptureStatus.ImageStatus\x12I\n\x0cvideo_status\x18\x05 \x01(\x0e\x32\x33.mavsdk.rpc.camera_server.CaptureStatus.VideoStatus\x12\x13\n\x0bimage_count\x18\x06 \x01(\x05\"\x91\x01\n\x0bImageStatus\x12\x15\n\x11IMAGE_STATUS_IDLE\x10\x00\x12$\n IMAGE_STATUS_CAPTURE_IN_PROGRESS\x10\x01\x12\x1e\n\x1aIMAGE_STATUS_INTERVAL_IDLE\x10\x02\x12%\n!IMAGE_STATUS_INTERVAL_IN_PROGRESS\x10\x03\"J\n\x0bVideoStatus\x12\x15\n\x11VIDEO_STATUS_IDLE\x10\x00\x12$\n VIDEO_STATUS_CAPTURE_IN_PROGRESS\x10\x01\"\\\n\x1dSetTrackingPointStatusRequest\x12;\n\rtracked_point\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.camera_server.TrackPoint\" \n\x1eSetTrackingPointStatusResponse\"h\n!SetTrackingRectangleStatusRequest\x12\x43\n\x11tracked_rectangle\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera_server.TrackRectangle\"$\n\"SetTrackingRectangleStatusResponse\"\x1d\n\x1bSetTrackingOffStatusRequest\"\x1e\n\x1cSetTrackingOffStatusResponse\"&\n$SubscribeTrackingPointCommandRequest\"Y\n\x1cTrackingPointCommandResponse\x12\x39\n\x0btrack_point\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.camera_server.TrackPoint\"*\n(SubscribeTrackingRectangleCommandRequest\"e\n TrackingRectangleCommandResponse\x12\x41\n\x0ftrack_rectangle\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera_server.TrackRectangle\"$\n\"SubscribeTrackingOffCommandRequest\"+\n\x1aTrackingOffCommandResponse\x12\r\n\x05\x64ummy\x18\x01 \x01(\x05\"k\n\"RespondTrackingPointCommandRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"q\n#RespondTrackingPointCommandResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"o\n&RespondTrackingRectangleCommandRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"u\n\'RespondTrackingRectangleCommandResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\"i\n RespondTrackingOffCommandRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\"o\n!RespondTrackingOffCommandResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult\">\n\nTrackPoint\x12\x0f\n\x07point_x\x18\x01 \x01(\x02\x12\x0f\n\x07point_y\x18\x02 \x01(\x02\x12\x0e\n\x06radius\x18\x03 \x01(\x02\"\x84\x01\n\x0eTrackRectangle\x12\x19\n\x11top_left_corner_x\x18\x01 \x01(\x02\x12\x19\n\x11top_left_corner_y\x18\x02 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_x\x18\x03 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_y\x18\x04 \x01(\x02*{\n\x0e\x43\x61meraFeedback\x12\x1b\n\x17\x43\x41MERA_FEEDBACK_UNKNOWN\x10\x00\x12\x16\n\x12\x43\x41MERA_FEEDBACK_OK\x10\x01\x12\x18\n\x14\x43\x41MERA_FEEDBACK_BUSY\x10\x02\x12\x1a\n\x16\x43\x41MERA_FEEDBACK_FAILED\x10\x03*8\n\x04Mode\x12\x10\n\x0cMODE_UNKNOWN\x10\x00\x12\x0e\n\nMODE_PHOTO\x10\x01\x12\x0e\n\nMODE_VIDEO\x10\x02\x32\xb8+\n\x13\x43\x61meraServerService\x12y\n\x0eSetInformation\x12/.mavsdk.rpc.camera_server.SetInformationRequest\x1a\x30.mavsdk.rpc.camera_server.SetInformationResponse\"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x11SetVideoStreaming\x12\x32.mavsdk.rpc.camera_server.SetVideoStreamingRequest\x1a\x33.mavsdk.rpc.camera_server.SetVideoStreamingResponse\"\x04\x80\xb5\x18\x01\x12v\n\rSetInProgress\x12..mavsdk.rpc.camera_server.SetInProgressRequest\x1a/.mavsdk.rpc.camera_server.SetInProgressResponse\"\x04\x80\xb5\x18\x01\x12~\n\x12SubscribeTakePhoto\x12\x33.mavsdk.rpc.camera_server.SubscribeTakePhotoRequest\x1a+.mavsdk.rpc.camera_server.TakePhotoResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x7f\n\x10RespondTakePhoto\x12\x31.mavsdk.rpc.camera_server.RespondTakePhotoRequest\x1a\x32.mavsdk.rpc.camera_server.RespondTakePhotoResponse\"\x04\x80\xb5\x18\x01\x12\x81\x01\n\x13SubscribeStartVideo\x12\x34.mavsdk.rpc.camera_server.SubscribeStartVideoRequest\x1a,.mavsdk.rpc.camera_server.StartVideoResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x82\x01\n\x11RespondStartVideo\x12\x32.mavsdk.rpc.camera_server.RespondStartVideoRequest\x1a\x33.mavsdk.rpc.camera_server.RespondStartVideoResponse\"\x04\x80\xb5\x18\x01\x12~\n\x12SubscribeStopVideo\x12\x33.mavsdk.rpc.camera_server.SubscribeStopVideoRequest\x1a+.mavsdk.rpc.camera_server.StopVideoResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x7f\n\x10RespondStopVideo\x12\x31.mavsdk.rpc.camera_server.RespondStopVideoRequest\x1a\x32.mavsdk.rpc.camera_server.RespondStopVideoResponse\"\x04\x80\xb5\x18\x01\x12\x9c\x01\n\x1cSubscribeStartVideoStreaming\x12=.mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest\x1a\x35.mavsdk.rpc.camera_server.StartVideoStreamingResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9d\x01\n\x1aRespondStartVideoStreaming\x12;.mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest\x1a<.mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse\"\x04\x80\xb5\x18\x01\x12\x99\x01\n\x1bSubscribeStopVideoStreaming\x12<.mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest\x1a\x34.mavsdk.rpc.camera_server.StopVideoStreamingResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9a\x01\n\x19RespondStopVideoStreaming\x12:.mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest\x1a;.mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse\"\x04\x80\xb5\x18\x01\x12x\n\x10SubscribeSetMode\x12\x31.mavsdk.rpc.camera_server.SubscribeSetModeRequest\x1a).mavsdk.rpc.camera_server.SetModeResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12y\n\x0eRespondSetMode\x12/.mavsdk.rpc.camera_server.RespondSetModeRequest\x1a\x30.mavsdk.rpc.camera_server.RespondSetModeResponse\"\x04\x80\xb5\x18\x01\x12\x99\x01\n\x1bSubscribeStorageInformation\x12<.mavsdk.rpc.camera_server.SubscribeStorageInformationRequest\x1a\x34.mavsdk.rpc.camera_server.StorageInformationResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9a\x01\n\x19RespondStorageInformation\x12:.mavsdk.rpc.camera_server.RespondStorageInformationRequest\x1a;.mavsdk.rpc.camera_server.RespondStorageInformationResponse\"\x04\x80\xb5\x18\x01\x12\x8a\x01\n\x16SubscribeCaptureStatus\x12\x37.mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest\x1a/.mavsdk.rpc.camera_server.CaptureStatusResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x8b\x01\n\x14RespondCaptureStatus\x12\x35.mavsdk.rpc.camera_server.RespondCaptureStatusRequest\x1a\x36.mavsdk.rpc.camera_server.RespondCaptureStatusResponse\"\x04\x80\xb5\x18\x01\x12\x8a\x01\n\x16SubscribeFormatStorage\x12\x37.mavsdk.rpc.camera_server.SubscribeFormatStorageRequest\x1a/.mavsdk.rpc.camera_server.FormatStorageResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x8b\x01\n\x14RespondFormatStorage\x12\x35.mavsdk.rpc.camera_server.RespondFormatStorageRequest\x1a\x36.mavsdk.rpc.camera_server.RespondFormatStorageResponse\"\x04\x80\xb5\x18\x01\x12\x8a\x01\n\x16SubscribeResetSettings\x12\x37.mavsdk.rpc.camera_server.SubscribeResetSettingsRequest\x1a/.mavsdk.rpc.camera_server.ResetSettingsResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x8b\x01\n\x14RespondResetSettings\x12\x35.mavsdk.rpc.camera_server.RespondResetSettingsRequest\x1a\x36.mavsdk.rpc.camera_server.RespondResetSettingsResponse\"\x04\x80\xb5\x18\x01\x12\x84\x01\n\x14SubscribeZoomInStart\x12\x35.mavsdk.rpc.camera_server.SubscribeZoomInStartRequest\x1a-.mavsdk.rpc.camera_server.ZoomInStartResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x85\x01\n\x12RespondZoomInStart\x12\x33.mavsdk.rpc.camera_server.RespondZoomInStartRequest\x1a\x34.mavsdk.rpc.camera_server.RespondZoomInStartResponse\"\x04\x80\xb5\x18\x01\x12\x87\x01\n\x15SubscribeZoomOutStart\x12\x36.mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest\x1a..mavsdk.rpc.camera_server.ZoomOutStartResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x88\x01\n\x13RespondZoomOutStart\x12\x34.mavsdk.rpc.camera_server.RespondZoomOutStartRequest\x1a\x35.mavsdk.rpc.camera_server.RespondZoomOutStartResponse\"\x04\x80\xb5\x18\x01\x12{\n\x11SubscribeZoomStop\x12\x32.mavsdk.rpc.camera_server.SubscribeZoomStopRequest\x1a*.mavsdk.rpc.camera_server.ZoomStopResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12|\n\x0fRespondZoomStop\x12\x30.mavsdk.rpc.camera_server.RespondZoomStopRequest\x1a\x31.mavsdk.rpc.camera_server.RespondZoomStopResponse\"\x04\x80\xb5\x18\x01\x12~\n\x12SubscribeZoomRange\x12\x33.mavsdk.rpc.camera_server.SubscribeZoomRangeRequest\x1a+.mavsdk.rpc.camera_server.ZoomRangeResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x7f\n\x10RespondZoomRange\x12\x31.mavsdk.rpc.camera_server.RespondZoomRangeRequest\x1a\x32.mavsdk.rpc.camera_server.RespondZoomRangeResponse\"\x04\x80\xb5\x18\x01\x12\x9d\x01\n\x1aSetTrackingRectangleStatus\x12;.mavsdk.rpc.camera_server.SetTrackingRectangleStatusRequest\x1a<.mavsdk.rpc.camera_server.SetTrackingRectangleStatusResponse\"\x04\x80\xb5\x18\x01\x12\x8b\x01\n\x14SetTrackingOffStatus\x12\x35.mavsdk.rpc.camera_server.SetTrackingOffStatusRequest\x1a\x36.mavsdk.rpc.camera_server.SetTrackingOffStatusResponse\"\x04\x80\xb5\x18\x01\x12\x9f\x01\n\x1dSubscribeTrackingPointCommand\x12>.mavsdk.rpc.camera_server.SubscribeTrackingPointCommandRequest\x1a\x36.mavsdk.rpc.camera_server.TrackingPointCommandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\xab\x01\n!SubscribeTrackingRectangleCommand\x12\x42.mavsdk.rpc.camera_server.SubscribeTrackingRectangleCommandRequest\x1a:.mavsdk.rpc.camera_server.TrackingRectangleCommandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x99\x01\n\x1bSubscribeTrackingOffCommand\x12<.mavsdk.rpc.camera_server.SubscribeTrackingOffCommandRequest\x1a\x34.mavsdk.rpc.camera_server.TrackingOffCommandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\xa0\x01\n\x1bRespondTrackingPointCommand\x12<.mavsdk.rpc.camera_server.RespondTrackingPointCommandRequest\x1a=.mavsdk.rpc.camera_server.RespondTrackingPointCommandResponse\"\x04\x80\xb5\x18\x01\x12\xac\x01\n\x1fRespondTrackingRectangleCommand\x12@.mavsdk.rpc.camera_server.RespondTrackingRectangleCommandRequest\x1a\x41.mavsdk.rpc.camera_server.RespondTrackingRectangleCommandResponse\"\x04\x80\xb5\x18\x01\x12\x9a\x01\n\x19RespondTrackingOffCommand\x12:.mavsdk.rpc.camera_server.RespondTrackingOffCommandRequest\x1a;.mavsdk.rpc.camera_server.RespondTrackingOffCommandResponse\"\x04\x80\xb5\x18\x01\x42,\n\x17io.mavsdk.camera_serverB\x11\x43\x61meraServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n!camera_server/camera_server.proto\x12\x18mavsdk.rpc.camera_server\x1a\x14mavsdk_options.proto"S\n\x15SetInformationRequest\x12:\n\x0binformation\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.camera_server.Information"d\n\x16SetInformationResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"]\n\x18SetVideoStreamingRequest\x12\x41\n\x0fvideo_streaming\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera_server.VideoStreaming"g\n\x19SetVideoStreamingResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"+\n\x14SetInProgressRequest\x12\x13\n\x0bin_progress\x18\x01 \x01(\x08"c\n\x15SetInProgressResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1b\n\x19SubscribeTakePhotoRequest""\n\x11TakePhotoResponse\x12\r\n\x05index\x18\x01 \x01(\x05"\x9d\x01\n\x17RespondTakePhotoRequest\x12\x45\n\x13take_photo_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\x12;\n\x0c\x63\x61pture_info\x18\x02 \x01(\x0b\x32%.mavsdk.rpc.camera_server.CaptureInfo"f\n\x18RespondTakePhotoResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1c\n\x1aSubscribeStartVideoRequest"\'\n\x12StartVideoResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05"b\n\x18RespondStartVideoRequest\x12\x46\n\x14start_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"g\n\x19RespondStartVideoResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1b\n\x19SubscribeStopVideoRequest"&\n\x11StopVideoResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05"`\n\x17RespondStopVideoRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"f\n\x18RespondStopVideoResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"%\n#SubscribeStartVideoStreamingRequest"0\n\x1bStartVideoStreamingResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05"u\n!RespondStartVideoStreamingRequest\x12P\n\x1estart_video_streaming_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"p\n"RespondStartVideoStreamingResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"$\n"SubscribeStopVideoStreamingRequest"/\n\x1aStopVideoStreamingResponse\x12\x11\n\tstream_id\x18\x01 \x01(\x05"s\n RespondStopVideoStreamingRequest\x12O\n\x1dstop_video_streaming_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"o\n!RespondStopVideoStreamingResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x19\n\x17SubscribeSetModeRequest"?\n\x0fSetModeResponse\x12,\n\x04mode\x18\x01 \x01(\x0e\x32\x1e.mavsdk.rpc.camera_server.Mode"\\\n\x15RespondSetModeRequest\x12\x43\n\x11set_mode_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"d\n\x16RespondSetModeResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"$\n"SubscribeStorageInformationRequest"0\n\x1aStorageInformationResponse\x12\x12\n\nstorage_id\x18\x01 \x01(\x05"\xbd\x01\n RespondStorageInformationRequest\x12N\n\x1cstorage_information_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\x12I\n\x13storage_information\x18\x02 \x01(\x0b\x32,.mavsdk.rpc.camera_server.StorageInformation"o\n!RespondStorageInformationResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1f\n\x1dSubscribeCaptureStatusRequest")\n\x15\x43\x61ptureStatusResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05"\xa9\x01\n\x1bRespondCaptureStatusRequest\x12I\n\x17\x63\x61pture_status_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback\x12?\n\x0e\x63\x61pture_status\x18\x02 \x01(\x0b\x32\'.mavsdk.rpc.camera_server.CaptureStatus"j\n\x1cRespondCaptureStatusResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1f\n\x1dSubscribeFormatStorageRequest"+\n\x15\x46ormatStorageResponse\x12\x12\n\nstorage_id\x18\x01 \x01(\x05"h\n\x1bRespondFormatStorageRequest\x12I\n\x17\x66ormat_storage_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"j\n\x1cRespondFormatStorageResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1f\n\x1dSubscribeResetSettingsRequest")\n\x15ResetSettingsResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05"h\n\x1bRespondResetSettingsRequest\x12I\n\x17reset_settings_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"j\n\x1cRespondResetSettingsResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1d\n\x1bSubscribeZoomInStartRequest"\'\n\x13ZoomInStartResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05"e\n\x19RespondZoomInStartRequest\x12H\n\x16zoom_in_start_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"h\n\x1aRespondZoomInStartResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1e\n\x1cSubscribeZoomOutStartRequest"(\n\x14ZoomOutStartResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05"g\n\x1aRespondZoomOutStartRequest\x12I\n\x17zoom_out_start_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"i\n\x1bRespondZoomOutStartResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1a\n\x18SubscribeZoomStopRequest"$\n\x10ZoomStopResponse\x12\x10\n\x08reserved\x18\x01 \x01(\x05"^\n\x16RespondZoomStopRequest\x12\x44\n\x12zoom_stop_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"e\n\x17RespondZoomStopResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x1b\n\x19SubscribeZoomRangeRequest"#\n\x11ZoomRangeResponse\x12\x0e\n\x06\x66\x61\x63tor\x18\x01 \x01(\x02"`\n\x17RespondZoomRangeRequest\x12\x45\n\x13zoom_range_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"f\n\x18RespondZoomRangeResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"\x8c\x03\n\x0bInformation\x12\x13\n\x0bvendor_name\x18\x01 \x01(\t\x12\x12\n\nmodel_name\x18\x02 \x01(\t\x12\x18\n\x10\x66irmware_version\x18\x03 \x01(\t\x12\x17\n\x0f\x66ocal_length_mm\x18\x04 \x01(\x02\x12!\n\x19horizontal_sensor_size_mm\x18\x05 \x01(\x02\x12\x1f\n\x17vertical_sensor_size_mm\x18\x06 \x01(\x02\x12 \n\x18horizontal_resolution_px\x18\x07 \x01(\r\x12\x1e\n\x16vertical_resolution_px\x18\x08 \x01(\r\x12\x0f\n\x07lens_id\x18\t \x01(\r\x12\x1f\n\x17\x64\x65\x66inition_file_version\x18\n \x01(\r\x12\x1b\n\x13\x64\x65\x66inition_file_uri\x18\x0b \x01(\t\x12%\n\x1dimage_in_video_mode_supported\x18\x0c \x01(\x08\x12%\n\x1dvideo_in_image_mode_supported\x18\r \x01(\x08";\n\x0eVideoStreaming\x12\x17\n\x0fhas_rtsp_server\x18\x01 \x01(\x08\x12\x10\n\x08rtsp_uri\x18\x02 \x01(\t"q\n\x08Position\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x12\x1b\n\x13relative_altitude_m\x18\x04 \x01(\x02"8\n\nQuaternion\x12\t\n\x01w\x18\x01 \x01(\x02\x12\t\n\x01x\x18\x02 \x01(\x02\x12\t\n\x01y\x18\x03 \x01(\x02\x12\t\n\x01z\x18\x04 \x01(\x02"\xd0\x01\n\x0b\x43\x61ptureInfo\x12\x34\n\x08position\x18\x01 \x01(\x0b\x32".mavsdk.rpc.camera_server.Position\x12\x41\n\x13\x61ttitude_quaternion\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.camera_server.Quaternion\x12\x13\n\x0btime_utc_us\x18\x03 \x01(\x04\x12\x12\n\nis_success\x18\x04 \x01(\x08\x12\r\n\x05index\x18\x05 \x01(\x05\x12\x10\n\x08\x66ile_url\x18\x06 \x01(\t"\xb3\x02\n\x12\x43\x61meraServerResult\x12\x43\n\x06result\x18\x01 \x01(\x0e\x32\x33.mavsdk.rpc.camera_server.CameraServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xc3\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x16\n\x12RESULT_IN_PROGRESS\x10\x02\x12\x0f\n\x0bRESULT_BUSY\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x10\n\x0cRESULT_ERROR\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x19\n\x15RESULT_WRONG_ARGUMENT\x10\x07\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x08"\x8c\x05\n\x12StorageInformation\x12\x18\n\x10used_storage_mib\x18\x01 \x01(\x02\x12\x1d\n\x15\x61vailable_storage_mib\x18\x02 \x01(\x02\x12\x19\n\x11total_storage_mib\x18\x03 \x01(\x02\x12R\n\x0estorage_status\x18\x04 \x01(\x0e\x32:.mavsdk.rpc.camera_server.StorageInformation.StorageStatus\x12\x12\n\nstorage_id\x18\x05 \x01(\r\x12N\n\x0cstorage_type\x18\x06 \x01(\x0e\x32\x38.mavsdk.rpc.camera_server.StorageInformation.StorageType\x12\x18\n\x10read_speed_mib_s\x18\x07 \x01(\x02\x12\x19\n\x11write_speed_mib_s\x18\x08 \x01(\x02"\x91\x01\n\rStorageStatus\x12 \n\x1cSTORAGE_STATUS_NOT_AVAILABLE\x10\x00\x12\x1e\n\x1aSTORAGE_STATUS_UNFORMATTED\x10\x01\x12\x1c\n\x18STORAGE_STATUS_FORMATTED\x10\x02\x12 \n\x1cSTORAGE_STATUS_NOT_SUPPORTED\x10\x03"\xa0\x01\n\x0bStorageType\x12\x18\n\x14STORAGE_TYPE_UNKNOWN\x10\x00\x12\x1a\n\x16STORAGE_TYPE_USB_STICK\x10\x01\x12\x13\n\x0fSTORAGE_TYPE_SD\x10\x02\x12\x18\n\x14STORAGE_TYPE_MICROSD\x10\x03\x12\x13\n\x0fSTORAGE_TYPE_HD\x10\x07\x12\x17\n\x12STORAGE_TYPE_OTHER\x10\xfe\x01"\xee\x03\n\rCaptureStatus\x12\x18\n\x10image_interval_s\x18\x01 \x01(\x02\x12\x18\n\x10recording_time_s\x18\x02 \x01(\x02\x12\x1e\n\x16\x61vailable_capacity_mib\x18\x03 \x01(\x02\x12I\n\x0cimage_status\x18\x04 \x01(\x0e\x32\x33.mavsdk.rpc.camera_server.CaptureStatus.ImageStatus\x12I\n\x0cvideo_status\x18\x05 \x01(\x0e\x32\x33.mavsdk.rpc.camera_server.CaptureStatus.VideoStatus\x12\x13\n\x0bimage_count\x18\x06 \x01(\x05"\x91\x01\n\x0bImageStatus\x12\x15\n\x11IMAGE_STATUS_IDLE\x10\x00\x12$\n IMAGE_STATUS_CAPTURE_IN_PROGRESS\x10\x01\x12\x1e\n\x1aIMAGE_STATUS_INTERVAL_IDLE\x10\x02\x12%\n!IMAGE_STATUS_INTERVAL_IN_PROGRESS\x10\x03"J\n\x0bVideoStatus\x12\x15\n\x11VIDEO_STATUS_IDLE\x10\x00\x12$\n VIDEO_STATUS_CAPTURE_IN_PROGRESS\x10\x01"\\\n\x1dSetTrackingPointStatusRequest\x12;\n\rtracked_point\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.camera_server.TrackPoint" \n\x1eSetTrackingPointStatusResponse"h\n!SetTrackingRectangleStatusRequest\x12\x43\n\x11tracked_rectangle\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera_server.TrackRectangle"$\n"SetTrackingRectangleStatusResponse"\x1d\n\x1bSetTrackingOffStatusRequest"\x1e\n\x1cSetTrackingOffStatusResponse"&\n$SubscribeTrackingPointCommandRequest"Y\n\x1cTrackingPointCommandResponse\x12\x39\n\x0btrack_point\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.camera_server.TrackPoint"*\n(SubscribeTrackingRectangleCommandRequest"e\n TrackingRectangleCommandResponse\x12\x41\n\x0ftrack_rectangle\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.camera_server.TrackRectangle"$\n"SubscribeTrackingOffCommandRequest"+\n\x1aTrackingOffCommandResponse\x12\r\n\x05\x64ummy\x18\x01 \x01(\x05"k\n"RespondTrackingPointCommandRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"q\n#RespondTrackingPointCommandResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"o\n&RespondTrackingRectangleCommandRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"u\n\'RespondTrackingRectangleCommandResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult"i\n RespondTrackingOffCommandRequest\x12\x45\n\x13stop_video_feedback\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.camera_server.CameraFeedback"o\n!RespondTrackingOffCommandResponse\x12J\n\x14\x63\x61mera_server_result\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.camera_server.CameraServerResult">\n\nTrackPoint\x12\x0f\n\x07point_x\x18\x01 \x01(\x02\x12\x0f\n\x07point_y\x18\x02 \x01(\x02\x12\x0e\n\x06radius\x18\x03 \x01(\x02"\x84\x01\n\x0eTrackRectangle\x12\x19\n\x11top_left_corner_x\x18\x01 \x01(\x02\x12\x19\n\x11top_left_corner_y\x18\x02 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_x\x18\x03 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_y\x18\x04 \x01(\x02*{\n\x0e\x43\x61meraFeedback\x12\x1b\n\x17\x43\x41MERA_FEEDBACK_UNKNOWN\x10\x00\x12\x16\n\x12\x43\x41MERA_FEEDBACK_OK\x10\x01\x12\x18\n\x14\x43\x41MERA_FEEDBACK_BUSY\x10\x02\x12\x1a\n\x16\x43\x41MERA_FEEDBACK_FAILED\x10\x03*8\n\x04Mode\x12\x10\n\x0cMODE_UNKNOWN\x10\x00\x12\x0e\n\nMODE_PHOTO\x10\x01\x12\x0e\n\nMODE_VIDEO\x10\x02\x32\xb8+\n\x13\x43\x61meraServerService\x12y\n\x0eSetInformation\x12/.mavsdk.rpc.camera_server.SetInformationRequest\x1a\x30.mavsdk.rpc.camera_server.SetInformationResponse"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x11SetVideoStreaming\x12\x32.mavsdk.rpc.camera_server.SetVideoStreamingRequest\x1a\x33.mavsdk.rpc.camera_server.SetVideoStreamingResponse"\x04\x80\xb5\x18\x01\x12v\n\rSetInProgress\x12..mavsdk.rpc.camera_server.SetInProgressRequest\x1a/.mavsdk.rpc.camera_server.SetInProgressResponse"\x04\x80\xb5\x18\x01\x12~\n\x12SubscribeTakePhoto\x12\x33.mavsdk.rpc.camera_server.SubscribeTakePhotoRequest\x1a+.mavsdk.rpc.camera_server.TakePhotoResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x7f\n\x10RespondTakePhoto\x12\x31.mavsdk.rpc.camera_server.RespondTakePhotoRequest\x1a\x32.mavsdk.rpc.camera_server.RespondTakePhotoResponse"\x04\x80\xb5\x18\x01\x12\x81\x01\n\x13SubscribeStartVideo\x12\x34.mavsdk.rpc.camera_server.SubscribeStartVideoRequest\x1a,.mavsdk.rpc.camera_server.StartVideoResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x82\x01\n\x11RespondStartVideo\x12\x32.mavsdk.rpc.camera_server.RespondStartVideoRequest\x1a\x33.mavsdk.rpc.camera_server.RespondStartVideoResponse"\x04\x80\xb5\x18\x01\x12~\n\x12SubscribeStopVideo\x12\x33.mavsdk.rpc.camera_server.SubscribeStopVideoRequest\x1a+.mavsdk.rpc.camera_server.StopVideoResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x7f\n\x10RespondStopVideo\x12\x31.mavsdk.rpc.camera_server.RespondStopVideoRequest\x1a\x32.mavsdk.rpc.camera_server.RespondStopVideoResponse"\x04\x80\xb5\x18\x01\x12\x9c\x01\n\x1cSubscribeStartVideoStreaming\x12=.mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest\x1a\x35.mavsdk.rpc.camera_server.StartVideoStreamingResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9d\x01\n\x1aRespondStartVideoStreaming\x12;.mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest\x1a<.mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse"\x04\x80\xb5\x18\x01\x12\x99\x01\n\x1bSubscribeStopVideoStreaming\x12<.mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest\x1a\x34.mavsdk.rpc.camera_server.StopVideoStreamingResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9a\x01\n\x19RespondStopVideoStreaming\x12:.mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest\x1a;.mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse"\x04\x80\xb5\x18\x01\x12x\n\x10SubscribeSetMode\x12\x31.mavsdk.rpc.camera_server.SubscribeSetModeRequest\x1a).mavsdk.rpc.camera_server.SetModeResponse"\x04\x80\xb5\x18\x00\x30\x01\x12y\n\x0eRespondSetMode\x12/.mavsdk.rpc.camera_server.RespondSetModeRequest\x1a\x30.mavsdk.rpc.camera_server.RespondSetModeResponse"\x04\x80\xb5\x18\x01\x12\x99\x01\n\x1bSubscribeStorageInformation\x12<.mavsdk.rpc.camera_server.SubscribeStorageInformationRequest\x1a\x34.mavsdk.rpc.camera_server.StorageInformationResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9a\x01\n\x19RespondStorageInformation\x12:.mavsdk.rpc.camera_server.RespondStorageInformationRequest\x1a;.mavsdk.rpc.camera_server.RespondStorageInformationResponse"\x04\x80\xb5\x18\x01\x12\x8a\x01\n\x16SubscribeCaptureStatus\x12\x37.mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest\x1a/.mavsdk.rpc.camera_server.CaptureStatusResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x8b\x01\n\x14RespondCaptureStatus\x12\x35.mavsdk.rpc.camera_server.RespondCaptureStatusRequest\x1a\x36.mavsdk.rpc.camera_server.RespondCaptureStatusResponse"\x04\x80\xb5\x18\x01\x12\x8a\x01\n\x16SubscribeFormatStorage\x12\x37.mavsdk.rpc.camera_server.SubscribeFormatStorageRequest\x1a/.mavsdk.rpc.camera_server.FormatStorageResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x8b\x01\n\x14RespondFormatStorage\x12\x35.mavsdk.rpc.camera_server.RespondFormatStorageRequest\x1a\x36.mavsdk.rpc.camera_server.RespondFormatStorageResponse"\x04\x80\xb5\x18\x01\x12\x8a\x01\n\x16SubscribeResetSettings\x12\x37.mavsdk.rpc.camera_server.SubscribeResetSettingsRequest\x1a/.mavsdk.rpc.camera_server.ResetSettingsResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x8b\x01\n\x14RespondResetSettings\x12\x35.mavsdk.rpc.camera_server.RespondResetSettingsRequest\x1a\x36.mavsdk.rpc.camera_server.RespondResetSettingsResponse"\x04\x80\xb5\x18\x01\x12\x84\x01\n\x14SubscribeZoomInStart\x12\x35.mavsdk.rpc.camera_server.SubscribeZoomInStartRequest\x1a-.mavsdk.rpc.camera_server.ZoomInStartResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x85\x01\n\x12RespondZoomInStart\x12\x33.mavsdk.rpc.camera_server.RespondZoomInStartRequest\x1a\x34.mavsdk.rpc.camera_server.RespondZoomInStartResponse"\x04\x80\xb5\x18\x01\x12\x87\x01\n\x15SubscribeZoomOutStart\x12\x36.mavsdk.rpc.camera_server.SubscribeZoomOutStartRequest\x1a..mavsdk.rpc.camera_server.ZoomOutStartResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x88\x01\n\x13RespondZoomOutStart\x12\x34.mavsdk.rpc.camera_server.RespondZoomOutStartRequest\x1a\x35.mavsdk.rpc.camera_server.RespondZoomOutStartResponse"\x04\x80\xb5\x18\x01\x12{\n\x11SubscribeZoomStop\x12\x32.mavsdk.rpc.camera_server.SubscribeZoomStopRequest\x1a*.mavsdk.rpc.camera_server.ZoomStopResponse"\x04\x80\xb5\x18\x00\x30\x01\x12|\n\x0fRespondZoomStop\x12\x30.mavsdk.rpc.camera_server.RespondZoomStopRequest\x1a\x31.mavsdk.rpc.camera_server.RespondZoomStopResponse"\x04\x80\xb5\x18\x01\x12~\n\x12SubscribeZoomRange\x12\x33.mavsdk.rpc.camera_server.SubscribeZoomRangeRequest\x1a+.mavsdk.rpc.camera_server.ZoomRangeResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x7f\n\x10RespondZoomRange\x12\x31.mavsdk.rpc.camera_server.RespondZoomRangeRequest\x1a\x32.mavsdk.rpc.camera_server.RespondZoomRangeResponse"\x04\x80\xb5\x18\x01\x12\x9d\x01\n\x1aSetTrackingRectangleStatus\x12;.mavsdk.rpc.camera_server.SetTrackingRectangleStatusRequest\x1a<.mavsdk.rpc.camera_server.SetTrackingRectangleStatusResponse"\x04\x80\xb5\x18\x01\x12\x8b\x01\n\x14SetTrackingOffStatus\x12\x35.mavsdk.rpc.camera_server.SetTrackingOffStatusRequest\x1a\x36.mavsdk.rpc.camera_server.SetTrackingOffStatusResponse"\x04\x80\xb5\x18\x01\x12\x9f\x01\n\x1dSubscribeTrackingPointCommand\x12>.mavsdk.rpc.camera_server.SubscribeTrackingPointCommandRequest\x1a\x36.mavsdk.rpc.camera_server.TrackingPointCommandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\xab\x01\n!SubscribeTrackingRectangleCommand\x12\x42.mavsdk.rpc.camera_server.SubscribeTrackingRectangleCommandRequest\x1a:.mavsdk.rpc.camera_server.TrackingRectangleCommandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x99\x01\n\x1bSubscribeTrackingOffCommand\x12<.mavsdk.rpc.camera_server.SubscribeTrackingOffCommandRequest\x1a\x34.mavsdk.rpc.camera_server.TrackingOffCommandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\xa0\x01\n\x1bRespondTrackingPointCommand\x12<.mavsdk.rpc.camera_server.RespondTrackingPointCommandRequest\x1a=.mavsdk.rpc.camera_server.RespondTrackingPointCommandResponse"\x04\x80\xb5\x18\x01\x12\xac\x01\n\x1fRespondTrackingRectangleCommand\x12@.mavsdk.rpc.camera_server.RespondTrackingRectangleCommandRequest\x1a\x41.mavsdk.rpc.camera_server.RespondTrackingRectangleCommandResponse"\x04\x80\xb5\x18\x01\x12\x9a\x01\n\x19RespondTrackingOffCommand\x12:.mavsdk.rpc.camera_server.RespondTrackingOffCommandRequest\x1a;.mavsdk.rpc.camera_server.RespondTrackingOffCommandResponse"\x04\x80\xb5\x18\x01\x42,\n\x17io.mavsdk.camera_serverB\x11\x43\x61meraServerProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'camera_server.camera_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "camera_server.camera_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\027io.mavsdk.camera_serverB\021CameraServerProto' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetInformation']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetInformation']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetVideoStreaming']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetVideoStreaming']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetInProgress']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetInProgress']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTakePhoto']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTakePhoto']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTakePhoto']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTakePhoto']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStartVideo']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStartVideo']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStartVideo']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStartVideo']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStopVideo']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStopVideo']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStopVideo']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStopVideo']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStartVideoStreaming']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStartVideoStreaming']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStartVideoStreaming']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStartVideoStreaming']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStopVideoStreaming']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStopVideoStreaming']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStopVideoStreaming']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStopVideoStreaming']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeSetMode']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeSetMode']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondSetMode']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondSetMode']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStorageInformation']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeStorageInformation']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStorageInformation']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondStorageInformation']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeCaptureStatus']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeCaptureStatus']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondCaptureStatus']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondCaptureStatus']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeFormatStorage']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeFormatStorage']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondFormatStorage']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondFormatStorage']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeResetSettings']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeResetSettings']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondResetSettings']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondResetSettings']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomInStart']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomInStart']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomInStart']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomInStart']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomOutStart']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomOutStart']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomOutStart']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomOutStart']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomStop']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomStop']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomStop']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomStop']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomRange']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeZoomRange']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomRange']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondZoomRange']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetTrackingRectangleStatus']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetTrackingRectangleStatus']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetTrackingOffStatus']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SetTrackingOffStatus']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTrackingPointCommand']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTrackingPointCommand']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTrackingRectangleCommand']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTrackingRectangleCommand']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTrackingOffCommand']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['SubscribeTrackingOffCommand']._serialized_options = b'\200\265\030\000' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTrackingPointCommand']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTrackingPointCommand']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTrackingRectangleCommand']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTrackingRectangleCommand']._serialized_options = b'\200\265\030\001' - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTrackingOffCommand']._loaded_options = None - _globals['_CAMERASERVERSERVICE'].methods_by_name['RespondTrackingOffCommand']._serialized_options = b'\200\265\030\001' - _globals['_CAMERAFEEDBACK']._serialized_start=8729 - _globals['_CAMERAFEEDBACK']._serialized_end=8852 - _globals['_MODE']._serialized_start=8854 - _globals['_MODE']._serialized_end=8910 - _globals['_SETINFORMATIONREQUEST']._serialized_start=85 - _globals['_SETINFORMATIONREQUEST']._serialized_end=168 - _globals['_SETINFORMATIONRESPONSE']._serialized_start=170 - _globals['_SETINFORMATIONRESPONSE']._serialized_end=270 - _globals['_SETVIDEOSTREAMINGREQUEST']._serialized_start=272 - _globals['_SETVIDEOSTREAMINGREQUEST']._serialized_end=365 - _globals['_SETVIDEOSTREAMINGRESPONSE']._serialized_start=367 - _globals['_SETVIDEOSTREAMINGRESPONSE']._serialized_end=470 - _globals['_SETINPROGRESSREQUEST']._serialized_start=472 - _globals['_SETINPROGRESSREQUEST']._serialized_end=515 - _globals['_SETINPROGRESSRESPONSE']._serialized_start=517 - _globals['_SETINPROGRESSRESPONSE']._serialized_end=616 - _globals['_SUBSCRIBETAKEPHOTOREQUEST']._serialized_start=618 - _globals['_SUBSCRIBETAKEPHOTOREQUEST']._serialized_end=645 - _globals['_TAKEPHOTORESPONSE']._serialized_start=647 - _globals['_TAKEPHOTORESPONSE']._serialized_end=681 - _globals['_RESPONDTAKEPHOTOREQUEST']._serialized_start=684 - _globals['_RESPONDTAKEPHOTOREQUEST']._serialized_end=841 - _globals['_RESPONDTAKEPHOTORESPONSE']._serialized_start=843 - _globals['_RESPONDTAKEPHOTORESPONSE']._serialized_end=945 - _globals['_SUBSCRIBESTARTVIDEOREQUEST']._serialized_start=947 - _globals['_SUBSCRIBESTARTVIDEOREQUEST']._serialized_end=975 - _globals['_STARTVIDEORESPONSE']._serialized_start=977 - _globals['_STARTVIDEORESPONSE']._serialized_end=1016 - _globals['_RESPONDSTARTVIDEOREQUEST']._serialized_start=1018 - _globals['_RESPONDSTARTVIDEOREQUEST']._serialized_end=1116 - _globals['_RESPONDSTARTVIDEORESPONSE']._serialized_start=1118 - _globals['_RESPONDSTARTVIDEORESPONSE']._serialized_end=1221 - _globals['_SUBSCRIBESTOPVIDEOREQUEST']._serialized_start=1223 - _globals['_SUBSCRIBESTOPVIDEOREQUEST']._serialized_end=1250 - _globals['_STOPVIDEORESPONSE']._serialized_start=1252 - _globals['_STOPVIDEORESPONSE']._serialized_end=1290 - _globals['_RESPONDSTOPVIDEOREQUEST']._serialized_start=1292 - _globals['_RESPONDSTOPVIDEOREQUEST']._serialized_end=1388 - _globals['_RESPONDSTOPVIDEORESPONSE']._serialized_start=1390 - _globals['_RESPONDSTOPVIDEORESPONSE']._serialized_end=1492 - _globals['_SUBSCRIBESTARTVIDEOSTREAMINGREQUEST']._serialized_start=1494 - _globals['_SUBSCRIBESTARTVIDEOSTREAMINGREQUEST']._serialized_end=1531 - _globals['_STARTVIDEOSTREAMINGRESPONSE']._serialized_start=1533 - _globals['_STARTVIDEOSTREAMINGRESPONSE']._serialized_end=1581 - _globals['_RESPONDSTARTVIDEOSTREAMINGREQUEST']._serialized_start=1583 - _globals['_RESPONDSTARTVIDEOSTREAMINGREQUEST']._serialized_end=1700 - _globals['_RESPONDSTARTVIDEOSTREAMINGRESPONSE']._serialized_start=1702 - _globals['_RESPONDSTARTVIDEOSTREAMINGRESPONSE']._serialized_end=1814 - _globals['_SUBSCRIBESTOPVIDEOSTREAMINGREQUEST']._serialized_start=1816 - _globals['_SUBSCRIBESTOPVIDEOSTREAMINGREQUEST']._serialized_end=1852 - _globals['_STOPVIDEOSTREAMINGRESPONSE']._serialized_start=1854 - _globals['_STOPVIDEOSTREAMINGRESPONSE']._serialized_end=1901 - _globals['_RESPONDSTOPVIDEOSTREAMINGREQUEST']._serialized_start=1903 - _globals['_RESPONDSTOPVIDEOSTREAMINGREQUEST']._serialized_end=2018 - _globals['_RESPONDSTOPVIDEOSTREAMINGRESPONSE']._serialized_start=2020 - _globals['_RESPONDSTOPVIDEOSTREAMINGRESPONSE']._serialized_end=2131 - _globals['_SUBSCRIBESETMODEREQUEST']._serialized_start=2133 - _globals['_SUBSCRIBESETMODEREQUEST']._serialized_end=2158 - _globals['_SETMODERESPONSE']._serialized_start=2160 - _globals['_SETMODERESPONSE']._serialized_end=2223 - _globals['_RESPONDSETMODEREQUEST']._serialized_start=2225 - _globals['_RESPONDSETMODEREQUEST']._serialized_end=2317 - _globals['_RESPONDSETMODERESPONSE']._serialized_start=2319 - _globals['_RESPONDSETMODERESPONSE']._serialized_end=2419 - _globals['_SUBSCRIBESTORAGEINFORMATIONREQUEST']._serialized_start=2421 - _globals['_SUBSCRIBESTORAGEINFORMATIONREQUEST']._serialized_end=2457 - _globals['_STORAGEINFORMATIONRESPONSE']._serialized_start=2459 - _globals['_STORAGEINFORMATIONRESPONSE']._serialized_end=2507 - _globals['_RESPONDSTORAGEINFORMATIONREQUEST']._serialized_start=2510 - _globals['_RESPONDSTORAGEINFORMATIONREQUEST']._serialized_end=2699 - _globals['_RESPONDSTORAGEINFORMATIONRESPONSE']._serialized_start=2701 - _globals['_RESPONDSTORAGEINFORMATIONRESPONSE']._serialized_end=2812 - _globals['_SUBSCRIBECAPTURESTATUSREQUEST']._serialized_start=2814 - _globals['_SUBSCRIBECAPTURESTATUSREQUEST']._serialized_end=2845 - _globals['_CAPTURESTATUSRESPONSE']._serialized_start=2847 - _globals['_CAPTURESTATUSRESPONSE']._serialized_end=2888 - _globals['_RESPONDCAPTURESTATUSREQUEST']._serialized_start=2891 - _globals['_RESPONDCAPTURESTATUSREQUEST']._serialized_end=3060 - _globals['_RESPONDCAPTURESTATUSRESPONSE']._serialized_start=3062 - _globals['_RESPONDCAPTURESTATUSRESPONSE']._serialized_end=3168 - _globals['_SUBSCRIBEFORMATSTORAGEREQUEST']._serialized_start=3170 - _globals['_SUBSCRIBEFORMATSTORAGEREQUEST']._serialized_end=3201 - _globals['_FORMATSTORAGERESPONSE']._serialized_start=3203 - _globals['_FORMATSTORAGERESPONSE']._serialized_end=3246 - _globals['_RESPONDFORMATSTORAGEREQUEST']._serialized_start=3248 - _globals['_RESPONDFORMATSTORAGEREQUEST']._serialized_end=3352 - _globals['_RESPONDFORMATSTORAGERESPONSE']._serialized_start=3354 - _globals['_RESPONDFORMATSTORAGERESPONSE']._serialized_end=3460 - _globals['_SUBSCRIBERESETSETTINGSREQUEST']._serialized_start=3462 - _globals['_SUBSCRIBERESETSETTINGSREQUEST']._serialized_end=3493 - _globals['_RESETSETTINGSRESPONSE']._serialized_start=3495 - _globals['_RESETSETTINGSRESPONSE']._serialized_end=3536 - _globals['_RESPONDRESETSETTINGSREQUEST']._serialized_start=3538 - _globals['_RESPONDRESETSETTINGSREQUEST']._serialized_end=3642 - _globals['_RESPONDRESETSETTINGSRESPONSE']._serialized_start=3644 - _globals['_RESPONDRESETSETTINGSRESPONSE']._serialized_end=3750 - _globals['_SUBSCRIBEZOOMINSTARTREQUEST']._serialized_start=3752 - _globals['_SUBSCRIBEZOOMINSTARTREQUEST']._serialized_end=3781 - _globals['_ZOOMINSTARTRESPONSE']._serialized_start=3783 - _globals['_ZOOMINSTARTRESPONSE']._serialized_end=3822 - _globals['_RESPONDZOOMINSTARTREQUEST']._serialized_start=3824 - _globals['_RESPONDZOOMINSTARTREQUEST']._serialized_end=3925 - _globals['_RESPONDZOOMINSTARTRESPONSE']._serialized_start=3927 - _globals['_RESPONDZOOMINSTARTRESPONSE']._serialized_end=4031 - _globals['_SUBSCRIBEZOOMOUTSTARTREQUEST']._serialized_start=4033 - _globals['_SUBSCRIBEZOOMOUTSTARTREQUEST']._serialized_end=4063 - _globals['_ZOOMOUTSTARTRESPONSE']._serialized_start=4065 - _globals['_ZOOMOUTSTARTRESPONSE']._serialized_end=4105 - _globals['_RESPONDZOOMOUTSTARTREQUEST']._serialized_start=4107 - _globals['_RESPONDZOOMOUTSTARTREQUEST']._serialized_end=4210 - _globals['_RESPONDZOOMOUTSTARTRESPONSE']._serialized_start=4212 - _globals['_RESPONDZOOMOUTSTARTRESPONSE']._serialized_end=4317 - _globals['_SUBSCRIBEZOOMSTOPREQUEST']._serialized_start=4319 - _globals['_SUBSCRIBEZOOMSTOPREQUEST']._serialized_end=4345 - _globals['_ZOOMSTOPRESPONSE']._serialized_start=4347 - _globals['_ZOOMSTOPRESPONSE']._serialized_end=4383 - _globals['_RESPONDZOOMSTOPREQUEST']._serialized_start=4385 - _globals['_RESPONDZOOMSTOPREQUEST']._serialized_end=4479 - _globals['_RESPONDZOOMSTOPRESPONSE']._serialized_start=4481 - _globals['_RESPONDZOOMSTOPRESPONSE']._serialized_end=4582 - _globals['_SUBSCRIBEZOOMRANGEREQUEST']._serialized_start=4584 - _globals['_SUBSCRIBEZOOMRANGEREQUEST']._serialized_end=4611 - _globals['_ZOOMRANGERESPONSE']._serialized_start=4613 - _globals['_ZOOMRANGERESPONSE']._serialized_end=4648 - _globals['_RESPONDZOOMRANGEREQUEST']._serialized_start=4650 - _globals['_RESPONDZOOMRANGEREQUEST']._serialized_end=4746 - _globals['_RESPONDZOOMRANGERESPONSE']._serialized_start=4748 - _globals['_RESPONDZOOMRANGERESPONSE']._serialized_end=4850 - _globals['_INFORMATION']._serialized_start=4853 - _globals['_INFORMATION']._serialized_end=5249 - _globals['_VIDEOSTREAMING']._serialized_start=5251 - _globals['_VIDEOSTREAMING']._serialized_end=5310 - _globals['_POSITION']._serialized_start=5312 - _globals['_POSITION']._serialized_end=5425 - _globals['_QUATERNION']._serialized_start=5427 - _globals['_QUATERNION']._serialized_end=5483 - _globals['_CAPTUREINFO']._serialized_start=5486 - _globals['_CAPTUREINFO']._serialized_end=5694 - _globals['_CAMERASERVERRESULT']._serialized_start=5697 - _globals['_CAMERASERVERRESULT']._serialized_end=6004 - _globals['_CAMERASERVERRESULT_RESULT']._serialized_start=5809 - _globals['_CAMERASERVERRESULT_RESULT']._serialized_end=6004 - _globals['_STORAGEINFORMATION']._serialized_start=6007 - _globals['_STORAGEINFORMATION']._serialized_end=6659 - _globals['_STORAGEINFORMATION_STORAGESTATUS']._serialized_start=6351 - _globals['_STORAGEINFORMATION_STORAGESTATUS']._serialized_end=6496 - _globals['_STORAGEINFORMATION_STORAGETYPE']._serialized_start=6499 - _globals['_STORAGEINFORMATION_STORAGETYPE']._serialized_end=6659 - _globals['_CAPTURESTATUS']._serialized_start=6662 - _globals['_CAPTURESTATUS']._serialized_end=7156 - _globals['_CAPTURESTATUS_IMAGESTATUS']._serialized_start=6935 - _globals['_CAPTURESTATUS_IMAGESTATUS']._serialized_end=7080 - _globals['_CAPTURESTATUS_VIDEOSTATUS']._serialized_start=7082 - _globals['_CAPTURESTATUS_VIDEOSTATUS']._serialized_end=7156 - _globals['_SETTRACKINGPOINTSTATUSREQUEST']._serialized_start=7158 - _globals['_SETTRACKINGPOINTSTATUSREQUEST']._serialized_end=7250 - _globals['_SETTRACKINGPOINTSTATUSRESPONSE']._serialized_start=7252 - _globals['_SETTRACKINGPOINTSTATUSRESPONSE']._serialized_end=7284 - _globals['_SETTRACKINGRECTANGLESTATUSREQUEST']._serialized_start=7286 - _globals['_SETTRACKINGRECTANGLESTATUSREQUEST']._serialized_end=7390 - _globals['_SETTRACKINGRECTANGLESTATUSRESPONSE']._serialized_start=7392 - _globals['_SETTRACKINGRECTANGLESTATUSRESPONSE']._serialized_end=7428 - _globals['_SETTRACKINGOFFSTATUSREQUEST']._serialized_start=7430 - _globals['_SETTRACKINGOFFSTATUSREQUEST']._serialized_end=7459 - _globals['_SETTRACKINGOFFSTATUSRESPONSE']._serialized_start=7461 - _globals['_SETTRACKINGOFFSTATUSRESPONSE']._serialized_end=7491 - _globals['_SUBSCRIBETRACKINGPOINTCOMMANDREQUEST']._serialized_start=7493 - _globals['_SUBSCRIBETRACKINGPOINTCOMMANDREQUEST']._serialized_end=7531 - _globals['_TRACKINGPOINTCOMMANDRESPONSE']._serialized_start=7533 - _globals['_TRACKINGPOINTCOMMANDRESPONSE']._serialized_end=7622 - _globals['_SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST']._serialized_start=7624 - _globals['_SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST']._serialized_end=7666 - _globals['_TRACKINGRECTANGLECOMMANDRESPONSE']._serialized_start=7668 - _globals['_TRACKINGRECTANGLECOMMANDRESPONSE']._serialized_end=7769 - _globals['_SUBSCRIBETRACKINGOFFCOMMANDREQUEST']._serialized_start=7771 - _globals['_SUBSCRIBETRACKINGOFFCOMMANDREQUEST']._serialized_end=7807 - _globals['_TRACKINGOFFCOMMANDRESPONSE']._serialized_start=7809 - _globals['_TRACKINGOFFCOMMANDRESPONSE']._serialized_end=7852 - _globals['_RESPONDTRACKINGPOINTCOMMANDREQUEST']._serialized_start=7854 - _globals['_RESPONDTRACKINGPOINTCOMMANDREQUEST']._serialized_end=7961 - _globals['_RESPONDTRACKINGPOINTCOMMANDRESPONSE']._serialized_start=7963 - _globals['_RESPONDTRACKINGPOINTCOMMANDRESPONSE']._serialized_end=8076 - _globals['_RESPONDTRACKINGRECTANGLECOMMANDREQUEST']._serialized_start=8078 - _globals['_RESPONDTRACKINGRECTANGLECOMMANDREQUEST']._serialized_end=8189 - _globals['_RESPONDTRACKINGRECTANGLECOMMANDRESPONSE']._serialized_start=8191 - _globals['_RESPONDTRACKINGRECTANGLECOMMANDRESPONSE']._serialized_end=8308 - _globals['_RESPONDTRACKINGOFFCOMMANDREQUEST']._serialized_start=8310 - _globals['_RESPONDTRACKINGOFFCOMMANDREQUEST']._serialized_end=8415 - _globals['_RESPONDTRACKINGOFFCOMMANDRESPONSE']._serialized_start=8417 - _globals['_RESPONDTRACKINGOFFCOMMANDRESPONSE']._serialized_end=8528 - _globals['_TRACKPOINT']._serialized_start=8530 - _globals['_TRACKPOINT']._serialized_end=8592 - _globals['_TRACKRECTANGLE']._serialized_start=8595 - _globals['_TRACKRECTANGLE']._serialized_end=8727 - _globals['_CAMERASERVERSERVICE']._serialized_start=8913 - _globals['_CAMERASERVERSERVICE']._serialized_end=14473 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\027io.mavsdk.camera_serverB\021CameraServerProto" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetInformation" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetInformation" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetVideoStreaming" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetInProgress" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetInProgress" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTakePhoto" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTakePhoto" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTakePhoto" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTakePhoto" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStartVideo" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStartVideo" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStartVideo" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStartVideo" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStopVideo" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStopVideo" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStopVideo" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStopVideo" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStartVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStartVideoStreaming" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStartVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStartVideoStreaming" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStopVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStopVideoStreaming" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStopVideoStreaming" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStopVideoStreaming" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeSetMode" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeSetMode" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondSetMode" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondSetMode" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStorageInformation" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeStorageInformation" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStorageInformation" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondStorageInformation" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeCaptureStatus" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeCaptureStatus" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondCaptureStatus" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondCaptureStatus" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeFormatStorage" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeFormatStorage" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondFormatStorage" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondFormatStorage" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeResetSettings" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeResetSettings" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondResetSettings" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondResetSettings" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomInStart" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomInStart" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomInStart" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomInStart" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomOutStart" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomOutStart" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomOutStart" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomOutStart" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomStop" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomStop" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomStop" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomStop" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomRange" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeZoomRange" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomRange" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondZoomRange" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetTrackingRectangleStatus" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetTrackingRectangleStatus" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetTrackingOffStatus" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SetTrackingOffStatus" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTrackingPointCommand" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTrackingPointCommand" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTrackingRectangleCommand" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTrackingRectangleCommand" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTrackingOffCommand" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "SubscribeTrackingOffCommand" + ]._serialized_options = b"\200\265\030\000" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTrackingPointCommand" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTrackingPointCommand" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTrackingRectangleCommand" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTrackingRectangleCommand" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTrackingOffCommand" + ]._loaded_options = None + _globals["_CAMERASERVERSERVICE"].methods_by_name[ + "RespondTrackingOffCommand" + ]._serialized_options = b"\200\265\030\001" + _globals["_CAMERAFEEDBACK"]._serialized_start = 8729 + _globals["_CAMERAFEEDBACK"]._serialized_end = 8852 + _globals["_MODE"]._serialized_start = 8854 + _globals["_MODE"]._serialized_end = 8910 + _globals["_SETINFORMATIONREQUEST"]._serialized_start = 85 + _globals["_SETINFORMATIONREQUEST"]._serialized_end = 168 + _globals["_SETINFORMATIONRESPONSE"]._serialized_start = 170 + _globals["_SETINFORMATIONRESPONSE"]._serialized_end = 270 + _globals["_SETVIDEOSTREAMINGREQUEST"]._serialized_start = 272 + _globals["_SETVIDEOSTREAMINGREQUEST"]._serialized_end = 365 + _globals["_SETVIDEOSTREAMINGRESPONSE"]._serialized_start = 367 + _globals["_SETVIDEOSTREAMINGRESPONSE"]._serialized_end = 470 + _globals["_SETINPROGRESSREQUEST"]._serialized_start = 472 + _globals["_SETINPROGRESSREQUEST"]._serialized_end = 515 + _globals["_SETINPROGRESSRESPONSE"]._serialized_start = 517 + _globals["_SETINPROGRESSRESPONSE"]._serialized_end = 616 + _globals["_SUBSCRIBETAKEPHOTOREQUEST"]._serialized_start = 618 + _globals["_SUBSCRIBETAKEPHOTOREQUEST"]._serialized_end = 645 + _globals["_TAKEPHOTORESPONSE"]._serialized_start = 647 + _globals["_TAKEPHOTORESPONSE"]._serialized_end = 681 + _globals["_RESPONDTAKEPHOTOREQUEST"]._serialized_start = 684 + _globals["_RESPONDTAKEPHOTOREQUEST"]._serialized_end = 841 + _globals["_RESPONDTAKEPHOTORESPONSE"]._serialized_start = 843 + _globals["_RESPONDTAKEPHOTORESPONSE"]._serialized_end = 945 + _globals["_SUBSCRIBESTARTVIDEOREQUEST"]._serialized_start = 947 + _globals["_SUBSCRIBESTARTVIDEOREQUEST"]._serialized_end = 975 + _globals["_STARTVIDEORESPONSE"]._serialized_start = 977 + _globals["_STARTVIDEORESPONSE"]._serialized_end = 1016 + _globals["_RESPONDSTARTVIDEOREQUEST"]._serialized_start = 1018 + _globals["_RESPONDSTARTVIDEOREQUEST"]._serialized_end = 1116 + _globals["_RESPONDSTARTVIDEORESPONSE"]._serialized_start = 1118 + _globals["_RESPONDSTARTVIDEORESPONSE"]._serialized_end = 1221 + _globals["_SUBSCRIBESTOPVIDEOREQUEST"]._serialized_start = 1223 + _globals["_SUBSCRIBESTOPVIDEOREQUEST"]._serialized_end = 1250 + _globals["_STOPVIDEORESPONSE"]._serialized_start = 1252 + _globals["_STOPVIDEORESPONSE"]._serialized_end = 1290 + _globals["_RESPONDSTOPVIDEOREQUEST"]._serialized_start = 1292 + _globals["_RESPONDSTOPVIDEOREQUEST"]._serialized_end = 1388 + _globals["_RESPONDSTOPVIDEORESPONSE"]._serialized_start = 1390 + _globals["_RESPONDSTOPVIDEORESPONSE"]._serialized_end = 1492 + _globals["_SUBSCRIBESTARTVIDEOSTREAMINGREQUEST"]._serialized_start = 1494 + _globals["_SUBSCRIBESTARTVIDEOSTREAMINGREQUEST"]._serialized_end = 1531 + _globals["_STARTVIDEOSTREAMINGRESPONSE"]._serialized_start = 1533 + _globals["_STARTVIDEOSTREAMINGRESPONSE"]._serialized_end = 1581 + _globals["_RESPONDSTARTVIDEOSTREAMINGREQUEST"]._serialized_start = 1583 + _globals["_RESPONDSTARTVIDEOSTREAMINGREQUEST"]._serialized_end = 1700 + _globals["_RESPONDSTARTVIDEOSTREAMINGRESPONSE"]._serialized_start = 1702 + _globals["_RESPONDSTARTVIDEOSTREAMINGRESPONSE"]._serialized_end = 1814 + _globals["_SUBSCRIBESTOPVIDEOSTREAMINGREQUEST"]._serialized_start = 1816 + _globals["_SUBSCRIBESTOPVIDEOSTREAMINGREQUEST"]._serialized_end = 1852 + _globals["_STOPVIDEOSTREAMINGRESPONSE"]._serialized_start = 1854 + _globals["_STOPVIDEOSTREAMINGRESPONSE"]._serialized_end = 1901 + _globals["_RESPONDSTOPVIDEOSTREAMINGREQUEST"]._serialized_start = 1903 + _globals["_RESPONDSTOPVIDEOSTREAMINGREQUEST"]._serialized_end = 2018 + _globals["_RESPONDSTOPVIDEOSTREAMINGRESPONSE"]._serialized_start = 2020 + _globals["_RESPONDSTOPVIDEOSTREAMINGRESPONSE"]._serialized_end = 2131 + _globals["_SUBSCRIBESETMODEREQUEST"]._serialized_start = 2133 + _globals["_SUBSCRIBESETMODEREQUEST"]._serialized_end = 2158 + _globals["_SETMODERESPONSE"]._serialized_start = 2160 + _globals["_SETMODERESPONSE"]._serialized_end = 2223 + _globals["_RESPONDSETMODEREQUEST"]._serialized_start = 2225 + _globals["_RESPONDSETMODEREQUEST"]._serialized_end = 2317 + _globals["_RESPONDSETMODERESPONSE"]._serialized_start = 2319 + _globals["_RESPONDSETMODERESPONSE"]._serialized_end = 2419 + _globals["_SUBSCRIBESTORAGEINFORMATIONREQUEST"]._serialized_start = 2421 + _globals["_SUBSCRIBESTORAGEINFORMATIONREQUEST"]._serialized_end = 2457 + _globals["_STORAGEINFORMATIONRESPONSE"]._serialized_start = 2459 + _globals["_STORAGEINFORMATIONRESPONSE"]._serialized_end = 2507 + _globals["_RESPONDSTORAGEINFORMATIONREQUEST"]._serialized_start = 2510 + _globals["_RESPONDSTORAGEINFORMATIONREQUEST"]._serialized_end = 2699 + _globals["_RESPONDSTORAGEINFORMATIONRESPONSE"]._serialized_start = 2701 + _globals["_RESPONDSTORAGEINFORMATIONRESPONSE"]._serialized_end = 2812 + _globals["_SUBSCRIBECAPTURESTATUSREQUEST"]._serialized_start = 2814 + _globals["_SUBSCRIBECAPTURESTATUSREQUEST"]._serialized_end = 2845 + _globals["_CAPTURESTATUSRESPONSE"]._serialized_start = 2847 + _globals["_CAPTURESTATUSRESPONSE"]._serialized_end = 2888 + _globals["_RESPONDCAPTURESTATUSREQUEST"]._serialized_start = 2891 + _globals["_RESPONDCAPTURESTATUSREQUEST"]._serialized_end = 3060 + _globals["_RESPONDCAPTURESTATUSRESPONSE"]._serialized_start = 3062 + _globals["_RESPONDCAPTURESTATUSRESPONSE"]._serialized_end = 3168 + _globals["_SUBSCRIBEFORMATSTORAGEREQUEST"]._serialized_start = 3170 + _globals["_SUBSCRIBEFORMATSTORAGEREQUEST"]._serialized_end = 3201 + _globals["_FORMATSTORAGERESPONSE"]._serialized_start = 3203 + _globals["_FORMATSTORAGERESPONSE"]._serialized_end = 3246 + _globals["_RESPONDFORMATSTORAGEREQUEST"]._serialized_start = 3248 + _globals["_RESPONDFORMATSTORAGEREQUEST"]._serialized_end = 3352 + _globals["_RESPONDFORMATSTORAGERESPONSE"]._serialized_start = 3354 + _globals["_RESPONDFORMATSTORAGERESPONSE"]._serialized_end = 3460 + _globals["_SUBSCRIBERESETSETTINGSREQUEST"]._serialized_start = 3462 + _globals["_SUBSCRIBERESETSETTINGSREQUEST"]._serialized_end = 3493 + _globals["_RESETSETTINGSRESPONSE"]._serialized_start = 3495 + _globals["_RESETSETTINGSRESPONSE"]._serialized_end = 3536 + _globals["_RESPONDRESETSETTINGSREQUEST"]._serialized_start = 3538 + _globals["_RESPONDRESETSETTINGSREQUEST"]._serialized_end = 3642 + _globals["_RESPONDRESETSETTINGSRESPONSE"]._serialized_start = 3644 + _globals["_RESPONDRESETSETTINGSRESPONSE"]._serialized_end = 3750 + _globals["_SUBSCRIBEZOOMINSTARTREQUEST"]._serialized_start = 3752 + _globals["_SUBSCRIBEZOOMINSTARTREQUEST"]._serialized_end = 3781 + _globals["_ZOOMINSTARTRESPONSE"]._serialized_start = 3783 + _globals["_ZOOMINSTARTRESPONSE"]._serialized_end = 3822 + _globals["_RESPONDZOOMINSTARTREQUEST"]._serialized_start = 3824 + _globals["_RESPONDZOOMINSTARTREQUEST"]._serialized_end = 3925 + _globals["_RESPONDZOOMINSTARTRESPONSE"]._serialized_start = 3927 + _globals["_RESPONDZOOMINSTARTRESPONSE"]._serialized_end = 4031 + _globals["_SUBSCRIBEZOOMOUTSTARTREQUEST"]._serialized_start = 4033 + _globals["_SUBSCRIBEZOOMOUTSTARTREQUEST"]._serialized_end = 4063 + _globals["_ZOOMOUTSTARTRESPONSE"]._serialized_start = 4065 + _globals["_ZOOMOUTSTARTRESPONSE"]._serialized_end = 4105 + _globals["_RESPONDZOOMOUTSTARTREQUEST"]._serialized_start = 4107 + _globals["_RESPONDZOOMOUTSTARTREQUEST"]._serialized_end = 4210 + _globals["_RESPONDZOOMOUTSTARTRESPONSE"]._serialized_start = 4212 + _globals["_RESPONDZOOMOUTSTARTRESPONSE"]._serialized_end = 4317 + _globals["_SUBSCRIBEZOOMSTOPREQUEST"]._serialized_start = 4319 + _globals["_SUBSCRIBEZOOMSTOPREQUEST"]._serialized_end = 4345 + _globals["_ZOOMSTOPRESPONSE"]._serialized_start = 4347 + _globals["_ZOOMSTOPRESPONSE"]._serialized_end = 4383 + _globals["_RESPONDZOOMSTOPREQUEST"]._serialized_start = 4385 + _globals["_RESPONDZOOMSTOPREQUEST"]._serialized_end = 4479 + _globals["_RESPONDZOOMSTOPRESPONSE"]._serialized_start = 4481 + _globals["_RESPONDZOOMSTOPRESPONSE"]._serialized_end = 4582 + _globals["_SUBSCRIBEZOOMRANGEREQUEST"]._serialized_start = 4584 + _globals["_SUBSCRIBEZOOMRANGEREQUEST"]._serialized_end = 4611 + _globals["_ZOOMRANGERESPONSE"]._serialized_start = 4613 + _globals["_ZOOMRANGERESPONSE"]._serialized_end = 4648 + _globals["_RESPONDZOOMRANGEREQUEST"]._serialized_start = 4650 + _globals["_RESPONDZOOMRANGEREQUEST"]._serialized_end = 4746 + _globals["_RESPONDZOOMRANGERESPONSE"]._serialized_start = 4748 + _globals["_RESPONDZOOMRANGERESPONSE"]._serialized_end = 4850 + _globals["_INFORMATION"]._serialized_start = 4853 + _globals["_INFORMATION"]._serialized_end = 5249 + _globals["_VIDEOSTREAMING"]._serialized_start = 5251 + _globals["_VIDEOSTREAMING"]._serialized_end = 5310 + _globals["_POSITION"]._serialized_start = 5312 + _globals["_POSITION"]._serialized_end = 5425 + _globals["_QUATERNION"]._serialized_start = 5427 + _globals["_QUATERNION"]._serialized_end = 5483 + _globals["_CAPTUREINFO"]._serialized_start = 5486 + _globals["_CAPTUREINFO"]._serialized_end = 5694 + _globals["_CAMERASERVERRESULT"]._serialized_start = 5697 + _globals["_CAMERASERVERRESULT"]._serialized_end = 6004 + _globals["_CAMERASERVERRESULT_RESULT"]._serialized_start = 5809 + _globals["_CAMERASERVERRESULT_RESULT"]._serialized_end = 6004 + _globals["_STORAGEINFORMATION"]._serialized_start = 6007 + _globals["_STORAGEINFORMATION"]._serialized_end = 6659 + _globals["_STORAGEINFORMATION_STORAGESTATUS"]._serialized_start = 6351 + _globals["_STORAGEINFORMATION_STORAGESTATUS"]._serialized_end = 6496 + _globals["_STORAGEINFORMATION_STORAGETYPE"]._serialized_start = 6499 + _globals["_STORAGEINFORMATION_STORAGETYPE"]._serialized_end = 6659 + _globals["_CAPTURESTATUS"]._serialized_start = 6662 + _globals["_CAPTURESTATUS"]._serialized_end = 7156 + _globals["_CAPTURESTATUS_IMAGESTATUS"]._serialized_start = 6935 + _globals["_CAPTURESTATUS_IMAGESTATUS"]._serialized_end = 7080 + _globals["_CAPTURESTATUS_VIDEOSTATUS"]._serialized_start = 7082 + _globals["_CAPTURESTATUS_VIDEOSTATUS"]._serialized_end = 7156 + _globals["_SETTRACKINGPOINTSTATUSREQUEST"]._serialized_start = 7158 + _globals["_SETTRACKINGPOINTSTATUSREQUEST"]._serialized_end = 7250 + _globals["_SETTRACKINGPOINTSTATUSRESPONSE"]._serialized_start = 7252 + _globals["_SETTRACKINGPOINTSTATUSRESPONSE"]._serialized_end = 7284 + _globals["_SETTRACKINGRECTANGLESTATUSREQUEST"]._serialized_start = 7286 + _globals["_SETTRACKINGRECTANGLESTATUSREQUEST"]._serialized_end = 7390 + _globals["_SETTRACKINGRECTANGLESTATUSRESPONSE"]._serialized_start = 7392 + _globals["_SETTRACKINGRECTANGLESTATUSRESPONSE"]._serialized_end = 7428 + _globals["_SETTRACKINGOFFSTATUSREQUEST"]._serialized_start = 7430 + _globals["_SETTRACKINGOFFSTATUSREQUEST"]._serialized_end = 7459 + _globals["_SETTRACKINGOFFSTATUSRESPONSE"]._serialized_start = 7461 + _globals["_SETTRACKINGOFFSTATUSRESPONSE"]._serialized_end = 7491 + _globals["_SUBSCRIBETRACKINGPOINTCOMMANDREQUEST"]._serialized_start = 7493 + _globals["_SUBSCRIBETRACKINGPOINTCOMMANDREQUEST"]._serialized_end = 7531 + _globals["_TRACKINGPOINTCOMMANDRESPONSE"]._serialized_start = 7533 + _globals["_TRACKINGPOINTCOMMANDRESPONSE"]._serialized_end = 7622 + _globals["_SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST"]._serialized_start = 7624 + _globals["_SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST"]._serialized_end = 7666 + _globals["_TRACKINGRECTANGLECOMMANDRESPONSE"]._serialized_start = 7668 + _globals["_TRACKINGRECTANGLECOMMANDRESPONSE"]._serialized_end = 7769 + _globals["_SUBSCRIBETRACKINGOFFCOMMANDREQUEST"]._serialized_start = 7771 + _globals["_SUBSCRIBETRACKINGOFFCOMMANDREQUEST"]._serialized_end = 7807 + _globals["_TRACKINGOFFCOMMANDRESPONSE"]._serialized_start = 7809 + _globals["_TRACKINGOFFCOMMANDRESPONSE"]._serialized_end = 7852 + _globals["_RESPONDTRACKINGPOINTCOMMANDREQUEST"]._serialized_start = 7854 + _globals["_RESPONDTRACKINGPOINTCOMMANDREQUEST"]._serialized_end = 7961 + _globals["_RESPONDTRACKINGPOINTCOMMANDRESPONSE"]._serialized_start = 7963 + _globals["_RESPONDTRACKINGPOINTCOMMANDRESPONSE"]._serialized_end = 8076 + _globals["_RESPONDTRACKINGRECTANGLECOMMANDREQUEST"]._serialized_start = 8078 + _globals["_RESPONDTRACKINGRECTANGLECOMMANDREQUEST"]._serialized_end = 8189 + _globals["_RESPONDTRACKINGRECTANGLECOMMANDRESPONSE"]._serialized_start = 8191 + _globals["_RESPONDTRACKINGRECTANGLECOMMANDRESPONSE"]._serialized_end = 8308 + _globals["_RESPONDTRACKINGOFFCOMMANDREQUEST"]._serialized_start = 8310 + _globals["_RESPONDTRACKINGOFFCOMMANDREQUEST"]._serialized_end = 8415 + _globals["_RESPONDTRACKINGOFFCOMMANDRESPONSE"]._serialized_start = 8417 + _globals["_RESPONDTRACKINGOFFCOMMANDRESPONSE"]._serialized_end = 8528 + _globals["_TRACKPOINT"]._serialized_start = 8530 + _globals["_TRACKPOINT"]._serialized_end = 8592 + _globals["_TRACKRECTANGLE"]._serialized_start = 8595 + _globals["_TRACKRECTANGLE"]._serialized_end = 8727 + _globals["_CAMERASERVERSERVICE"]._serialized_start = 8913 + _globals["_CAMERASERVERSERVICE"]._serialized_end = 14473 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/camera_server_pb2_grpc.py b/mavsdk/camera_server_pb2_grpc.py index 4ccb0def..dfbd73eb 100644 --- a/mavsdk/camera_server_pb2_grpc.py +++ b/mavsdk/camera_server_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import camera_server_pb2 as camera__server_dot_camera__server__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in camera_server/camera_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in camera_server/camera_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class CameraServerServiceStub(object): - """Provides handling of camera interface - """ + """Provides handling of camera interface""" def __init__(self, channel): """Constructor. @@ -36,704 +39,707 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetInformation = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/SetInformation', - request_serializer=camera__server_dot_camera__server__pb2.SetInformationRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.SetInformationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SetInformation", + request_serializer=camera__server_dot_camera__server__pb2.SetInformationRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.SetInformationResponse.FromString, + _registered_method=True, + ) self.SetVideoStreaming = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreaming', - request_serializer=camera__server_dot_camera__server__pb2.SetVideoStreamingRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.SetVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreaming", + request_serializer=camera__server_dot_camera__server__pb2.SetVideoStreamingRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.SetVideoStreamingResponse.FromString, + _registered_method=True, + ) self.SetInProgress = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/SetInProgress', - request_serializer=camera__server_dot_camera__server__pb2.SetInProgressRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.SetInProgressResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", + request_serializer=camera__server_dot_camera__server__pb2.SetInProgressRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.SetInProgressResponse.FromString, + _registered_method=True, + ) self.SubscribeTakePhoto = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeTakePhotoRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.TakePhotoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeTakePhotoRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.TakePhotoResponse.FromString, + _registered_method=True, + ) self.RespondTakePhoto = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto', - request_serializer=camera__server_dot_camera__server__pb2.RespondTakePhotoRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondTakePhotoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", + request_serializer=camera__server_dot_camera__server__pb2.RespondTakePhotoRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondTakePhotoResponse.FromString, + _registered_method=True, + ) self.SubscribeStartVideo = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.StartVideoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.StartVideoResponse.FromString, + _registered_method=True, + ) self.RespondStartVideo = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideo', - request_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideo", + request_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoResponse.FromString, + _registered_method=True, + ) self.SubscribeStopVideo = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.StopVideoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.StopVideoResponse.FromString, + _registered_method=True, + ) self.RespondStopVideo = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideo', - request_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideo", + request_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoResponse.FromString, + _registered_method=True, + ) self.SubscribeStartVideoStreaming = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoStreamingRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.StartVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoStreamingRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.StartVideoStreamingResponse.FromString, + _registered_method=True, + ) self.RespondStartVideoStreaming = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideoStreaming', - request_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideoStreaming", + request_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingResponse.FromString, + _registered_method=True, + ) self.SubscribeStopVideoStreaming = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoStreamingRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.StopVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoStreamingRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.StopVideoStreamingResponse.FromString, + _registered_method=True, + ) self.RespondStopVideoStreaming = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideoStreaming', - request_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideoStreaming", + request_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingResponse.FromString, + _registered_method=True, + ) self.SubscribeSetMode = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeSetModeRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.SetModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeSetModeRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.SetModeResponse.FromString, + _registered_method=True, + ) self.RespondSetMode = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondSetMode', - request_serializer=camera__server_dot_camera__server__pb2.RespondSetModeRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondSetModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondSetMode", + request_serializer=camera__server_dot_camera__server__pb2.RespondSetModeRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondSetModeResponse.FromString, + _registered_method=True, + ) self.SubscribeStorageInformation = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStorageInformation', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeStorageInformationRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.StorageInformationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStorageInformation", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeStorageInformationRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.StorageInformationResponse.FromString, + _registered_method=True, + ) self.RespondStorageInformation = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation', - request_serializer=camera__server_dot_camera__server__pb2.RespondStorageInformationRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondStorageInformationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation", + request_serializer=camera__server_dot_camera__server__pb2.RespondStorageInformationRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondStorageInformationResponse.FromString, + _registered_method=True, + ) self.SubscribeCaptureStatus = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeCaptureStatusRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.CaptureStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeCaptureStatusRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.CaptureStatusResponse.FromString, + _registered_method=True, + ) self.RespondCaptureStatus = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus', - request_serializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus", + request_serializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusResponse.FromString, + _registered_method=True, + ) self.SubscribeFormatStorage = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeFormatStorage', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeFormatStorageRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.FormatStorageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeFormatStorage", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeFormatStorageRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.FormatStorageResponse.FromString, + _registered_method=True, + ) self.RespondFormatStorage = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondFormatStorage', - request_serializer=camera__server_dot_camera__server__pb2.RespondFormatStorageRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondFormatStorageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondFormatStorage", + request_serializer=camera__server_dot_camera__server__pb2.RespondFormatStorageRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondFormatStorageResponse.FromString, + _registered_method=True, + ) self.SubscribeResetSettings = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeResetSettingsRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.ResetSettingsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeResetSettingsRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.ResetSettingsResponse.FromString, + _registered_method=True, + ) self.RespondResetSettings = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondResetSettings', - request_serializer=camera__server_dot_camera__server__pb2.RespondResetSettingsRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondResetSettingsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondResetSettings", + request_serializer=camera__server_dot_camera__server__pb2.RespondResetSettingsRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondResetSettingsResponse.FromString, + _registered_method=True, + ) self.SubscribeZoomInStart = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomInStart', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomInStartRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.ZoomInStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomInStart", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomInStartRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.ZoomInStartResponse.FromString, + _registered_method=True, + ) self.RespondZoomInStart = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomInStart', - request_serializer=camera__server_dot_camera__server__pb2.RespondZoomInStartRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomInStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomInStart", + request_serializer=camera__server_dot_camera__server__pb2.RespondZoomInStartRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomInStartResponse.FromString, + _registered_method=True, + ) self.SubscribeZoomOutStart = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomOutStart', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomOutStartRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.ZoomOutStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomOutStart", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomOutStartRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.ZoomOutStartResponse.FromString, + _registered_method=True, + ) self.RespondZoomOutStart = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomOutStart', - request_serializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomOutStart", + request_serializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartResponse.FromString, + _registered_method=True, + ) self.SubscribeZoomStop = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomStop', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomStopRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.ZoomStopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomStop", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomStopRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.ZoomStopResponse.FromString, + _registered_method=True, + ) self.RespondZoomStop = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomStop', - request_serializer=camera__server_dot_camera__server__pb2.RespondZoomStopRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomStopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomStop", + request_serializer=camera__server_dot_camera__server__pb2.RespondZoomStopRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomStopResponse.FromString, + _registered_method=True, + ) self.SubscribeZoomRange = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomRange', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomRangeRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.ZoomRangeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomRange", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeZoomRangeRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.ZoomRangeResponse.FromString, + _registered_method=True, + ) self.RespondZoomRange = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomRange', - request_serializer=camera__server_dot_camera__server__pb2.RespondZoomRangeRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomRangeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomRange", + request_serializer=camera__server_dot_camera__server__pb2.RespondZoomRangeRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondZoomRangeResponse.FromString, + _registered_method=True, + ) self.SetTrackingRectangleStatus = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/SetTrackingRectangleStatus', - request_serializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SetTrackingRectangleStatus", + request_serializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusResponse.FromString, + _registered_method=True, + ) self.SetTrackingOffStatus = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/SetTrackingOffStatus', - request_serializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SetTrackingOffStatus", + request_serializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusResponse.FromString, + _registered_method=True, + ) self.SubscribeTrackingPointCommand = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingPointCommand', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeTrackingPointCommandRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.TrackingPointCommandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingPointCommand", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeTrackingPointCommandRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.TrackingPointCommandResponse.FromString, + _registered_method=True, + ) self.SubscribeTrackingRectangleCommand = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingRectangleCommand', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeTrackingRectangleCommandRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.TrackingRectangleCommandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingRectangleCommand", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeTrackingRectangleCommandRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.TrackingRectangleCommandResponse.FromString, + _registered_method=True, + ) self.SubscribeTrackingOffCommand = channel.unary_stream( - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingOffCommand', - request_serializer=camera__server_dot_camera__server__pb2.SubscribeTrackingOffCommandRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.TrackingOffCommandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingOffCommand", + request_serializer=camera__server_dot_camera__server__pb2.SubscribeTrackingOffCommandRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.TrackingOffCommandResponse.FromString, + _registered_method=True, + ) self.RespondTrackingPointCommand = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingPointCommand', - request_serializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingPointCommand", + request_serializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandResponse.FromString, + _registered_method=True, + ) self.RespondTrackingRectangleCommand = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingRectangleCommand', - request_serializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingRectangleCommand", + request_serializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandResponse.FromString, + _registered_method=True, + ) self.RespondTrackingOffCommand = channel.unary_unary( - '/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingOffCommand', - request_serializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandRequest.SerializeToString, - response_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingOffCommand", + request_serializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandRequest.SerializeToString, + response_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandResponse.FromString, + _registered_method=True, + ) class CameraServerServiceServicer(object): - """Provides handling of camera interface - """ + """Provides handling of camera interface""" def SetInformation(self, request, context): - """Sets the camera information. This must be called as soon as the camera server is created. - """ + """Sets the camera information. This must be called as soon as the camera server is created.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetVideoStreaming(self, request, context): - """Sets video streaming settings. - """ + """Sets video streaming settings.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetInProgress(self, request, context): - """Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. - """ + """Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTakePhoto(self, request, context): - """Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. - """ + """Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTakePhoto(self, request, context): - """Respond to an image capture request from SubscribeTakePhoto. - """ + """Respond to an image capture request from SubscribeTakePhoto.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStartVideo(self, request, context): - """Subscribe to start video requests. Each request received should respond to using RespondStartVideo - """ + """Subscribe to start video requests. Each request received should respond to using RespondStartVideo""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondStartVideo(self, request, context): - """Subscribe to stop video requests. Each request received should respond using StopVideoResponse - """ + """Subscribe to stop video requests. Each request received should respond using StopVideoResponse""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStopVideo(self, request, context): - """Subscribe to stop video requests. Each request received should response to using RespondStopVideo - """ + """Subscribe to stop video requests. Each request received should response to using RespondStopVideo""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondStopVideo(self, request, context): - """Respond to stop video request from SubscribeStopVideo. - """ + """Respond to stop video request from SubscribeStopVideo.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStartVideoStreaming(self, request, context): - """Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming - """ + """Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondStartVideoStreaming(self, request, context): - """Respond to start video streaming from SubscribeStartVideoStreaming. - """ + """Respond to start video streaming from SubscribeStartVideoStreaming.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStopVideoStreaming(self, request, context): - """Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming - """ + """Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondStopVideoStreaming(self, request, context): - """Respond to stop video streaming from SubscribeStopVideoStreaming. - """ + """Respond to stop video streaming from SubscribeStopVideoStreaming.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeSetMode(self, request, context): - """Subscribe to set camera mode requests. Each request received should response to using RespondSetMode - """ + """Subscribe to set camera mode requests. Each request received should response to using RespondSetMode""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondSetMode(self, request, context): - """Respond to set camera mode from SubscribeSetMode. - """ + """Respond to set camera mode from SubscribeSetMode.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStorageInformation(self, request, context): - """Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation - """ + """Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondStorageInformation(self, request, context): - """Respond to camera storage information from SubscribeStorageInformation. - """ + """Respond to camera storage information from SubscribeStorageInformation.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCaptureStatus(self, request, context): - """Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus - """ + """Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondCaptureStatus(self, request, context): - """Respond to camera capture status from SubscribeCaptureStatus. - """ + """Respond to camera capture status from SubscribeCaptureStatus.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFormatStorage(self, request, context): - """Subscribe to format storage requests. Each request received should response to using RespondFormatStorage - """ + """Subscribe to format storage requests. Each request received should response to using RespondFormatStorage""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondFormatStorage(self, request, context): - """Respond to format storage from SubscribeFormatStorage. - """ + """Respond to format storage from SubscribeFormatStorage.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeResetSettings(self, request, context): - """Subscribe to reset settings requests. Each request received should response to using RespondResetSettings - """ + """Subscribe to reset settings requests. Each request received should response to using RespondResetSettings""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondResetSettings(self, request, context): - """Respond to reset settings from SubscribeResetSettings. - """ + """Respond to reset settings from SubscribeResetSettings.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeZoomInStart(self, request, context): - """Subscribe to zoom in start command - """ + """Subscribe to zoom in start command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondZoomInStart(self, request, context): - """Respond to zoom in start. - """ + """Respond to zoom in start.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeZoomOutStart(self, request, context): - """Subscribe to zoom out start command - """ + """Subscribe to zoom out start command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondZoomOutStart(self, request, context): - """Respond to zoom out start. - """ + """Respond to zoom out start.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeZoomStop(self, request, context): - """Subscribe to zoom stop command - """ + """Subscribe to zoom stop command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondZoomStop(self, request, context): - """Respond to zoom stop. - """ + """Respond to zoom stop.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeZoomRange(self, request, context): - """Subscribe to zoom range command - """ + """Subscribe to zoom range command""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondZoomRange(self, request, context): - """Respond to zoom range. - """ + """Respond to zoom range.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTrackingRectangleStatus(self, request, context): - """Set/update the current rectangle tracking status. - """ + """Set/update the current rectangle tracking status.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTrackingOffStatus(self, request, context): - """Set the current tracking status to off. - """ + """Set the current tracking status to off.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTrackingPointCommand(self, request, context): - """Subscribe to incoming tracking point command. - """ + """Subscribe to incoming tracking point command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTrackingRectangleCommand(self, request, context): - """Subscribe to incoming tracking rectangle command. - """ + """Subscribe to incoming tracking rectangle command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTrackingOffCommand(self, request, context): - """Subscribe to incoming tracking off command. - """ + """Subscribe to incoming tracking off command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTrackingPointCommand(self, request, context): - """Respond to an incoming tracking point command. - """ + """Respond to an incoming tracking point command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTrackingRectangleCommand(self, request, context): - """Respond to an incoming tracking rectangle command. - """ + """Respond to an incoming tracking rectangle command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTrackingOffCommand(self, request, context): - """Respond to an incoming tracking off command. - """ + """Respond to an incoming tracking off command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_CameraServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetInformation': grpc.unary_unary_rpc_method_handler( - servicer.SetInformation, - request_deserializer=camera__server_dot_camera__server__pb2.SetInformationRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.SetInformationResponse.SerializeToString, - ), - 'SetVideoStreaming': grpc.unary_unary_rpc_method_handler( - servicer.SetVideoStreaming, - request_deserializer=camera__server_dot_camera__server__pb2.SetVideoStreamingRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.SetVideoStreamingResponse.SerializeToString, - ), - 'SetInProgress': grpc.unary_unary_rpc_method_handler( - servicer.SetInProgress, - request_deserializer=camera__server_dot_camera__server__pb2.SetInProgressRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.SetInProgressResponse.SerializeToString, - ), - 'SubscribeTakePhoto': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTakePhoto, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTakePhotoRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.TakePhotoResponse.SerializeToString, - ), - 'RespondTakePhoto': grpc.unary_unary_rpc_method_handler( - servicer.RespondTakePhoto, - request_deserializer=camera__server_dot_camera__server__pb2.RespondTakePhotoRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondTakePhotoResponse.SerializeToString, - ), - 'SubscribeStartVideo': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStartVideo, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.StartVideoResponse.SerializeToString, - ), - 'RespondStartVideo': grpc.unary_unary_rpc_method_handler( - servicer.RespondStartVideo, - request_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoResponse.SerializeToString, - ), - 'SubscribeStopVideo': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStopVideo, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.StopVideoResponse.SerializeToString, - ), - 'RespondStopVideo': grpc.unary_unary_rpc_method_handler( - servicer.RespondStopVideo, - request_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoResponse.SerializeToString, - ), - 'SubscribeStartVideoStreaming': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStartVideoStreaming, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoStreamingRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.StartVideoStreamingResponse.SerializeToString, - ), - 'RespondStartVideoStreaming': grpc.unary_unary_rpc_method_handler( - servicer.RespondStartVideoStreaming, - request_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingResponse.SerializeToString, - ), - 'SubscribeStopVideoStreaming': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStopVideoStreaming, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoStreamingRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.StopVideoStreamingResponse.SerializeToString, - ), - 'RespondStopVideoStreaming': grpc.unary_unary_rpc_method_handler( - servicer.RespondStopVideoStreaming, - request_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingResponse.SerializeToString, - ), - 'SubscribeSetMode': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeSetMode, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeSetModeRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.SetModeResponse.SerializeToString, - ), - 'RespondSetMode': grpc.unary_unary_rpc_method_handler( - servicer.RespondSetMode, - request_deserializer=camera__server_dot_camera__server__pb2.RespondSetModeRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondSetModeResponse.SerializeToString, - ), - 'SubscribeStorageInformation': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStorageInformation, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStorageInformationRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.StorageInformationResponse.SerializeToString, - ), - 'RespondStorageInformation': grpc.unary_unary_rpc_method_handler( - servicer.RespondStorageInformation, - request_deserializer=camera__server_dot_camera__server__pb2.RespondStorageInformationRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondStorageInformationResponse.SerializeToString, - ), - 'SubscribeCaptureStatus': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCaptureStatus, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeCaptureStatusRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.CaptureStatusResponse.SerializeToString, - ), - 'RespondCaptureStatus': grpc.unary_unary_rpc_method_handler( - servicer.RespondCaptureStatus, - request_deserializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusResponse.SerializeToString, - ), - 'SubscribeFormatStorage': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFormatStorage, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeFormatStorageRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.FormatStorageResponse.SerializeToString, - ), - 'RespondFormatStorage': grpc.unary_unary_rpc_method_handler( - servicer.RespondFormatStorage, - request_deserializer=camera__server_dot_camera__server__pb2.RespondFormatStorageRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondFormatStorageResponse.SerializeToString, - ), - 'SubscribeResetSettings': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeResetSettings, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeResetSettingsRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.ResetSettingsResponse.SerializeToString, - ), - 'RespondResetSettings': grpc.unary_unary_rpc_method_handler( - servicer.RespondResetSettings, - request_deserializer=camera__server_dot_camera__server__pb2.RespondResetSettingsRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondResetSettingsResponse.SerializeToString, - ), - 'SubscribeZoomInStart': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeZoomInStart, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomInStartRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.ZoomInStartResponse.SerializeToString, - ), - 'RespondZoomInStart': grpc.unary_unary_rpc_method_handler( - servicer.RespondZoomInStart, - request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomInStartRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondZoomInStartResponse.SerializeToString, - ), - 'SubscribeZoomOutStart': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeZoomOutStart, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomOutStartRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.ZoomOutStartResponse.SerializeToString, - ), - 'RespondZoomOutStart': grpc.unary_unary_rpc_method_handler( - servicer.RespondZoomOutStart, - request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartResponse.SerializeToString, - ), - 'SubscribeZoomStop': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeZoomStop, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomStopRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.ZoomStopResponse.SerializeToString, - ), - 'RespondZoomStop': grpc.unary_unary_rpc_method_handler( - servicer.RespondZoomStop, - request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomStopRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondZoomStopResponse.SerializeToString, - ), - 'SubscribeZoomRange': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeZoomRange, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomRangeRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.ZoomRangeResponse.SerializeToString, - ), - 'RespondZoomRange': grpc.unary_unary_rpc_method_handler( - servicer.RespondZoomRange, - request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomRangeRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondZoomRangeResponse.SerializeToString, - ), - 'SetTrackingRectangleStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetTrackingRectangleStatus, - request_deserializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusResponse.SerializeToString, - ), - 'SetTrackingOffStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetTrackingOffStatus, - request_deserializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusResponse.SerializeToString, - ), - 'SubscribeTrackingPointCommand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTrackingPointCommand, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTrackingPointCommandRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.TrackingPointCommandResponse.SerializeToString, - ), - 'SubscribeTrackingRectangleCommand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTrackingRectangleCommand, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTrackingRectangleCommandRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.TrackingRectangleCommandResponse.SerializeToString, - ), - 'SubscribeTrackingOffCommand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTrackingOffCommand, - request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTrackingOffCommandRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.TrackingOffCommandResponse.SerializeToString, - ), - 'RespondTrackingPointCommand': grpc.unary_unary_rpc_method_handler( - servicer.RespondTrackingPointCommand, - request_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandResponse.SerializeToString, - ), - 'RespondTrackingRectangleCommand': grpc.unary_unary_rpc_method_handler( - servicer.RespondTrackingRectangleCommand, - request_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandResponse.SerializeToString, - ), - 'RespondTrackingOffCommand': grpc.unary_unary_rpc_method_handler( - servicer.RespondTrackingOffCommand, - request_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandRequest.FromString, - response_serializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandResponse.SerializeToString, - ), + "SetInformation": grpc.unary_unary_rpc_method_handler( + servicer.SetInformation, + request_deserializer=camera__server_dot_camera__server__pb2.SetInformationRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.SetInformationResponse.SerializeToString, + ), + "SetVideoStreaming": grpc.unary_unary_rpc_method_handler( + servicer.SetVideoStreaming, + request_deserializer=camera__server_dot_camera__server__pb2.SetVideoStreamingRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.SetVideoStreamingResponse.SerializeToString, + ), + "SetInProgress": grpc.unary_unary_rpc_method_handler( + servicer.SetInProgress, + request_deserializer=camera__server_dot_camera__server__pb2.SetInProgressRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.SetInProgressResponse.SerializeToString, + ), + "SubscribeTakePhoto": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTakePhoto, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTakePhotoRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.TakePhotoResponse.SerializeToString, + ), + "RespondTakePhoto": grpc.unary_unary_rpc_method_handler( + servicer.RespondTakePhoto, + request_deserializer=camera__server_dot_camera__server__pb2.RespondTakePhotoRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondTakePhotoResponse.SerializeToString, + ), + "SubscribeStartVideo": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStartVideo, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.StartVideoResponse.SerializeToString, + ), + "RespondStartVideo": grpc.unary_unary_rpc_method_handler( + servicer.RespondStartVideo, + request_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoResponse.SerializeToString, + ), + "SubscribeStopVideo": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStopVideo, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.StopVideoResponse.SerializeToString, + ), + "RespondStopVideo": grpc.unary_unary_rpc_method_handler( + servicer.RespondStopVideo, + request_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoResponse.SerializeToString, + ), + "SubscribeStartVideoStreaming": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStartVideoStreaming, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStartVideoStreamingRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.StartVideoStreamingResponse.SerializeToString, + ), + "RespondStartVideoStreaming": grpc.unary_unary_rpc_method_handler( + servicer.RespondStartVideoStreaming, + request_deserializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondStartVideoStreamingResponse.SerializeToString, + ), + "SubscribeStopVideoStreaming": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStopVideoStreaming, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStopVideoStreamingRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.StopVideoStreamingResponse.SerializeToString, + ), + "RespondStopVideoStreaming": grpc.unary_unary_rpc_method_handler( + servicer.RespondStopVideoStreaming, + request_deserializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondStopVideoStreamingResponse.SerializeToString, + ), + "SubscribeSetMode": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeSetMode, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeSetModeRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.SetModeResponse.SerializeToString, + ), + "RespondSetMode": grpc.unary_unary_rpc_method_handler( + servicer.RespondSetMode, + request_deserializer=camera__server_dot_camera__server__pb2.RespondSetModeRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondSetModeResponse.SerializeToString, + ), + "SubscribeStorageInformation": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStorageInformation, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeStorageInformationRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.StorageInformationResponse.SerializeToString, + ), + "RespondStorageInformation": grpc.unary_unary_rpc_method_handler( + servicer.RespondStorageInformation, + request_deserializer=camera__server_dot_camera__server__pb2.RespondStorageInformationRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondStorageInformationResponse.SerializeToString, + ), + "SubscribeCaptureStatus": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCaptureStatus, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeCaptureStatusRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.CaptureStatusResponse.SerializeToString, + ), + "RespondCaptureStatus": grpc.unary_unary_rpc_method_handler( + servicer.RespondCaptureStatus, + request_deserializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondCaptureStatusResponse.SerializeToString, + ), + "SubscribeFormatStorage": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFormatStorage, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeFormatStorageRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.FormatStorageResponse.SerializeToString, + ), + "RespondFormatStorage": grpc.unary_unary_rpc_method_handler( + servicer.RespondFormatStorage, + request_deserializer=camera__server_dot_camera__server__pb2.RespondFormatStorageRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondFormatStorageResponse.SerializeToString, + ), + "SubscribeResetSettings": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeResetSettings, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeResetSettingsRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.ResetSettingsResponse.SerializeToString, + ), + "RespondResetSettings": grpc.unary_unary_rpc_method_handler( + servicer.RespondResetSettings, + request_deserializer=camera__server_dot_camera__server__pb2.RespondResetSettingsRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondResetSettingsResponse.SerializeToString, + ), + "SubscribeZoomInStart": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeZoomInStart, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomInStartRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.ZoomInStartResponse.SerializeToString, + ), + "RespondZoomInStart": grpc.unary_unary_rpc_method_handler( + servicer.RespondZoomInStart, + request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomInStartRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondZoomInStartResponse.SerializeToString, + ), + "SubscribeZoomOutStart": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeZoomOutStart, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomOutStartRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.ZoomOutStartResponse.SerializeToString, + ), + "RespondZoomOutStart": grpc.unary_unary_rpc_method_handler( + servicer.RespondZoomOutStart, + request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondZoomOutStartResponse.SerializeToString, + ), + "SubscribeZoomStop": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeZoomStop, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomStopRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.ZoomStopResponse.SerializeToString, + ), + "RespondZoomStop": grpc.unary_unary_rpc_method_handler( + servicer.RespondZoomStop, + request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomStopRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondZoomStopResponse.SerializeToString, + ), + "SubscribeZoomRange": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeZoomRange, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeZoomRangeRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.ZoomRangeResponse.SerializeToString, + ), + "RespondZoomRange": grpc.unary_unary_rpc_method_handler( + servicer.RespondZoomRange, + request_deserializer=camera__server_dot_camera__server__pb2.RespondZoomRangeRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondZoomRangeResponse.SerializeToString, + ), + "SetTrackingRectangleStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetTrackingRectangleStatus, + request_deserializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusResponse.SerializeToString, + ), + "SetTrackingOffStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetTrackingOffStatus, + request_deserializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.SetTrackingOffStatusResponse.SerializeToString, + ), + "SubscribeTrackingPointCommand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTrackingPointCommand, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTrackingPointCommandRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.TrackingPointCommandResponse.SerializeToString, + ), + "SubscribeTrackingRectangleCommand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTrackingRectangleCommand, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTrackingRectangleCommandRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.TrackingRectangleCommandResponse.SerializeToString, + ), + "SubscribeTrackingOffCommand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTrackingOffCommand, + request_deserializer=camera__server_dot_camera__server__pb2.SubscribeTrackingOffCommandRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.TrackingOffCommandResponse.SerializeToString, + ), + "RespondTrackingPointCommand": grpc.unary_unary_rpc_method_handler( + servicer.RespondTrackingPointCommand, + request_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondTrackingPointCommandResponse.SerializeToString, + ), + "RespondTrackingRectangleCommand": grpc.unary_unary_rpc_method_handler( + servicer.RespondTrackingRectangleCommand, + request_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandResponse.SerializeToString, + ), + "RespondTrackingOffCommand": grpc.unary_unary_rpc_method_handler( + servicer.RespondTrackingOffCommand, + request_deserializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandRequest.FromString, + response_serializer=camera__server_dot_camera__server__pb2.RespondTrackingOffCommandResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.camera_server.CameraServerService', rpc_method_handlers) + "mavsdk.rpc.camera_server.CameraServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.camera_server.CameraServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.camera_server.CameraServerService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class CameraServerService(object): - """Provides handling of camera interface - """ + """Provides handling of camera interface""" @staticmethod - def SetInformation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetInformation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SetInformation', + "/mavsdk.rpc.camera_server.CameraServerService/SetInformation", camera__server_dot_camera__server__pb2.SetInformationRequest.SerializeToString, camera__server_dot_camera__server__pb2.SetInformationResponse.FromString, options, @@ -744,23 +750,26 @@ def SetInformation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreaming', + "/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreaming", camera__server_dot_camera__server__pb2.SetVideoStreamingRequest.SerializeToString, camera__server_dot_camera__server__pb2.SetVideoStreamingResponse.FromString, options, @@ -771,23 +780,26 @@ def SetVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetInProgress(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetInProgress( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SetInProgress', + "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", camera__server_dot_camera__server__pb2.SetInProgressRequest.SerializeToString, camera__server_dot_camera__server__pb2.SetInProgressResponse.FromString, options, @@ -798,23 +810,26 @@ def SetInProgress(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeTakePhoto(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTakePhoto( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", camera__server_dot_camera__server__pb2.SubscribeTakePhotoRequest.SerializeToString, camera__server_dot_camera__server__pb2.TakePhotoResponse.FromString, options, @@ -825,23 +840,26 @@ def SubscribeTakePhoto(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondTakePhoto(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondTakePhoto( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto', + "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", camera__server_dot_camera__server__pb2.RespondTakePhotoRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondTakePhotoResponse.FromString, options, @@ -852,23 +870,26 @@ def RespondTakePhoto(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStartVideo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStartVideo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo", camera__server_dot_camera__server__pb2.SubscribeStartVideoRequest.SerializeToString, camera__server_dot_camera__server__pb2.StartVideoResponse.FromString, options, @@ -879,23 +900,26 @@ def SubscribeStartVideo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondStartVideo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondStartVideo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideo', + "/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideo", camera__server_dot_camera__server__pb2.RespondStartVideoRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondStartVideoResponse.FromString, options, @@ -906,23 +930,26 @@ def RespondStartVideo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStopVideo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStopVideo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", camera__server_dot_camera__server__pb2.SubscribeStopVideoRequest.SerializeToString, camera__server_dot_camera__server__pb2.StopVideoResponse.FromString, options, @@ -933,23 +960,26 @@ def SubscribeStopVideo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondStopVideo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondStopVideo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideo', + "/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideo", camera__server_dot_camera__server__pb2.RespondStopVideoRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondStopVideoResponse.FromString, options, @@ -960,23 +990,26 @@ def RespondStopVideo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStartVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStartVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming", camera__server_dot_camera__server__pb2.SubscribeStartVideoStreamingRequest.SerializeToString, camera__server_dot_camera__server__pb2.StartVideoStreamingResponse.FromString, options, @@ -987,23 +1020,26 @@ def SubscribeStartVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondStartVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondStartVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideoStreaming', + "/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideoStreaming", camera__server_dot_camera__server__pb2.RespondStartVideoStreamingRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondStartVideoStreamingResponse.FromString, options, @@ -1014,23 +1050,26 @@ def RespondStartVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStopVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStopVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming", camera__server_dot_camera__server__pb2.SubscribeStopVideoStreamingRequest.SerializeToString, camera__server_dot_camera__server__pb2.StopVideoStreamingResponse.FromString, options, @@ -1041,23 +1080,26 @@ def SubscribeStopVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondStopVideoStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondStopVideoStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideoStreaming', + "/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideoStreaming", camera__server_dot_camera__server__pb2.RespondStopVideoStreamingRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondStopVideoStreamingResponse.FromString, options, @@ -1068,23 +1110,26 @@ def RespondStopVideoStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeSetMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeSetMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode", camera__server_dot_camera__server__pb2.SubscribeSetModeRequest.SerializeToString, camera__server_dot_camera__server__pb2.SetModeResponse.FromString, options, @@ -1095,23 +1140,26 @@ def SubscribeSetMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondSetMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondSetMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondSetMode', + "/mavsdk.rpc.camera_server.CameraServerService/RespondSetMode", camera__server_dot_camera__server__pb2.RespondSetModeRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondSetModeResponse.FromString, options, @@ -1122,23 +1170,26 @@ def RespondSetMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStorageInformation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStorageInformation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeStorageInformation', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStorageInformation", camera__server_dot_camera__server__pb2.SubscribeStorageInformationRequest.SerializeToString, camera__server_dot_camera__server__pb2.StorageInformationResponse.FromString, options, @@ -1149,23 +1200,26 @@ def SubscribeStorageInformation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondStorageInformation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondStorageInformation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation', + "/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation", camera__server_dot_camera__server__pb2.RespondStorageInformationRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondStorageInformationResponse.FromString, options, @@ -1176,23 +1230,26 @@ def RespondStorageInformation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCaptureStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCaptureStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus", camera__server_dot_camera__server__pb2.SubscribeCaptureStatusRequest.SerializeToString, camera__server_dot_camera__server__pb2.CaptureStatusResponse.FromString, options, @@ -1203,23 +1260,26 @@ def SubscribeCaptureStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondCaptureStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondCaptureStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus', + "/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus", camera__server_dot_camera__server__pb2.RespondCaptureStatusRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondCaptureStatusResponse.FromString, options, @@ -1230,23 +1290,26 @@ def RespondCaptureStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeFormatStorage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeFormatStorage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeFormatStorage', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeFormatStorage", camera__server_dot_camera__server__pb2.SubscribeFormatStorageRequest.SerializeToString, camera__server_dot_camera__server__pb2.FormatStorageResponse.FromString, options, @@ -1257,23 +1320,26 @@ def SubscribeFormatStorage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondFormatStorage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondFormatStorage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondFormatStorage', + "/mavsdk.rpc.camera_server.CameraServerService/RespondFormatStorage", camera__server_dot_camera__server__pb2.RespondFormatStorageRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondFormatStorageResponse.FromString, options, @@ -1284,23 +1350,26 @@ def RespondFormatStorage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeResetSettings(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeResetSettings( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings", camera__server_dot_camera__server__pb2.SubscribeResetSettingsRequest.SerializeToString, camera__server_dot_camera__server__pb2.ResetSettingsResponse.FromString, options, @@ -1311,23 +1380,26 @@ def SubscribeResetSettings(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondResetSettings(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondResetSettings( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondResetSettings', + "/mavsdk.rpc.camera_server.CameraServerService/RespondResetSettings", camera__server_dot_camera__server__pb2.RespondResetSettingsRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondResetSettingsResponse.FromString, options, @@ -1338,23 +1410,26 @@ def RespondResetSettings(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeZoomInStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeZoomInStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomInStart', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomInStart", camera__server_dot_camera__server__pb2.SubscribeZoomInStartRequest.SerializeToString, camera__server_dot_camera__server__pb2.ZoomInStartResponse.FromString, options, @@ -1365,23 +1440,26 @@ def SubscribeZoomInStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondZoomInStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondZoomInStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomInStart', + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomInStart", camera__server_dot_camera__server__pb2.RespondZoomInStartRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondZoomInStartResponse.FromString, options, @@ -1392,23 +1470,26 @@ def RespondZoomInStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeZoomOutStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeZoomOutStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomOutStart', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomOutStart", camera__server_dot_camera__server__pb2.SubscribeZoomOutStartRequest.SerializeToString, camera__server_dot_camera__server__pb2.ZoomOutStartResponse.FromString, options, @@ -1419,23 +1500,26 @@ def SubscribeZoomOutStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondZoomOutStart(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondZoomOutStart( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomOutStart', + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomOutStart", camera__server_dot_camera__server__pb2.RespondZoomOutStartRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondZoomOutStartResponse.FromString, options, @@ -1446,23 +1530,26 @@ def RespondZoomOutStart(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeZoomStop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeZoomStop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomStop', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomStop", camera__server_dot_camera__server__pb2.SubscribeZoomStopRequest.SerializeToString, camera__server_dot_camera__server__pb2.ZoomStopResponse.FromString, options, @@ -1473,23 +1560,26 @@ def SubscribeZoomStop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondZoomStop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondZoomStop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomStop', + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomStop", camera__server_dot_camera__server__pb2.RespondZoomStopRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondZoomStopResponse.FromString, options, @@ -1500,23 +1590,26 @@ def RespondZoomStop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeZoomRange(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeZoomRange( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomRange', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeZoomRange", camera__server_dot_camera__server__pb2.SubscribeZoomRangeRequest.SerializeToString, camera__server_dot_camera__server__pb2.ZoomRangeResponse.FromString, options, @@ -1527,23 +1620,26 @@ def SubscribeZoomRange(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondZoomRange(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondZoomRange( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondZoomRange', + "/mavsdk.rpc.camera_server.CameraServerService/RespondZoomRange", camera__server_dot_camera__server__pb2.RespondZoomRangeRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondZoomRangeResponse.FromString, options, @@ -1554,23 +1650,26 @@ def RespondZoomRange(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetTrackingRectangleStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetTrackingRectangleStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SetTrackingRectangleStatus', + "/mavsdk.rpc.camera_server.CameraServerService/SetTrackingRectangleStatus", camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusRequest.SerializeToString, camera__server_dot_camera__server__pb2.SetTrackingRectangleStatusResponse.FromString, options, @@ -1581,23 +1680,26 @@ def SetTrackingRectangleStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetTrackingOffStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetTrackingOffStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SetTrackingOffStatus', + "/mavsdk.rpc.camera_server.CameraServerService/SetTrackingOffStatus", camera__server_dot_camera__server__pb2.SetTrackingOffStatusRequest.SerializeToString, camera__server_dot_camera__server__pb2.SetTrackingOffStatusResponse.FromString, options, @@ -1608,23 +1710,26 @@ def SetTrackingOffStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeTrackingPointCommand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTrackingPointCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingPointCommand', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingPointCommand", camera__server_dot_camera__server__pb2.SubscribeTrackingPointCommandRequest.SerializeToString, camera__server_dot_camera__server__pb2.TrackingPointCommandResponse.FromString, options, @@ -1635,23 +1740,26 @@ def SubscribeTrackingPointCommand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeTrackingRectangleCommand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTrackingRectangleCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingRectangleCommand', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingRectangleCommand", camera__server_dot_camera__server__pb2.SubscribeTrackingRectangleCommandRequest.SerializeToString, camera__server_dot_camera__server__pb2.TrackingRectangleCommandResponse.FromString, options, @@ -1662,23 +1770,26 @@ def SubscribeTrackingRectangleCommand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeTrackingOffCommand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTrackingOffCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingOffCommand', + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTrackingOffCommand", camera__server_dot_camera__server__pb2.SubscribeTrackingOffCommandRequest.SerializeToString, camera__server_dot_camera__server__pb2.TrackingOffCommandResponse.FromString, options, @@ -1689,23 +1800,26 @@ def SubscribeTrackingOffCommand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondTrackingPointCommand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondTrackingPointCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingPointCommand', + "/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingPointCommand", camera__server_dot_camera__server__pb2.RespondTrackingPointCommandRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondTrackingPointCommandResponse.FromString, options, @@ -1716,23 +1830,26 @@ def RespondTrackingPointCommand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondTrackingRectangleCommand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondTrackingRectangleCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingRectangleCommand', + "/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingRectangleCommand", camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondTrackingRectangleCommandResponse.FromString, options, @@ -1743,23 +1860,26 @@ def RespondTrackingRectangleCommand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RespondTrackingOffCommand(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RespondTrackingOffCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingOffCommand', + "/mavsdk.rpc.camera_server.CameraServerService/RespondTrackingOffCommand", camera__server_dot_camera__server__pb2.RespondTrackingOffCommandRequest.SerializeToString, camera__server_dot_camera__server__pb2.RespondTrackingOffCommandResponse.FromString, options, @@ -1770,4 +1890,5 @@ def RespondTrackingOffCommand(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/component_information.py b/mavsdk/component_information.py index b10b52ea..342e8471 100644 --- a/mavsdk/component_information.py +++ b/mavsdk/component_information.py @@ -8,53 +8,52 @@ class FloatParam: """ - Meta information for parameter of type float. + Meta information for parameter of type float. - Parameters - ---------- - name : std::string - Name (max 16 chars) + Parameters + ---------- + name : std::string + Name (max 16 chars) - short_description : std::string - Short description + short_description : std::string + Short description - long_description : std::string - Long description + long_description : std::string + Long description - unit : std::string - Unit + unit : std::string + Unit - decimal_places : int32_t - Decimal places for user to show + decimal_places : int32_t + Decimal places for user to show - start_value : float - Current/starting value + start_value : float + Current/starting value - default_value : float - Default value + default_value : float + Default value - min_value : float - Minimum value + min_value : float + Minimum value - max_value : float - Maximum value + max_value : float + Maximum value - """ - - + """ def __init__( - self, - name, - short_description, - long_description, - unit, - decimal_places, - start_value, - default_value, - min_value, - max_value): - """ Initializes the FloatParam object """ + self, + name, + short_description, + long_description, + unit, + decimal_places, + start_value, + default_value, + min_value, + max_value, + ): + """Initializes the FloatParam object""" self.name = name self.short_description = short_description self.long_description = long_description @@ -66,27 +65,29 @@ def __init__( self.max_value = max_value def __eq__(self, to_compare): - """ Checks if two FloatParam are the same """ + """Checks if two FloatParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # FloatParam object - return \ - (self.name == to_compare.name) and \ - (self.short_description == to_compare.short_description) and \ - (self.long_description == to_compare.long_description) and \ - (self.unit == to_compare.unit) and \ - (self.decimal_places == to_compare.decimal_places) and \ - (self.start_value == to_compare.start_value) and \ - (self.default_value == to_compare.default_value) and \ - (self.min_value == to_compare.min_value) and \ - (self.max_value == to_compare.max_value) + return ( + (self.name == to_compare.name) + and (self.short_description == to_compare.short_description) + and (self.long_description == to_compare.long_description) + and (self.unit == to_compare.unit) + and (self.decimal_places == to_compare.decimal_places) + and (self.start_value == to_compare.start_value) + and (self.default_value == to_compare.default_value) + and (self.min_value == to_compare.min_value) + and (self.max_value == to_compare.max_value) + ) except AttributeError: return False def __str__(self): - """ FloatParam in string representation """ - struct_repr = ", ".join([ + """FloatParam in string representation""" + struct_repr = ", ".join( + [ "name: " + str(self.name), "short_description: " + str(self.short_description), "long_description: " + str(self.long_description), @@ -95,298 +96,213 @@ def __str__(self): "start_value: " + str(self.start_value), "default_value: " + str(self.default_value), "min_value: " + str(self.min_value), - "max_value: " + str(self.max_value) - ]) + "max_value: " + str(self.max_value), + ] + ) return f"FloatParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFloatParam): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FloatParam( - - rpcFloatParam.name, - - - rpcFloatParam.short_description, - - - rpcFloatParam.long_description, - - - rpcFloatParam.unit, - - - rpcFloatParam.decimal_places, - - - rpcFloatParam.start_value, - - - rpcFloatParam.default_value, - - - rpcFloatParam.min_value, - - - rpcFloatParam.max_value - ) + rpcFloatParam.name, + rpcFloatParam.short_description, + rpcFloatParam.long_description, + rpcFloatParam.unit, + rpcFloatParam.decimal_places, + rpcFloatParam.start_value, + rpcFloatParam.default_value, + rpcFloatParam.min_value, + rpcFloatParam.max_value, + ) def translate_to_rpc(self, rpcFloatParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFloatParam.name = self.name - - - - - + rpcFloatParam.short_description = self.short_description - - - - - + rpcFloatParam.long_description = self.long_description - - - - - + rpcFloatParam.unit = self.unit - - - - - + rpcFloatParam.decimal_places = self.decimal_places - - - - - + rpcFloatParam.start_value = self.start_value - - - - - + rpcFloatParam.default_value = self.default_value - - - - - + rpcFloatParam.min_value = self.min_value - - - - - + rpcFloatParam.max_value = self.max_value - - - class FloatParamUpdate: """ - A float param that has been updated. + A float param that has been updated. - Parameters - ---------- - name : std::string - Name of param that changed + Parameters + ---------- + name : std::string + Name of param that changed - value : float - New value of param + value : float + New value of param - """ - - + """ - def __init__( - self, - name, - value): - """ Initializes the FloatParamUpdate object """ + def __init__(self, name, value): + """Initializes the FloatParamUpdate object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two FloatParamUpdate are the same """ + """Checks if two FloatParamUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # FloatParamUpdate object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ FloatParamUpdate in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """FloatParamUpdate in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"FloatParamUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFloatParamUpdate): - """ Translates a gRPC struct to the SDK equivalent """ - return FloatParamUpdate( - - rpcFloatParamUpdate.name, - - - rpcFloatParamUpdate.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return FloatParamUpdate(rpcFloatParamUpdate.name, rpcFloatParamUpdate.value) def translate_to_rpc(self, rpcFloatParamUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFloatParamUpdate.name = self.name - - - - - + rpcFloatParamUpdate.value = self.value - - - class ComponentInformationResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for param requests. + Possible results returned for param requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 def translate_to_rpc(self): if self == ComponentInformationResult.Result.UNKNOWN: - return component_information_pb2.ComponentInformationResult.RESULT_UNKNOWN + return ( + component_information_pb2.ComponentInformationResult.RESULT_UNKNOWN + ) if self == ComponentInformationResult.Result.SUCCESS: - return component_information_pb2.ComponentInformationResult.RESULT_SUCCESS + return ( + component_information_pb2.ComponentInformationResult.RESULT_SUCCESS + ) if self == ComponentInformationResult.Result.NO_SYSTEM: return component_information_pb2.ComponentInformationResult.RESULT_NO_SYSTEM @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == component_information_pb2.ComponentInformationResult.RESULT_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == component_information_pb2.ComponentInformationResult.RESULT_UNKNOWN + ): return ComponentInformationResult.Result.UNKNOWN - if rpc_enum_value == component_information_pb2.ComponentInformationResult.RESULT_SUCCESS: + if ( + rpc_enum_value + == component_information_pb2.ComponentInformationResult.RESULT_SUCCESS + ): return ComponentInformationResult.Result.SUCCESS - if rpc_enum_value == component_information_pb2.ComponentInformationResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == component_information_pb2.ComponentInformationResult.RESULT_NO_SYSTEM + ): return ComponentInformationResult.Result.NO_SYSTEM def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ComponentInformationResult object """ + def __init__(self, result, result_str): + """Initializes the ComponentInformationResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ComponentInformationResult are the same """ + """Checks if two ComponentInformationResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ComponentInformationResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ComponentInformationResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ComponentInformationResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ComponentInformationResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcComponentInformationResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ComponentInformationResult( - - ComponentInformationResult.Result.translate_from_rpc(rpcComponentInformationResult.result), - - - rpcComponentInformationResult.result_str - ) + ComponentInformationResult.Result.translate_from_rpc( + rpcComponentInformationResult.result + ), + rpcComponentInformationResult.result_str, + ) def translate_to_rpc(self, rpcComponentInformationResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcComponentInformationResult.result = self.result.translate_to_rpc() - - - - - - rpcComponentInformationResult.result_str = self.result_str - - - + rpcComponentInformationResult.result_str = self.result_str class ComponentInformationError(Exception): - """ Raised when a ComponentInformationResult is a fail code """ + """Raised when a ComponentInformationResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -399,66 +315,65 @@ def __str__(self): class ComponentInformation(AsyncBase): """ - Access component information such as parameters. + Access component information such as parameters. - Generated by dcsdkgen - MAVSDK ComponentInformation API + Generated by dcsdkgen - MAVSDK ComponentInformation API """ # Plugin name name = "ComponentInformation" def _setup_stub(self, channel): - """ Setups the api stub """ - self._stub = component_information_pb2_grpc.ComponentInformationServiceStub(channel) + """Setups the api stub""" + self._stub = component_information_pb2_grpc.ComponentInformationServiceStub( + channel + ) - def _extract_result(self, response): - """ Returns the response status and description """ - return ComponentInformationResult.translate_from_rpc(response.component_information_result) - + """Returns the response status and description""" + return ComponentInformationResult.translate_from_rpc( + response.component_information_result + ) async def access_float_params(self): """ - List available float params. + List available float params. - Returns - ------- - params : [FloatParam] - Float param definitions + Returns + ------- + params : [FloatParam] + Float param definitions - Raises - ------ - ComponentInformationError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ComponentInformationError + If the request fails. The error contains the reason for the failure. """ request = component_information_pb2.AccessFloatParamsRequest() response = await self._stub.AccessFloatParams(request) - result = self._extract_result(response) if result.result != ComponentInformationResult.Result.SUCCESS: raise ComponentInformationError(result, "access_float_params()") - params = [] for params_rpc in response.params: params.append(FloatParam.translate_from_rpc(params_rpc)) return params - async def float_param(self): """ - Subscribe to float param changes/updates. + Subscribe to float param changes/updates. + + Yields + ------- + param_update : FloatParamUpdate + A param update - Yields - ------- - param_update : FloatParamUpdate - A param update - """ request = component_information_pb2.SubscribeFloatParamRequest() @@ -466,9 +381,6 @@ async def float_param(self): try: async for response in float_param_stream: - - - yield FloatParamUpdate.translate_from_rpc(response.param_update) finally: - float_param_stream.cancel() \ No newline at end of file + float_param_stream.cancel() diff --git a/mavsdk/component_information_pb2.py b/mavsdk/component_information_pb2.py index 382f44b6..c45b6e73 100644 --- a/mavsdk/component_information_pb2.py +++ b/mavsdk/component_information_pb2.py @@ -2,6 +2,7 @@ # Generated by the protocol buffer compiler. DO NOT EDIT! # source: component_information/component_information.proto """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import message as _message @@ -15,92 +16,136 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n1component_information/component_information.proto\x12 mavsdk.rpc.component_information\x1a\x14mavsdk_options.proto\"\xc7\x01\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\x19\n\x11short_description\x18\x02 \x01(\t\x12\x18\n\x10long_description\x18\x03 \x01(\t\x12\x0c\n\x04unit\x18\x04 \x01(\t\x12\x16\n\x0e\x64\x65\x63imal_places\x18\x05 \x01(\x05\x12\x13\n\x0bstart_value\x18\x06 \x01(\x02\x12\x15\n\rdefault_value\x18\x07 \x01(\x02\x12\x11\n\tmin_value\x18\x08 \x01(\x02\x12\x11\n\tmax_value\x18\t \x01(\x02\"\x1a\n\x18\x41\x63\x63\x65ssFloatParamsRequest\"\xbd\x01\n\x19\x41\x63\x63\x65ssFloatParamsResponse\x12\x62\n\x1c\x63omponent_information_result\x18\x01 \x01(\x0b\x32<.mavsdk.rpc.component_information.ComponentInformationResult\x12<\n\x06params\x18\x02 \x03(\x0b\x32,.mavsdk.rpc.component_information.FloatParam\"/\n\x10\x46loatParamUpdate\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02\"\x1c\n\x1aSubscribeFloatParamRequest\"^\n\x12\x46loatParamResponse\x12H\n\x0cparam_update\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.component_information.FloatParamUpdate\"\xcd\x01\n\x1a\x43omponentInformationResult\x12S\n\x06result\x18\x01 \x01(\x0e\x32\x43.mavsdk.rpc.component_information.ComponentInformationResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"F\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x03\x32\xc6\x02\n\x1b\x43omponentInformationService\x12\x92\x01\n\x11\x41\x63\x63\x65ssFloatParams\x12:.mavsdk.rpc.component_information.AccessFloatParamsRequest\x1a;.mavsdk.rpc.component_information.AccessFloatParamsResponse\"\x04\x80\xb5\x18\x01\x12\x91\x01\n\x13SubscribeFloatParam\x12<.mavsdk.rpc.component_information.SubscribeFloatParamRequest\x1a\x34.mavsdk.rpc.component_information.FloatParamResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42<\n\x1fio.mavsdk.component_informationB\x19\x43omponentInformationProtob\x06proto3') - - - -_FLOATPARAM = DESCRIPTOR.message_types_by_name['FloatParam'] -_ACCESSFLOATPARAMSREQUEST = DESCRIPTOR.message_types_by_name['AccessFloatParamsRequest'] -_ACCESSFLOATPARAMSRESPONSE = DESCRIPTOR.message_types_by_name['AccessFloatParamsResponse'] -_FLOATPARAMUPDATE = DESCRIPTOR.message_types_by_name['FloatParamUpdate'] -_SUBSCRIBEFLOATPARAMREQUEST = DESCRIPTOR.message_types_by_name['SubscribeFloatParamRequest'] -_FLOATPARAMRESPONSE = DESCRIPTOR.message_types_by_name['FloatParamResponse'] -_COMPONENTINFORMATIONRESULT = DESCRIPTOR.message_types_by_name['ComponentInformationResult'] -_COMPONENTINFORMATIONRESULT_RESULT = _COMPONENTINFORMATIONRESULT.enum_types_by_name['Result'] -FloatParam = _reflection.GeneratedProtocolMessageType('FloatParam', (_message.Message,), { - 'DESCRIPTOR' : _FLOATPARAM, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParam) - }) +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n1component_information/component_information.proto\x12 mavsdk.rpc.component_information\x1a\x14mavsdk_options.proto"\xc7\x01\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\x19\n\x11short_description\x18\x02 \x01(\t\x12\x18\n\x10long_description\x18\x03 \x01(\t\x12\x0c\n\x04unit\x18\x04 \x01(\t\x12\x16\n\x0e\x64\x65\x63imal_places\x18\x05 \x01(\x05\x12\x13\n\x0bstart_value\x18\x06 \x01(\x02\x12\x15\n\rdefault_value\x18\x07 \x01(\x02\x12\x11\n\tmin_value\x18\x08 \x01(\x02\x12\x11\n\tmax_value\x18\t \x01(\x02"\x1a\n\x18\x41\x63\x63\x65ssFloatParamsRequest"\xbd\x01\n\x19\x41\x63\x63\x65ssFloatParamsResponse\x12\x62\n\x1c\x63omponent_information_result\x18\x01 \x01(\x0b\x32<.mavsdk.rpc.component_information.ComponentInformationResult\x12<\n\x06params\x18\x02 \x03(\x0b\x32,.mavsdk.rpc.component_information.FloatParam"/\n\x10\x46loatParamUpdate\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02"\x1c\n\x1aSubscribeFloatParamRequest"^\n\x12\x46loatParamResponse\x12H\n\x0cparam_update\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.component_information.FloatParamUpdate"\xcd\x01\n\x1a\x43omponentInformationResult\x12S\n\x06result\x18\x01 \x01(\x0e\x32\x43.mavsdk.rpc.component_information.ComponentInformationResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"F\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x03\x32\xc6\x02\n\x1b\x43omponentInformationService\x12\x92\x01\n\x11\x41\x63\x63\x65ssFloatParams\x12:.mavsdk.rpc.component_information.AccessFloatParamsRequest\x1a;.mavsdk.rpc.component_information.AccessFloatParamsResponse"\x04\x80\xb5\x18\x01\x12\x91\x01\n\x13SubscribeFloatParam\x12<.mavsdk.rpc.component_information.SubscribeFloatParamRequest\x1a\x34.mavsdk.rpc.component_information.FloatParamResponse"\x04\x80\xb5\x18\x00\x30\x01\x42<\n\x1fio.mavsdk.component_informationB\x19\x43omponentInformationProtob\x06proto3' +) + + +_FLOATPARAM = DESCRIPTOR.message_types_by_name["FloatParam"] +_ACCESSFLOATPARAMSREQUEST = DESCRIPTOR.message_types_by_name["AccessFloatParamsRequest"] +_ACCESSFLOATPARAMSRESPONSE = DESCRIPTOR.message_types_by_name[ + "AccessFloatParamsResponse" +] +_FLOATPARAMUPDATE = DESCRIPTOR.message_types_by_name["FloatParamUpdate"] +_SUBSCRIBEFLOATPARAMREQUEST = DESCRIPTOR.message_types_by_name[ + "SubscribeFloatParamRequest" +] +_FLOATPARAMRESPONSE = DESCRIPTOR.message_types_by_name["FloatParamResponse"] +_COMPONENTINFORMATIONRESULT = DESCRIPTOR.message_types_by_name[ + "ComponentInformationResult" +] +_COMPONENTINFORMATIONRESULT_RESULT = _COMPONENTINFORMATIONRESULT.enum_types_by_name[ + "Result" +] +FloatParam = _reflection.GeneratedProtocolMessageType( + "FloatParam", + (_message.Message,), + { + "DESCRIPTOR": _FLOATPARAM, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParam) + }, +) _sym_db.RegisterMessage(FloatParam) -AccessFloatParamsRequest = _reflection.GeneratedProtocolMessageType('AccessFloatParamsRequest', (_message.Message,), { - 'DESCRIPTOR' : _ACCESSFLOATPARAMSREQUEST, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.AccessFloatParamsRequest) - }) +AccessFloatParamsRequest = _reflection.GeneratedProtocolMessageType( + "AccessFloatParamsRequest", + (_message.Message,), + { + "DESCRIPTOR": _ACCESSFLOATPARAMSREQUEST, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.AccessFloatParamsRequest) + }, +) _sym_db.RegisterMessage(AccessFloatParamsRequest) -AccessFloatParamsResponse = _reflection.GeneratedProtocolMessageType('AccessFloatParamsResponse', (_message.Message,), { - 'DESCRIPTOR' : _ACCESSFLOATPARAMSRESPONSE, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.AccessFloatParamsResponse) - }) +AccessFloatParamsResponse = _reflection.GeneratedProtocolMessageType( + "AccessFloatParamsResponse", + (_message.Message,), + { + "DESCRIPTOR": _ACCESSFLOATPARAMSRESPONSE, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.AccessFloatParamsResponse) + }, +) _sym_db.RegisterMessage(AccessFloatParamsResponse) -FloatParamUpdate = _reflection.GeneratedProtocolMessageType('FloatParamUpdate', (_message.Message,), { - 'DESCRIPTOR' : _FLOATPARAMUPDATE, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParamUpdate) - }) +FloatParamUpdate = _reflection.GeneratedProtocolMessageType( + "FloatParamUpdate", + (_message.Message,), + { + "DESCRIPTOR": _FLOATPARAMUPDATE, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParamUpdate) + }, +) _sym_db.RegisterMessage(FloatParamUpdate) -SubscribeFloatParamRequest = _reflection.GeneratedProtocolMessageType('SubscribeFloatParamRequest', (_message.Message,), { - 'DESCRIPTOR' : _SUBSCRIBEFLOATPARAMREQUEST, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.SubscribeFloatParamRequest) - }) +SubscribeFloatParamRequest = _reflection.GeneratedProtocolMessageType( + "SubscribeFloatParamRequest", + (_message.Message,), + { + "DESCRIPTOR": _SUBSCRIBEFLOATPARAMREQUEST, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.SubscribeFloatParamRequest) + }, +) _sym_db.RegisterMessage(SubscribeFloatParamRequest) -FloatParamResponse = _reflection.GeneratedProtocolMessageType('FloatParamResponse', (_message.Message,), { - 'DESCRIPTOR' : _FLOATPARAMRESPONSE, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParamResponse) - }) +FloatParamResponse = _reflection.GeneratedProtocolMessageType( + "FloatParamResponse", + (_message.Message,), + { + "DESCRIPTOR": _FLOATPARAMRESPONSE, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.FloatParamResponse) + }, +) _sym_db.RegisterMessage(FloatParamResponse) -ComponentInformationResult = _reflection.GeneratedProtocolMessageType('ComponentInformationResult', (_message.Message,), { - 'DESCRIPTOR' : _COMPONENTINFORMATIONRESULT, - '__module__' : 'component_information.component_information_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.ComponentInformationResult) - }) +ComponentInformationResult = _reflection.GeneratedProtocolMessageType( + "ComponentInformationResult", + (_message.Message,), + { + "DESCRIPTOR": _COMPONENTINFORMATIONRESULT, + "__module__": "component_information.component_information_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information.ComponentInformationResult) + }, +) _sym_db.RegisterMessage(ComponentInformationResult) -_COMPONENTINFORMATIONSERVICE = DESCRIPTOR.services_by_name['ComponentInformationService'] +_COMPONENTINFORMATIONSERVICE = DESCRIPTOR.services_by_name[ + "ComponentInformationService" +] if _descriptor._USE_C_DESCRIPTORS == False: - - DESCRIPTOR._options = None - DESCRIPTOR._serialized_options = b'\n\037io.mavsdk.component_informationB\031ComponentInformationProto' - _COMPONENTINFORMATIONSERVICE.methods_by_name['AccessFloatParams']._options = None - _COMPONENTINFORMATIONSERVICE.methods_by_name['AccessFloatParams']._serialized_options = b'\200\265\030\001' - _COMPONENTINFORMATIONSERVICE.methods_by_name['SubscribeFloatParam']._options = None - _COMPONENTINFORMATIONSERVICE.methods_by_name['SubscribeFloatParam']._serialized_options = b'\200\265\030\000' - _FLOATPARAM._serialized_start=110 - _FLOATPARAM._serialized_end=309 - _ACCESSFLOATPARAMSREQUEST._serialized_start=311 - _ACCESSFLOATPARAMSREQUEST._serialized_end=337 - _ACCESSFLOATPARAMSRESPONSE._serialized_start=340 - _ACCESSFLOATPARAMSRESPONSE._serialized_end=529 - _FLOATPARAMUPDATE._serialized_start=531 - _FLOATPARAMUPDATE._serialized_end=578 - _SUBSCRIBEFLOATPARAMREQUEST._serialized_start=580 - _SUBSCRIBEFLOATPARAMREQUEST._serialized_end=608 - _FLOATPARAMRESPONSE._serialized_start=610 - _FLOATPARAMRESPONSE._serialized_end=704 - _COMPONENTINFORMATIONRESULT._serialized_start=707 - _COMPONENTINFORMATIONRESULT._serialized_end=912 - _COMPONENTINFORMATIONRESULT_RESULT._serialized_start=842 - _COMPONENTINFORMATIONRESULT_RESULT._serialized_end=912 - _COMPONENTINFORMATIONSERVICE._serialized_start=915 - _COMPONENTINFORMATIONSERVICE._serialized_end=1241 + DESCRIPTOR._options = None + DESCRIPTOR._serialized_options = ( + b"\n\037io.mavsdk.component_informationB\031ComponentInformationProto" + ) + _COMPONENTINFORMATIONSERVICE.methods_by_name["AccessFloatParams"]._options = None + _COMPONENTINFORMATIONSERVICE.methods_by_name[ + "AccessFloatParams" + ]._serialized_options = b"\200\265\030\001" + _COMPONENTINFORMATIONSERVICE.methods_by_name["SubscribeFloatParam"]._options = None + _COMPONENTINFORMATIONSERVICE.methods_by_name[ + "SubscribeFloatParam" + ]._serialized_options = b"\200\265\030\000" + _FLOATPARAM._serialized_start = 110 + _FLOATPARAM._serialized_end = 309 + _ACCESSFLOATPARAMSREQUEST._serialized_start = 311 + _ACCESSFLOATPARAMSREQUEST._serialized_end = 337 + _ACCESSFLOATPARAMSRESPONSE._serialized_start = 340 + _ACCESSFLOATPARAMSRESPONSE._serialized_end = 529 + _FLOATPARAMUPDATE._serialized_start = 531 + _FLOATPARAMUPDATE._serialized_end = 578 + _SUBSCRIBEFLOATPARAMREQUEST._serialized_start = 580 + _SUBSCRIBEFLOATPARAMREQUEST._serialized_end = 608 + _FLOATPARAMRESPONSE._serialized_start = 610 + _FLOATPARAMRESPONSE._serialized_end = 704 + _COMPONENTINFORMATIONRESULT._serialized_start = 707 + _COMPONENTINFORMATIONRESULT._serialized_end = 912 + _COMPONENTINFORMATIONRESULT_RESULT._serialized_start = 842 + _COMPONENTINFORMATIONRESULT_RESULT._serialized_end = 912 + _COMPONENTINFORMATIONSERVICE._serialized_start = 915 + _COMPONENTINFORMATIONSERVICE._serialized_end = 1241 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/component_information_pb2_grpc.py b/mavsdk/component_information_pb2_grpc.py index 7f0036aa..185bf578 100644 --- a/mavsdk/component_information_pb2_grpc.py +++ b/mavsdk/component_information_pb2_grpc.py @@ -1,13 +1,15 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc -from . import component_information_pb2 as component__information_dot_component__information__pb2 +from . import ( + component_information_pb2 as component__information_dot_component__information__pb2, +) class ComponentInformationServiceStub(object): - """Access component information such as parameters. - """ + """Access component information such as parameters.""" def __init__(self, channel): """Constructor. @@ -16,91 +18,115 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.AccessFloatParams = channel.unary_unary( - '/mavsdk.rpc.component_information.ComponentInformationService/AccessFloatParams', - request_serializer=component__information_dot_component__information__pb2.AccessFloatParamsRequest.SerializeToString, - response_deserializer=component__information_dot_component__information__pb2.AccessFloatParamsResponse.FromString, - ) + "/mavsdk.rpc.component_information.ComponentInformationService/AccessFloatParams", + request_serializer=component__information_dot_component__information__pb2.AccessFloatParamsRequest.SerializeToString, + response_deserializer=component__information_dot_component__information__pb2.AccessFloatParamsResponse.FromString, + ) self.SubscribeFloatParam = channel.unary_stream( - '/mavsdk.rpc.component_information.ComponentInformationService/SubscribeFloatParam', - request_serializer=component__information_dot_component__information__pb2.SubscribeFloatParamRequest.SerializeToString, - response_deserializer=component__information_dot_component__information__pb2.FloatParamResponse.FromString, - ) + "/mavsdk.rpc.component_information.ComponentInformationService/SubscribeFloatParam", + request_serializer=component__information_dot_component__information__pb2.SubscribeFloatParamRequest.SerializeToString, + response_deserializer=component__information_dot_component__information__pb2.FloatParamResponse.FromString, + ) class ComponentInformationServiceServicer(object): - """Access component information such as parameters. - """ + """Access component information such as parameters.""" def AccessFloatParams(self, request, context): """ List available float params. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFloatParam(self, request, context): """ Subscribe to float param changes/updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ComponentInformationServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'AccessFloatParams': grpc.unary_unary_rpc_method_handler( - servicer.AccessFloatParams, - request_deserializer=component__information_dot_component__information__pb2.AccessFloatParamsRequest.FromString, - response_serializer=component__information_dot_component__information__pb2.AccessFloatParamsResponse.SerializeToString, - ), - 'SubscribeFloatParam': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFloatParam, - request_deserializer=component__information_dot_component__information__pb2.SubscribeFloatParamRequest.FromString, - response_serializer=component__information_dot_component__information__pb2.FloatParamResponse.SerializeToString, - ), + "AccessFloatParams": grpc.unary_unary_rpc_method_handler( + servicer.AccessFloatParams, + request_deserializer=component__information_dot_component__information__pb2.AccessFloatParamsRequest.FromString, + response_serializer=component__information_dot_component__information__pb2.AccessFloatParamsResponse.SerializeToString, + ), + "SubscribeFloatParam": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFloatParam, + request_deserializer=component__information_dot_component__information__pb2.SubscribeFloatParamRequest.FromString, + response_serializer=component__information_dot_component__information__pb2.FloatParamResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.component_information.ComponentInformationService', rpc_method_handlers) + "mavsdk.rpc.component_information.ComponentInformationService", + rpc_method_handlers, + ) server.add_generic_rpc_handlers((generic_handler,)) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ComponentInformationService(object): - """Access component information such as parameters. - """ + """Access component information such as parameters.""" @staticmethod - def AccessFloatParams(request, + def AccessFloatParams( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.component_information.ComponentInformationService/AccessFloatParams', + "/mavsdk.rpc.component_information.ComponentInformationService/AccessFloatParams", component__information_dot_component__information__pb2.AccessFloatParamsRequest.SerializeToString, component__information_dot_component__information__pb2.AccessFloatParamsResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SubscribeFloatParam(request, + def SubscribeFloatParam( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_stream( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.component_information.ComponentInformationService/SubscribeFloatParam', + "/mavsdk.rpc.component_information.ComponentInformationService/SubscribeFloatParam", component__information_dot_component__information__pb2.SubscribeFloatParamRequest.SerializeToString, component__information_dot_component__information__pb2.FloatParamResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) diff --git a/mavsdk/component_information_server.py b/mavsdk/component_information_server.py index 70355101..9e8fd789 100644 --- a/mavsdk/component_information_server.py +++ b/mavsdk/component_information_server.py @@ -8,53 +8,52 @@ class FloatParam: """ - Meta information for parameter of type float. + Meta information for parameter of type float. - Parameters - ---------- - name : std::string - Name (max 16 chars) + Parameters + ---------- + name : std::string + Name (max 16 chars) - short_description : std::string - Short description + short_description : std::string + Short description - long_description : std::string - Long description + long_description : std::string + Long description - unit : std::string - Unit + unit : std::string + Unit - decimal_places : int32_t - Decimal places for user to show + decimal_places : int32_t + Decimal places for user to show - start_value : float - Current/starting value + start_value : float + Current/starting value - default_value : float - Default value + default_value : float + Default value - min_value : float - Minimum value + min_value : float + Minimum value - max_value : float - Maximum value + max_value : float + Maximum value - """ - - + """ def __init__( - self, - name, - short_description, - long_description, - unit, - decimal_places, - start_value, - default_value, - min_value, - max_value): - """ Initializes the FloatParam object """ + self, + name, + short_description, + long_description, + unit, + decimal_places, + start_value, + default_value, + min_value, + max_value, + ): + """Initializes the FloatParam object""" self.name = name self.short_description = short_description self.long_description = long_description @@ -66,27 +65,29 @@ def __init__( self.max_value = max_value def __eq__(self, to_compare): - """ Checks if two FloatParam are the same """ + """Checks if two FloatParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # FloatParam object - return \ - (self.name == to_compare.name) and \ - (self.short_description == to_compare.short_description) and \ - (self.long_description == to_compare.long_description) and \ - (self.unit == to_compare.unit) and \ - (self.decimal_places == to_compare.decimal_places) and \ - (self.start_value == to_compare.start_value) and \ - (self.default_value == to_compare.default_value) and \ - (self.min_value == to_compare.min_value) and \ - (self.max_value == to_compare.max_value) + return ( + (self.name == to_compare.name) + and (self.short_description == to_compare.short_description) + and (self.long_description == to_compare.long_description) + and (self.unit == to_compare.unit) + and (self.decimal_places == to_compare.decimal_places) + and (self.start_value == to_compare.start_value) + and (self.default_value == to_compare.default_value) + and (self.min_value == to_compare.min_value) + and (self.max_value == to_compare.max_value) + ) except AttributeError: return False def __str__(self): - """ FloatParam in string representation """ - struct_repr = ", ".join([ + """FloatParam in string representation""" + struct_repr = ", ".join( + [ "name: " + str(self.name), "short_description: " + str(self.short_description), "long_description: " + str(self.long_description), @@ -95,223 +96,142 @@ def __str__(self): "start_value: " + str(self.start_value), "default_value: " + str(self.default_value), "min_value: " + str(self.min_value), - "max_value: " + str(self.max_value) - ]) + "max_value: " + str(self.max_value), + ] + ) return f"FloatParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFloatParam): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FloatParam( - - rpcFloatParam.name, - - - rpcFloatParam.short_description, - - - rpcFloatParam.long_description, - - - rpcFloatParam.unit, - - - rpcFloatParam.decimal_places, - - - rpcFloatParam.start_value, - - - rpcFloatParam.default_value, - - - rpcFloatParam.min_value, - - - rpcFloatParam.max_value - ) + rpcFloatParam.name, + rpcFloatParam.short_description, + rpcFloatParam.long_description, + rpcFloatParam.unit, + rpcFloatParam.decimal_places, + rpcFloatParam.start_value, + rpcFloatParam.default_value, + rpcFloatParam.min_value, + rpcFloatParam.max_value, + ) def translate_to_rpc(self, rpcFloatParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFloatParam.name = self.name - - - - - + rpcFloatParam.short_description = self.short_description - - - - - + rpcFloatParam.long_description = self.long_description - - - - - + rpcFloatParam.unit = self.unit - - - - - + rpcFloatParam.decimal_places = self.decimal_places - - - - - + rpcFloatParam.start_value = self.start_value - - - - - + rpcFloatParam.default_value = self.default_value - - - - - + rpcFloatParam.min_value = self.min_value - - - - - + rpcFloatParam.max_value = self.max_value - - - class FloatParamUpdate: """ - A float param that has been updated. + A float param that has been updated. - Parameters - ---------- - name : std::string - Name of param that changed + Parameters + ---------- + name : std::string + Name of param that changed - value : float - New value of param + value : float + New value of param - """ - - + """ - def __init__( - self, - name, - value): - """ Initializes the FloatParamUpdate object """ + def __init__(self, name, value): + """Initializes the FloatParamUpdate object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two FloatParamUpdate are the same """ + """Checks if two FloatParamUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # FloatParamUpdate object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ FloatParamUpdate in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """FloatParamUpdate in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"FloatParamUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFloatParamUpdate): - """ Translates a gRPC struct to the SDK equivalent """ - return FloatParamUpdate( - - rpcFloatParamUpdate.name, - - - rpcFloatParamUpdate.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return FloatParamUpdate(rpcFloatParamUpdate.name, rpcFloatParamUpdate.value) def translate_to_rpc(self, rpcFloatParamUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFloatParamUpdate.name = self.name - - - - - + rpcFloatParamUpdate.value = self.value - - - class ComponentInformationServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for param requests. + Possible results returned for param requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - DUPLICATE_PARAM - Duplicate param + DUPLICATE_PARAM + Duplicate param - INVALID_PARAM_START_VALUE - Invalid start param value + INVALID_PARAM_START_VALUE + Invalid start param value - INVALID_PARAM_DEFAULT_VALUE - Invalid default param value + INVALID_PARAM_DEFAULT_VALUE + Invalid default param value - INVALID_PARAM_NAME - Invalid param name + INVALID_PARAM_NAME + Invalid param name - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 DUPLICATE_PARAM = 2 @@ -327,9 +247,15 @@ def translate_to_rpc(self): return component_information_server_pb2.ComponentInformationServerResult.RESULT_SUCCESS if self == ComponentInformationServerResult.Result.DUPLICATE_PARAM: return component_information_server_pb2.ComponentInformationServerResult.RESULT_DUPLICATE_PARAM - if self == ComponentInformationServerResult.Result.INVALID_PARAM_START_VALUE: + if ( + self + == ComponentInformationServerResult.Result.INVALID_PARAM_START_VALUE + ): return component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_START_VALUE - if self == ComponentInformationServerResult.Result.INVALID_PARAM_DEFAULT_VALUE: + if ( + self + == ComponentInformationServerResult.Result.INVALID_PARAM_DEFAULT_VALUE + ): return component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_DEFAULT_VALUE if self == ComponentInformationServerResult.Result.INVALID_PARAM_NAME: return component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_NAME @@ -338,87 +264,93 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_UNKNOWN + ): return ComponentInformationServerResult.Result.UNKNOWN - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_SUCCESS: + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_SUCCESS + ): return ComponentInformationServerResult.Result.SUCCESS - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_DUPLICATE_PARAM: + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_DUPLICATE_PARAM + ): return ComponentInformationServerResult.Result.DUPLICATE_PARAM - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_START_VALUE: + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_START_VALUE + ): return ComponentInformationServerResult.Result.INVALID_PARAM_START_VALUE - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_DEFAULT_VALUE: - return ComponentInformationServerResult.Result.INVALID_PARAM_DEFAULT_VALUE - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_NAME: + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_DEFAULT_VALUE + ): + return ( + ComponentInformationServerResult.Result.INVALID_PARAM_DEFAULT_VALUE + ) + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_INVALID_PARAM_NAME + ): return ComponentInformationServerResult.Result.INVALID_PARAM_NAME - if rpc_enum_value == component_information_server_pb2.ComponentInformationServerResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == component_information_server_pb2.ComponentInformationServerResult.RESULT_NO_SYSTEM + ): return ComponentInformationServerResult.Result.NO_SYSTEM def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ComponentInformationServerResult object """ + def __init__(self, result, result_str): + """Initializes the ComponentInformationServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ComponentInformationServerResult are the same """ + """Checks if two ComponentInformationServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ComponentInformationServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ComponentInformationServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ComponentInformationServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ComponentInformationServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcComponentInformationServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ComponentInformationServerResult( - - ComponentInformationServerResult.Result.translate_from_rpc(rpcComponentInformationServerResult.result), - - - rpcComponentInformationServerResult.result_str - ) + ComponentInformationServerResult.Result.translate_from_rpc( + rpcComponentInformationServerResult.result + ), + rpcComponentInformationServerResult.result_str, + ) def translate_to_rpc(self, rpcComponentInformationServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcComponentInformationServerResult.result = self.result.translate_to_rpc() - - - - - - rpcComponentInformationServerResult.result_str = self.result_str - - - + rpcComponentInformationServerResult.result_str = self.result_str class ComponentInformationServerError(Exception): - """ Raised when a ComponentInformationServerResult is a fail code """ + """Raised when a ComponentInformationServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -431,63 +363,66 @@ def __str__(self): class ComponentInformationServer(AsyncBase): """ - Provide component information such as parameters. + Provide component information such as parameters. - Generated by dcsdkgen - MAVSDK ComponentInformationServer API + Generated by dcsdkgen - MAVSDK ComponentInformationServer API """ # Plugin name name = "ComponentInformationServer" def _setup_stub(self, channel): - """ Setups the api stub """ - self._stub = component_information_server_pb2_grpc.ComponentInformationServerServiceStub(channel) + """Setups the api stub""" + self._stub = ( + component_information_server_pb2_grpc.ComponentInformationServerServiceStub( + channel + ) + ) - def _extract_result(self, response): - """ Returns the response status and description """ - return ComponentInformationServerResult.translate_from_rpc(response.component_information_server_result) - + """Returns the response status and description""" + return ComponentInformationServerResult.translate_from_rpc( + response.component_information_server_result + ) async def provide_float_param(self, param): """ - Provide a param of type float. + Provide a param of type float. - Parameters - ---------- - param : FloatParam - Float param definition + Parameters + ---------- + param : FloatParam + Float param definition - Raises - ------ - ComponentInformationServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ComponentInformationServerError + If the request fails. The error contains the reason for the failure. """ request = component_information_server_pb2.ProvideFloatParamRequest() - + param.translate_to_rpc(request.param) - - + response = await self._stub.ProvideFloatParam(request) - result = self._extract_result(response) if result.result != ComponentInformationServerResult.Result.SUCCESS: - raise ComponentInformationServerError(result, "provide_float_param()", param) - + raise ComponentInformationServerError( + result, "provide_float_param()", param + ) async def float_param(self): """ - Subscribe to float param updates. + Subscribe to float param updates. + + Yields + ------- + param_update : FloatParamUpdate + A param update - Yields - ------- - param_update : FloatParamUpdate - A param update - """ request = component_information_server_pb2.SubscribeFloatParamRequest() @@ -495,9 +430,6 @@ async def float_param(self): try: async for response in float_param_stream: - - - yield FloatParamUpdate.translate_from_rpc(response.param_update) finally: - float_param_stream.cancel() \ No newline at end of file + float_param_stream.cancel() diff --git a/mavsdk/component_information_server_pb2.py b/mavsdk/component_information_server_pb2.py index e57533ab..912a840c 100644 --- a/mavsdk/component_information_server_pb2.py +++ b/mavsdk/component_information_server_pb2.py @@ -2,6 +2,7 @@ # Generated by the protocol buffer compiler. DO NOT EDIT! # source: component_information_server/component_information_server.proto """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import message as _message @@ -15,92 +16,140 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n?component_information_server/component_information_server.proto\x12\'mavsdk.rpc.component_information_server\x1a\x14mavsdk_options.proto\"\xc7\x01\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\x19\n\x11short_description\x18\x02 \x01(\t\x12\x18\n\x10long_description\x18\x03 \x01(\t\x12\x0c\n\x04unit\x18\x04 \x01(\t\x12\x16\n\x0e\x64\x65\x63imal_places\x18\x05 \x01(\x05\x12\x13\n\x0bstart_value\x18\x06 \x01(\x02\x12\x15\n\rdefault_value\x18\x07 \x01(\x02\x12\x11\n\tmin_value\x18\x08 \x01(\x02\x12\x11\n\tmax_value\x18\t \x01(\x02\"^\n\x18ProvideFloatParamRequest\x12\x42\n\x05param\x18\x01 \x01(\x0b\x32\x33.mavsdk.rpc.component_information_server.FloatParam\"\x93\x01\n\x19ProvideFloatParamResponse\x12v\n#component_information_server_result\x18\x01 \x01(\x0b\x32I.mavsdk.rpc.component_information_server.ComponentInformationServerResult\"/\n\x10\x46loatParamUpdate\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02\"\x1c\n\x1aSubscribeFloatParamRequest\"e\n\x12\x46loatParamResponse\x12O\n\x0cparam_update\x18\x01 \x01(\x0b\x32\x39.mavsdk.rpc.component_information_server.FloatParamUpdate\"\xea\x02\n ComponentInformationServerResult\x12`\n\x06result\x18\x01 \x01(\x0e\x32P.mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xcf\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x1a\n\x16RESULT_DUPLICATE_PARAM\x10\x02\x12$\n RESULT_INVALID_PARAM_START_VALUE\x10\x03\x12&\n\"RESULT_INVALID_PARAM_DEFAULT_VALUE\x10\x04\x12\x1d\n\x19RESULT_INVALID_PARAM_NAME\x10\x05\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x06\x32\xe8\x02\n!ComponentInformationServerService\x12\xa0\x01\n\x11ProvideFloatParam\x12\x41.mavsdk.rpc.component_information_server.ProvideFloatParamRequest\x1a\x42.mavsdk.rpc.component_information_server.ProvideFloatParamResponse\"\x04\x80\xb5\x18\x01\x12\x9f\x01\n\x13SubscribeFloatParam\x12\x43.mavsdk.rpc.component_information_server.SubscribeFloatParamRequest\x1a;.mavsdk.rpc.component_information_server.FloatParamResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42I\n&io.mavsdk.component_information_serverB\x1f\x43omponentInformationServerProtob\x06proto3') - - - -_FLOATPARAM = DESCRIPTOR.message_types_by_name['FloatParam'] -_PROVIDEFLOATPARAMREQUEST = DESCRIPTOR.message_types_by_name['ProvideFloatParamRequest'] -_PROVIDEFLOATPARAMRESPONSE = DESCRIPTOR.message_types_by_name['ProvideFloatParamResponse'] -_FLOATPARAMUPDATE = DESCRIPTOR.message_types_by_name['FloatParamUpdate'] -_SUBSCRIBEFLOATPARAMREQUEST = DESCRIPTOR.message_types_by_name['SubscribeFloatParamRequest'] -_FLOATPARAMRESPONSE = DESCRIPTOR.message_types_by_name['FloatParamResponse'] -_COMPONENTINFORMATIONSERVERRESULT = DESCRIPTOR.message_types_by_name['ComponentInformationServerResult'] -_COMPONENTINFORMATIONSERVERRESULT_RESULT = _COMPONENTINFORMATIONSERVERRESULT.enum_types_by_name['Result'] -FloatParam = _reflection.GeneratedProtocolMessageType('FloatParam', (_message.Message,), { - 'DESCRIPTOR' : _FLOATPARAM, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParam) - }) +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n?component_information_server/component_information_server.proto\x12\'mavsdk.rpc.component_information_server\x1a\x14mavsdk_options.proto"\xc7\x01\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\x19\n\x11short_description\x18\x02 \x01(\t\x12\x18\n\x10long_description\x18\x03 \x01(\t\x12\x0c\n\x04unit\x18\x04 \x01(\t\x12\x16\n\x0e\x64\x65\x63imal_places\x18\x05 \x01(\x05\x12\x13\n\x0bstart_value\x18\x06 \x01(\x02\x12\x15\n\rdefault_value\x18\x07 \x01(\x02\x12\x11\n\tmin_value\x18\x08 \x01(\x02\x12\x11\n\tmax_value\x18\t \x01(\x02"^\n\x18ProvideFloatParamRequest\x12\x42\n\x05param\x18\x01 \x01(\x0b\x32\x33.mavsdk.rpc.component_information_server.FloatParam"\x93\x01\n\x19ProvideFloatParamResponse\x12v\n#component_information_server_result\x18\x01 \x01(\x0b\x32I.mavsdk.rpc.component_information_server.ComponentInformationServerResult"/\n\x10\x46loatParamUpdate\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02"\x1c\n\x1aSubscribeFloatParamRequest"e\n\x12\x46loatParamResponse\x12O\n\x0cparam_update\x18\x01 \x01(\x0b\x32\x39.mavsdk.rpc.component_information_server.FloatParamUpdate"\xea\x02\n ComponentInformationServerResult\x12`\n\x06result\x18\x01 \x01(\x0e\x32P.mavsdk.rpc.component_information_server.ComponentInformationServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xcf\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x1a\n\x16RESULT_DUPLICATE_PARAM\x10\x02\x12$\n RESULT_INVALID_PARAM_START_VALUE\x10\x03\x12&\n"RESULT_INVALID_PARAM_DEFAULT_VALUE\x10\x04\x12\x1d\n\x19RESULT_INVALID_PARAM_NAME\x10\x05\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x06\x32\xe8\x02\n!ComponentInformationServerService\x12\xa0\x01\n\x11ProvideFloatParam\x12\x41.mavsdk.rpc.component_information_server.ProvideFloatParamRequest\x1a\x42.mavsdk.rpc.component_information_server.ProvideFloatParamResponse"\x04\x80\xb5\x18\x01\x12\x9f\x01\n\x13SubscribeFloatParam\x12\x43.mavsdk.rpc.component_information_server.SubscribeFloatParamRequest\x1a;.mavsdk.rpc.component_information_server.FloatParamResponse"\x04\x80\xb5\x18\x00\x30\x01\x42I\n&io.mavsdk.component_information_serverB\x1f\x43omponentInformationServerProtob\x06proto3' +) + + +_FLOATPARAM = DESCRIPTOR.message_types_by_name["FloatParam"] +_PROVIDEFLOATPARAMREQUEST = DESCRIPTOR.message_types_by_name["ProvideFloatParamRequest"] +_PROVIDEFLOATPARAMRESPONSE = DESCRIPTOR.message_types_by_name[ + "ProvideFloatParamResponse" +] +_FLOATPARAMUPDATE = DESCRIPTOR.message_types_by_name["FloatParamUpdate"] +_SUBSCRIBEFLOATPARAMREQUEST = DESCRIPTOR.message_types_by_name[ + "SubscribeFloatParamRequest" +] +_FLOATPARAMRESPONSE = DESCRIPTOR.message_types_by_name["FloatParamResponse"] +_COMPONENTINFORMATIONSERVERRESULT = DESCRIPTOR.message_types_by_name[ + "ComponentInformationServerResult" +] +_COMPONENTINFORMATIONSERVERRESULT_RESULT = ( + _COMPONENTINFORMATIONSERVERRESULT.enum_types_by_name["Result"] +) +FloatParam = _reflection.GeneratedProtocolMessageType( + "FloatParam", + (_message.Message,), + { + "DESCRIPTOR": _FLOATPARAM, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParam) + }, +) _sym_db.RegisterMessage(FloatParam) -ProvideFloatParamRequest = _reflection.GeneratedProtocolMessageType('ProvideFloatParamRequest', (_message.Message,), { - 'DESCRIPTOR' : _PROVIDEFLOATPARAMREQUEST, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) - }) +ProvideFloatParamRequest = _reflection.GeneratedProtocolMessageType( + "ProvideFloatParamRequest", + (_message.Message,), + { + "DESCRIPTOR": _PROVIDEFLOATPARAMREQUEST, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvideFloatParamRequest) + }, +) _sym_db.RegisterMessage(ProvideFloatParamRequest) -ProvideFloatParamResponse = _reflection.GeneratedProtocolMessageType('ProvideFloatParamResponse', (_message.Message,), { - 'DESCRIPTOR' : _PROVIDEFLOATPARAMRESPONSE, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) - }) +ProvideFloatParamResponse = _reflection.GeneratedProtocolMessageType( + "ProvideFloatParamResponse", + (_message.Message,), + { + "DESCRIPTOR": _PROVIDEFLOATPARAMRESPONSE, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ProvideFloatParamResponse) + }, +) _sym_db.RegisterMessage(ProvideFloatParamResponse) -FloatParamUpdate = _reflection.GeneratedProtocolMessageType('FloatParamUpdate', (_message.Message,), { - 'DESCRIPTOR' : _FLOATPARAMUPDATE, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParamUpdate) - }) +FloatParamUpdate = _reflection.GeneratedProtocolMessageType( + "FloatParamUpdate", + (_message.Message,), + { + "DESCRIPTOR": _FLOATPARAMUPDATE, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParamUpdate) + }, +) _sym_db.RegisterMessage(FloatParamUpdate) -SubscribeFloatParamRequest = _reflection.GeneratedProtocolMessageType('SubscribeFloatParamRequest', (_message.Message,), { - 'DESCRIPTOR' : _SUBSCRIBEFLOATPARAMREQUEST, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.SubscribeFloatParamRequest) - }) +SubscribeFloatParamRequest = _reflection.GeneratedProtocolMessageType( + "SubscribeFloatParamRequest", + (_message.Message,), + { + "DESCRIPTOR": _SUBSCRIBEFLOATPARAMREQUEST, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.SubscribeFloatParamRequest) + }, +) _sym_db.RegisterMessage(SubscribeFloatParamRequest) -FloatParamResponse = _reflection.GeneratedProtocolMessageType('FloatParamResponse', (_message.Message,), { - 'DESCRIPTOR' : _FLOATPARAMRESPONSE, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParamResponse) - }) +FloatParamResponse = _reflection.GeneratedProtocolMessageType( + "FloatParamResponse", + (_message.Message,), + { + "DESCRIPTOR": _FLOATPARAMRESPONSE, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.FloatParamResponse) + }, +) _sym_db.RegisterMessage(FloatParamResponse) -ComponentInformationServerResult = _reflection.GeneratedProtocolMessageType('ComponentInformationServerResult', (_message.Message,), { - 'DESCRIPTOR' : _COMPONENTINFORMATIONSERVERRESULT, - '__module__' : 'component_information_server.component_information_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ComponentInformationServerResult) - }) +ComponentInformationServerResult = _reflection.GeneratedProtocolMessageType( + "ComponentInformationServerResult", + (_message.Message,), + { + "DESCRIPTOR": _COMPONENTINFORMATIONSERVERRESULT, + "__module__": "component_information_server.component_information_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.component_information_server.ComponentInformationServerResult) + }, +) _sym_db.RegisterMessage(ComponentInformationServerResult) -_COMPONENTINFORMATIONSERVERSERVICE = DESCRIPTOR.services_by_name['ComponentInformationServerService'] +_COMPONENTINFORMATIONSERVERSERVICE = DESCRIPTOR.services_by_name[ + "ComponentInformationServerService" +] if _descriptor._USE_C_DESCRIPTORS == False: - - DESCRIPTOR._options = None - DESCRIPTOR._serialized_options = b'\n&io.mavsdk.component_information_serverB\037ComponentInformationServerProto' - _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name['ProvideFloatParam']._options = None - _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name['ProvideFloatParam']._serialized_options = b'\200\265\030\001' - _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name['SubscribeFloatParam']._options = None - _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name['SubscribeFloatParam']._serialized_options = b'\200\265\030\000' - _FLOATPARAM._serialized_start=131 - _FLOATPARAM._serialized_end=330 - _PROVIDEFLOATPARAMREQUEST._serialized_start=332 - _PROVIDEFLOATPARAMREQUEST._serialized_end=426 - _PROVIDEFLOATPARAMRESPONSE._serialized_start=429 - _PROVIDEFLOATPARAMRESPONSE._serialized_end=576 - _FLOATPARAMUPDATE._serialized_start=578 - _FLOATPARAMUPDATE._serialized_end=625 - _SUBSCRIBEFLOATPARAMREQUEST._serialized_start=627 - _SUBSCRIBEFLOATPARAMREQUEST._serialized_end=655 - _FLOATPARAMRESPONSE._serialized_start=657 - _FLOATPARAMRESPONSE._serialized_end=758 - _COMPONENTINFORMATIONSERVERRESULT._serialized_start=761 - _COMPONENTINFORMATIONSERVERRESULT._serialized_end=1123 - _COMPONENTINFORMATIONSERVERRESULT_RESULT._serialized_start=916 - _COMPONENTINFORMATIONSERVERRESULT_RESULT._serialized_end=1123 - _COMPONENTINFORMATIONSERVERSERVICE._serialized_start=1126 - _COMPONENTINFORMATIONSERVERSERVICE._serialized_end=1486 + DESCRIPTOR._options = None + DESCRIPTOR._serialized_options = ( + b"\n&io.mavsdk.component_information_serverB\037ComponentInformationServerProto" + ) + _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name[ + "ProvideFloatParam" + ]._options = None + _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name[ + "ProvideFloatParam" + ]._serialized_options = b"\200\265\030\001" + _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name[ + "SubscribeFloatParam" + ]._options = None + _COMPONENTINFORMATIONSERVERSERVICE.methods_by_name[ + "SubscribeFloatParam" + ]._serialized_options = b"\200\265\030\000" + _FLOATPARAM._serialized_start = 131 + _FLOATPARAM._serialized_end = 330 + _PROVIDEFLOATPARAMREQUEST._serialized_start = 332 + _PROVIDEFLOATPARAMREQUEST._serialized_end = 426 + _PROVIDEFLOATPARAMRESPONSE._serialized_start = 429 + _PROVIDEFLOATPARAMRESPONSE._serialized_end = 576 + _FLOATPARAMUPDATE._serialized_start = 578 + _FLOATPARAMUPDATE._serialized_end = 625 + _SUBSCRIBEFLOATPARAMREQUEST._serialized_start = 627 + _SUBSCRIBEFLOATPARAMREQUEST._serialized_end = 655 + _FLOATPARAMRESPONSE._serialized_start = 657 + _FLOATPARAMRESPONSE._serialized_end = 758 + _COMPONENTINFORMATIONSERVERRESULT._serialized_start = 761 + _COMPONENTINFORMATIONSERVERRESULT._serialized_end = 1123 + _COMPONENTINFORMATIONSERVERRESULT_RESULT._serialized_start = 916 + _COMPONENTINFORMATIONSERVERRESULT_RESULT._serialized_end = 1123 + _COMPONENTINFORMATIONSERVERSERVICE._serialized_start = 1126 + _COMPONENTINFORMATIONSERVERSERVICE._serialized_end = 1486 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/component_information_server_pb2_grpc.py b/mavsdk/component_information_server_pb2_grpc.py index 304b914a..e1676d0d 100644 --- a/mavsdk/component_information_server_pb2_grpc.py +++ b/mavsdk/component_information_server_pb2_grpc.py @@ -1,13 +1,15 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc -from . import component_information_server_pb2 as component__information__server_dot_component__information__server__pb2 +from . import ( + component_information_server_pb2 as component__information__server_dot_component__information__server__pb2, +) class ComponentInformationServerServiceStub(object): - """Provide component information such as parameters. - """ + """Provide component information such as parameters.""" def __init__(self, channel): """Constructor. @@ -16,91 +18,115 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.ProvideFloatParam = channel.unary_unary( - '/mavsdk.rpc.component_information_server.ComponentInformationServerService/ProvideFloatParam', - request_serializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamRequest.SerializeToString, - response_deserializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamResponse.FromString, - ) + "/mavsdk.rpc.component_information_server.ComponentInformationServerService/ProvideFloatParam", + request_serializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamRequest.SerializeToString, + response_deserializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamResponse.FromString, + ) self.SubscribeFloatParam = channel.unary_stream( - '/mavsdk.rpc.component_information_server.ComponentInformationServerService/SubscribeFloatParam', - request_serializer=component__information__server_dot_component__information__server__pb2.SubscribeFloatParamRequest.SerializeToString, - response_deserializer=component__information__server_dot_component__information__server__pb2.FloatParamResponse.FromString, - ) + "/mavsdk.rpc.component_information_server.ComponentInformationServerService/SubscribeFloatParam", + request_serializer=component__information__server_dot_component__information__server__pb2.SubscribeFloatParamRequest.SerializeToString, + response_deserializer=component__information__server_dot_component__information__server__pb2.FloatParamResponse.FromString, + ) class ComponentInformationServerServiceServicer(object): - """Provide component information such as parameters. - """ + """Provide component information such as parameters.""" def ProvideFloatParam(self, request, context): """ Provide a param of type float. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFloatParam(self, request, context): """ Subscribe to float param updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ComponentInformationServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'ProvideFloatParam': grpc.unary_unary_rpc_method_handler( - servicer.ProvideFloatParam, - request_deserializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamRequest.FromString, - response_serializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamResponse.SerializeToString, - ), - 'SubscribeFloatParam': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFloatParam, - request_deserializer=component__information__server_dot_component__information__server__pb2.SubscribeFloatParamRequest.FromString, - response_serializer=component__information__server_dot_component__information__server__pb2.FloatParamResponse.SerializeToString, - ), + "ProvideFloatParam": grpc.unary_unary_rpc_method_handler( + servicer.ProvideFloatParam, + request_deserializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamRequest.FromString, + response_serializer=component__information__server_dot_component__information__server__pb2.ProvideFloatParamResponse.SerializeToString, + ), + "SubscribeFloatParam": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFloatParam, + request_deserializer=component__information__server_dot_component__information__server__pb2.SubscribeFloatParamRequest.FromString, + response_serializer=component__information__server_dot_component__information__server__pb2.FloatParamResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.component_information_server.ComponentInformationServerService', rpc_method_handlers) + "mavsdk.rpc.component_information_server.ComponentInformationServerService", + rpc_method_handlers, + ) server.add_generic_rpc_handlers((generic_handler,)) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ComponentInformationServerService(object): - """Provide component information such as parameters. - """ + """Provide component information such as parameters.""" @staticmethod - def ProvideFloatParam(request, + def ProvideFloatParam( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.component_information_server.ComponentInformationServerService/ProvideFloatParam', + "/mavsdk.rpc.component_information_server.ComponentInformationServerService/ProvideFloatParam", component__information__server_dot_component__information__server__pb2.ProvideFloatParamRequest.SerializeToString, component__information__server_dot_component__information__server__pb2.ProvideFloatParamResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SubscribeFloatParam(request, + def SubscribeFloatParam( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_stream( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.component_information_server.ComponentInformationServerService/SubscribeFloatParam', + "/mavsdk.rpc.component_information_server.ComponentInformationServerService/SubscribeFloatParam", component__information__server_dot_component__information__server__pb2.SubscribeFloatParamRequest.SerializeToString, component__information__server_dot_component__information__server__pb2.FloatParamResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) diff --git a/mavsdk/component_metadata.py b/mavsdk/component_metadata.py index 268d8979..f9315a23 100644 --- a/mavsdk/component_metadata.py +++ b/mavsdk/component_metadata.py @@ -8,25 +8,24 @@ class MetadataType(Enum): """ - The metadata type + The metadata type - Values - ------ - ALL_COMPLETED - This is set in the subscription callback when all metadata types completed for a given component ID + Values + ------ + ALL_COMPLETED + This is set in the subscription callback when all metadata types completed for a given component ID - PARAMETER - Parameter metadata + PARAMETER + Parameter metadata - EVENTS - Event definitions + EVENTS + Event definitions - ACTUATORS - Actuator definitions + ACTUATORS + Actuator definitions - """ + """ - ALL_COMPLETED = 0 PARAMETER = 1 EVENTS = 2 @@ -44,7 +43,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == component_metadata_pb2.METADATA_TYPE_ALL_COMPLETED: return MetadataType.ALL_COMPLETED if rpc_enum_value == component_metadata_pb2.METADATA_TYPE_PARAMETER: @@ -60,114 +59,95 @@ def __str__(self): class MetadataData: """ - Metadata response - - Parameters - ---------- - json_metadata : std::string - The JSON metadata + Metadata response - """ + Parameters + ---------- + json_metadata : std::string + The JSON metadata - + """ - def __init__( - self, - json_metadata): - """ Initializes the MetadataData object """ + def __init__(self, json_metadata): + """Initializes the MetadataData object""" self.json_metadata = json_metadata def __eq__(self, to_compare): - """ Checks if two MetadataData are the same """ + """Checks if two MetadataData are the same""" try: # Try to compare - this likely fails when it is compared to a non # MetadataData object - return \ - (self.json_metadata == to_compare.json_metadata) + return self.json_metadata == to_compare.json_metadata except AttributeError: return False def __str__(self): - """ MetadataData in string representation """ - struct_repr = ", ".join([ - "json_metadata: " + str(self.json_metadata) - ]) + """MetadataData in string representation""" + struct_repr = ", ".join(["json_metadata: " + str(self.json_metadata)]) return f"MetadataData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMetadataData): - """ Translates a gRPC struct to the SDK equivalent """ - return MetadataData( - - rpcMetadataData.json_metadata - ) + """Translates a gRPC struct to the SDK equivalent""" + return MetadataData(rpcMetadataData.json_metadata) def translate_to_rpc(self, rpcMetadataData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMetadataData.json_metadata = self.json_metadata - - - class ComponentMetadataResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned + Possible results returned - Values - ------ - SUCCESS - Success + Values + ------ + SUCCESS + Success - NOT_AVAILABLE - Not available + NOT_AVAILABLE + Not available - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - UNSUPPORTED - Unsupported + UNSUPPORTED + Unsupported - DENIED - Denied + DENIED + Denied - FAILED - Failed + FAILED + Failed - TIMEOUT - Timeout + TIMEOUT + Timeout - NO_SYSTEM - No system + NO_SYSTEM + No system - NOT_REQUESTED - Not requested + NOT_REQUESTED + Not requested - """ + """ - SUCCESS = 0 NOT_AVAILABLE = 1 CONNECTION_ERROR = 2 @@ -182,7 +162,9 @@ def translate_to_rpc(self): if self == ComponentMetadataResult.Result.SUCCESS: return component_metadata_pb2.ComponentMetadataResult.RESULT_SUCCESS if self == ComponentMetadataResult.Result.NOT_AVAILABLE: - return component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_AVAILABLE + return ( + component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_AVAILABLE + ) if self == ComponentMetadataResult.Result.CONNECTION_ERROR: return component_metadata_pb2.ComponentMetadataResult.RESULT_CONNECTION_ERROR if self == ComponentMetadataResult.Result.UNSUPPORTED: @@ -196,185 +178,175 @@ def translate_to_rpc(self): if self == ComponentMetadataResult.Result.NO_SYSTEM: return component_metadata_pb2.ComponentMetadataResult.RESULT_NO_SYSTEM if self == ComponentMetadataResult.Result.NOT_REQUESTED: - return component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_REQUESTED + return ( + component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_REQUESTED + ) @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_SUCCESS: + """Parses a gRPC response""" + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_SUCCESS + ): return ComponentMetadataResult.Result.SUCCESS - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_AVAILABLE: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_AVAILABLE + ): return ComponentMetadataResult.Result.NOT_AVAILABLE - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_CONNECTION_ERROR + ): return ComponentMetadataResult.Result.CONNECTION_ERROR - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_UNSUPPORTED: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_UNSUPPORTED + ): return ComponentMetadataResult.Result.UNSUPPORTED - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_DENIED: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_DENIED + ): return ComponentMetadataResult.Result.DENIED - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_FAILED: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_FAILED + ): return ComponentMetadataResult.Result.FAILED - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_TIMEOUT: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_TIMEOUT + ): return ComponentMetadataResult.Result.TIMEOUT - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_NO_SYSTEM + ): return ComponentMetadataResult.Result.NO_SYSTEM - if rpc_enum_value == component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_REQUESTED: + if ( + rpc_enum_value + == component_metadata_pb2.ComponentMetadataResult.RESULT_NOT_REQUESTED + ): return ComponentMetadataResult.Result.NOT_REQUESTED def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ComponentMetadataResult object """ + def __init__(self, result, result_str): + """Initializes the ComponentMetadataResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ComponentMetadataResult are the same """ + """Checks if two ComponentMetadataResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ComponentMetadataResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ComponentMetadataResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ComponentMetadataResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ComponentMetadataResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcComponentMetadataResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ComponentMetadataResult( - - ComponentMetadataResult.Result.translate_from_rpc(rpcComponentMetadataResult.result), - - - rpcComponentMetadataResult.result_str - ) + ComponentMetadataResult.Result.translate_from_rpc( + rpcComponentMetadataResult.result + ), + rpcComponentMetadataResult.result_str, + ) def translate_to_rpc(self, rpcComponentMetadataResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcComponentMetadataResult.result = self.result.translate_to_rpc() - - - - - + rpcComponentMetadataResult.result_str = self.result_str - - - class MetadataUpdate: """ - Metadata for a given component and type + Metadata for a given component and type - Parameters - ---------- - compid : uint32_t - The component ID + Parameters + ---------- + compid : uint32_t + The component ID - type : MetadataType - The metadata type + type : MetadataType + The metadata type - json_metadata : std::string - The JSON metadata + json_metadata : std::string + The JSON metadata - """ - - + """ - def __init__( - self, - compid, - type, - json_metadata): - """ Initializes the MetadataUpdate object """ + def __init__(self, compid, type, json_metadata): + """Initializes the MetadataUpdate object""" self.compid = compid self.type = type self.json_metadata = json_metadata def __eq__(self, to_compare): - """ Checks if two MetadataUpdate are the same """ + """Checks if two MetadataUpdate are the same""" try: # Try to compare - this likely fails when it is compared to a non # MetadataUpdate object - return \ - (self.compid == to_compare.compid) and \ - (self.type == to_compare.type) and \ - (self.json_metadata == to_compare.json_metadata) + return ( + (self.compid == to_compare.compid) + and (self.type == to_compare.type) + and (self.json_metadata == to_compare.json_metadata) + ) except AttributeError: return False def __str__(self): - """ MetadataUpdate in string representation """ - struct_repr = ", ".join([ + """MetadataUpdate in string representation""" + struct_repr = ", ".join( + [ "compid: " + str(self.compid), "type: " + str(self.type), - "json_metadata: " + str(self.json_metadata) - ]) + "json_metadata: " + str(self.json_metadata), + ] + ) return f"MetadataUpdate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMetadataUpdate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MetadataUpdate( - - rpcMetadataUpdate.compid, - - - MetadataType.translate_from_rpc(rpcMetadataUpdate.type), - - - rpcMetadataUpdate.json_metadata - ) + rpcMetadataUpdate.compid, + MetadataType.translate_from_rpc(rpcMetadataUpdate.type), + rpcMetadataUpdate.json_metadata, + ) def translate_to_rpc(self, rpcMetadataUpdate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMetadataUpdate.compid = self.compid - - - - - + rpcMetadataUpdate.type = self.type.translate_to_rpc() - - - - - - rpcMetadataUpdate.json_metadata = self.json_metadata - - - + rpcMetadataUpdate.json_metadata = self.json_metadata class ComponentMetadataError(Exception): - """ Raised when a ComponentMetadataResult is a fail code """ + """Raised when a ComponentMetadataResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -387,66 +359,62 @@ def __str__(self): class ComponentMetadata(AsyncBase): """ - Access component metadata json definitions, such as parameters. + Access component metadata json definitions, such as parameters. - Generated by dcsdkgen - MAVSDK ComponentMetadata API + Generated by dcsdkgen - MAVSDK ComponentMetadata API """ # Plugin name name = "ComponentMetadata" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = component_metadata_pb2_grpc.ComponentMetadataServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ - return ComponentMetadataResult.translate_from_rpc(response.component_metadata_result) - + """Returns the response status and description""" + return ComponentMetadataResult.translate_from_rpc( + response.component_metadata_result + ) async def request_component(self, compid): """ - Request metadata from a specific component. This is used to start requesting metadata from a component. - The metadata can later be accessed via subscription (see below) or GetMetadata. + Request metadata from a specific component. This is used to start requesting metadata from a component. + The metadata can later be accessed via subscription (see below) or GetMetadata. + + Parameters + ---------- + compid : uint32_t + The component ID to request - Parameters - ---------- - compid : uint32_t - The component ID to request - """ request = component_metadata_pb2.RequestComponentRequest() request.compid = compid response = await self._stub.RequestComponent(request) - - async def request_autopilot_component(self): """ - Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. - The metadata can later be accessed via subscription (see below) or GetMetadata. + Request metadata from the autopilot component. This is used to start requesting metadata from the autopilot. + The metadata can later be accessed via subscription (see below) or GetMetadata. + - """ request = component_metadata_pb2.RequestAutopilotComponentRequest() response = await self._stub.RequestAutopilotComponent(request) - - async def metadata_available(self): """ - Register a callback that gets called when metadata is available + Register a callback that gets called when metadata is available + + Yields + ------- + data : MetadataUpdate + The metadata data - Yields - ------- - data : MetadataUpdate - The metadata data - """ request = component_metadata_pb2.SubscribeMetadataAvailableRequest() @@ -454,56 +422,47 @@ async def metadata_available(self): try: async for response in metadata_available_stream: - - - yield MetadataUpdate.translate_from_rpc(response.data) finally: metadata_available_stream.cancel() async def get_metadata(self, compid, metadata_type): """ - Access metadata. This can be used if you know the metadata is available already, otherwise use - the subscription to get notified when it becomes available. - - Parameters - ---------- - compid : uint32_t - The component ID to request - - metadata_type : MetadataType - The metadata type - - Returns - ------- - response : MetadataData - The response - - Raises - ------ - ComponentMetadataError - If the request fails. The error contains the reason for the failure. + Access metadata. This can be used if you know the metadata is available already, otherwise use + the subscription to get notified when it becomes available. + + Parameters + ---------- + compid : uint32_t + The component ID to request + + metadata_type : MetadataType + The metadata type + + Returns + ------- + response : MetadataData + The response + + Raises + ------ + ComponentMetadataError + If the request fails. The error contains the reason for the failure. """ request = component_metadata_pb2.GetMetadataRequest() - - + request.compid = compid - - - - + request.metadata_type = metadata_type.translate_to_rpc() - - + response = await self._stub.GetMetadata(request) - result = self._extract_result(response) if result.result != ComponentMetadataResult.Result.SUCCESS: - raise ComponentMetadataError(result, "get_metadata()", compid, metadata_type) - + raise ComponentMetadataError( + result, "get_metadata()", compid, metadata_type + ) return MetadataData.translate_from_rpc(response.response) - \ No newline at end of file diff --git a/mavsdk/component_metadata_pb2.py b/mavsdk/component_metadata_pb2.py index ddc2db34..b3ea1f47 100644 --- a/mavsdk/component_metadata_pb2.py +++ b/mavsdk/component_metadata_pb2.py @@ -4,18 +4,20 @@ # source: component_metadata/component_metadata.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( _runtime_version.Domain.PUBLIC, 5, 29, 0, - '', - 'component_metadata/component_metadata.proto' + "", + "component_metadata/component_metadata.proto", ) # @@protoc_insertion_point(imports) @@ -25,48 +27,72 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n+component_metadata/component_metadata.proto\x12\x1dmavsdk.rpc.component_metadata\x1a\x14mavsdk_options.proto\")\n\x17RequestComponentRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\"\x1a\n\x18RequestComponentResponse\"h\n\x12GetMetadataRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\x12\x42\n\rmetadata_type\x18\x02 \x01(\x0e\x32+.mavsdk.rpc.component_metadata.MetadataType\"\xaf\x01\n\x13GetMetadataResponse\x12Y\n\x19\x63omponent_metadata_result\x18\x01 \x01(\x0b\x32\x36.mavsdk.rpc.component_metadata.ComponentMetadataResult\x12=\n\x08response\x18\x02 \x01(\x0b\x32+.mavsdk.rpc.component_metadata.MetadataData\"%\n\x0cMetadataData\x12\x15\n\rjson_metadata\x18\x01 \x01(\t\"\xd4\x02\n\x17\x43omponentMetadataResult\x12M\n\x06result\x18\x01 \x01(\x0e\x32=.mavsdk.rpc.component_metadata.ComponentMetadataResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xd5\x01\n\x06Result\x12\x12\n\x0eRESULT_SUCCESS\x10\x00\x12\x18\n\x14RESULT_NOT_AVAILABLE\x10\x01\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x02\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x11\n\rRESULT_FAILED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07\x12\x18\n\x14RESULT_NOT_REQUESTED\x10\x08\"\"\n RequestAutopilotComponentRequest\"#\n!RequestAutopilotComponentResponse\"#\n!SubscribeMetadataAvailableRequest\"X\n\x19MetadataAvailableResponse\x12;\n\x04\x64\x61ta\x18\x01 \x01(\x0b\x32-.mavsdk.rpc.component_metadata.MetadataUpdate\"r\n\x0eMetadataUpdate\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\x12\x39\n\x04type\x18\x02 \x01(\x0e\x32+.mavsdk.rpc.component_metadata.MetadataType\x12\x15\n\rjson_metadata\x18\x03 \x01(\t*\x83\x01\n\x0cMetadataType\x12\x1f\n\x1bMETADATA_TYPE_ALL_COMPLETED\x10\x00\x12\x1b\n\x17METADATA_TYPE_PARAMETER\x10\x01\x12\x18\n\x14METADATA_TYPE_EVENTS\x10\x02\x12\x1b\n\x17METADATA_TYPE_ACTUATORS\x10\x03\x32\xec\x04\n\x18\x43omponentMetadataService\x12\x89\x01\n\x10RequestComponent\x12\x36.mavsdk.rpc.component_metadata.RequestComponentRequest\x1a\x37.mavsdk.rpc.component_metadata.RequestComponentResponse\"\x04\x80\xb5\x18\x01\x12\xa4\x01\n\x19RequestAutopilotComponent\x12?.mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest\x1a@.mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse\"\x04\x80\xb5\x18\x01\x12\xa0\x01\n\x1aSubscribeMetadataAvailable\x12@.mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest\x1a\x38.mavsdk.rpc.component_metadata.MetadataAvailableResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12z\n\x0bGetMetadata\x12\x31.mavsdk.rpc.component_metadata.GetMetadataRequest\x1a\x32.mavsdk.rpc.component_metadata.GetMetadataResponse\"\x04\x80\xb5\x18\x01\x42\x36\n\x1cio.mavsdk.component_metadataB\x16\x43omponentMetadataProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n+component_metadata/component_metadata.proto\x12\x1dmavsdk.rpc.component_metadata\x1a\x14mavsdk_options.proto")\n\x17RequestComponentRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r"\x1a\n\x18RequestComponentResponse"h\n\x12GetMetadataRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\x12\x42\n\rmetadata_type\x18\x02 \x01(\x0e\x32+.mavsdk.rpc.component_metadata.MetadataType"\xaf\x01\n\x13GetMetadataResponse\x12Y\n\x19\x63omponent_metadata_result\x18\x01 \x01(\x0b\x32\x36.mavsdk.rpc.component_metadata.ComponentMetadataResult\x12=\n\x08response\x18\x02 \x01(\x0b\x32+.mavsdk.rpc.component_metadata.MetadataData"%\n\x0cMetadataData\x12\x15\n\rjson_metadata\x18\x01 \x01(\t"\xd4\x02\n\x17\x43omponentMetadataResult\x12M\n\x06result\x18\x01 \x01(\x0e\x32=.mavsdk.rpc.component_metadata.ComponentMetadataResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xd5\x01\n\x06Result\x12\x12\n\x0eRESULT_SUCCESS\x10\x00\x12\x18\n\x14RESULT_NOT_AVAILABLE\x10\x01\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x02\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x11\n\rRESULT_FAILED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07\x12\x18\n\x14RESULT_NOT_REQUESTED\x10\x08""\n RequestAutopilotComponentRequest"#\n!RequestAutopilotComponentResponse"#\n!SubscribeMetadataAvailableRequest"X\n\x19MetadataAvailableResponse\x12;\n\x04\x64\x61ta\x18\x01 \x01(\x0b\x32-.mavsdk.rpc.component_metadata.MetadataUpdate"r\n\x0eMetadataUpdate\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\x12\x39\n\x04type\x18\x02 \x01(\x0e\x32+.mavsdk.rpc.component_metadata.MetadataType\x12\x15\n\rjson_metadata\x18\x03 \x01(\t*\x83\x01\n\x0cMetadataType\x12\x1f\n\x1bMETADATA_TYPE_ALL_COMPLETED\x10\x00\x12\x1b\n\x17METADATA_TYPE_PARAMETER\x10\x01\x12\x18\n\x14METADATA_TYPE_EVENTS\x10\x02\x12\x1b\n\x17METADATA_TYPE_ACTUATORS\x10\x03\x32\xec\x04\n\x18\x43omponentMetadataService\x12\x89\x01\n\x10RequestComponent\x12\x36.mavsdk.rpc.component_metadata.RequestComponentRequest\x1a\x37.mavsdk.rpc.component_metadata.RequestComponentResponse"\x04\x80\xb5\x18\x01\x12\xa4\x01\n\x19RequestAutopilotComponent\x12?.mavsdk.rpc.component_metadata.RequestAutopilotComponentRequest\x1a@.mavsdk.rpc.component_metadata.RequestAutopilotComponentResponse"\x04\x80\xb5\x18\x01\x12\xa0\x01\n\x1aSubscribeMetadataAvailable\x12@.mavsdk.rpc.component_metadata.SubscribeMetadataAvailableRequest\x1a\x38.mavsdk.rpc.component_metadata.MetadataAvailableResponse"\x04\x80\xb5\x18\x00\x30\x01\x12z\n\x0bGetMetadata\x12\x31.mavsdk.rpc.component_metadata.GetMetadataRequest\x1a\x32.mavsdk.rpc.component_metadata.GetMetadataResponse"\x04\x80\xb5\x18\x01\x42\x36\n\x1cio.mavsdk.component_metadataB\x16\x43omponentMetadataProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'component_metadata.component_metadata_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "component_metadata.component_metadata_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\034io.mavsdk.component_metadataB\026ComponentMetadataProto' - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['RequestComponent']._loaded_options = None - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['RequestComponent']._serialized_options = b'\200\265\030\001' - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['RequestAutopilotComponent']._loaded_options = None - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['RequestAutopilotComponent']._serialized_options = b'\200\265\030\001' - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['SubscribeMetadataAvailable']._loaded_options = None - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['SubscribeMetadataAvailable']._serialized_options = b'\200\265\030\000' - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['GetMetadata']._loaded_options = None - _globals['_COMPONENTMETADATASERVICE'].methods_by_name['GetMetadata']._serialized_options = b'\200\265\030\001' - _globals['_METADATATYPE']._serialized_start=1154 - _globals['_METADATATYPE']._serialized_end=1285 - _globals['_REQUESTCOMPONENTREQUEST']._serialized_start=100 - _globals['_REQUESTCOMPONENTREQUEST']._serialized_end=141 - _globals['_REQUESTCOMPONENTRESPONSE']._serialized_start=143 - _globals['_REQUESTCOMPONENTRESPONSE']._serialized_end=169 - _globals['_GETMETADATAREQUEST']._serialized_start=171 - _globals['_GETMETADATAREQUEST']._serialized_end=275 - _globals['_GETMETADATARESPONSE']._serialized_start=278 - _globals['_GETMETADATARESPONSE']._serialized_end=453 - _globals['_METADATADATA']._serialized_start=455 - _globals['_METADATADATA']._serialized_end=492 - _globals['_COMPONENTMETADATARESULT']._serialized_start=495 - _globals['_COMPONENTMETADATARESULT']._serialized_end=835 - _globals['_COMPONENTMETADATARESULT_RESULT']._serialized_start=622 - _globals['_COMPONENTMETADATARESULT_RESULT']._serialized_end=835 - _globals['_REQUESTAUTOPILOTCOMPONENTREQUEST']._serialized_start=837 - _globals['_REQUESTAUTOPILOTCOMPONENTREQUEST']._serialized_end=871 - _globals['_REQUESTAUTOPILOTCOMPONENTRESPONSE']._serialized_start=873 - _globals['_REQUESTAUTOPILOTCOMPONENTRESPONSE']._serialized_end=908 - _globals['_SUBSCRIBEMETADATAAVAILABLEREQUEST']._serialized_start=910 - _globals['_SUBSCRIBEMETADATAAVAILABLEREQUEST']._serialized_end=945 - _globals['_METADATAAVAILABLERESPONSE']._serialized_start=947 - _globals['_METADATAAVAILABLERESPONSE']._serialized_end=1035 - _globals['_METADATAUPDATE']._serialized_start=1037 - _globals['_METADATAUPDATE']._serialized_end=1151 - _globals['_COMPONENTMETADATASERVICE']._serialized_start=1288 - _globals['_COMPONENTMETADATASERVICE']._serialized_end=1908 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = ( + b"\n\034io.mavsdk.component_metadataB\026ComponentMetadataProto" + ) + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "RequestComponent" + ]._loaded_options = None + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "RequestComponent" + ]._serialized_options = b"\200\265\030\001" + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "RequestAutopilotComponent" + ]._loaded_options = None + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "RequestAutopilotComponent" + ]._serialized_options = b"\200\265\030\001" + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "SubscribeMetadataAvailable" + ]._loaded_options = None + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "SubscribeMetadataAvailable" + ]._serialized_options = b"\200\265\030\000" + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "GetMetadata" + ]._loaded_options = None + _globals["_COMPONENTMETADATASERVICE"].methods_by_name[ + "GetMetadata" + ]._serialized_options = b"\200\265\030\001" + _globals["_METADATATYPE"]._serialized_start = 1154 + _globals["_METADATATYPE"]._serialized_end = 1285 + _globals["_REQUESTCOMPONENTREQUEST"]._serialized_start = 100 + _globals["_REQUESTCOMPONENTREQUEST"]._serialized_end = 141 + _globals["_REQUESTCOMPONENTRESPONSE"]._serialized_start = 143 + _globals["_REQUESTCOMPONENTRESPONSE"]._serialized_end = 169 + _globals["_GETMETADATAREQUEST"]._serialized_start = 171 + _globals["_GETMETADATAREQUEST"]._serialized_end = 275 + _globals["_GETMETADATARESPONSE"]._serialized_start = 278 + _globals["_GETMETADATARESPONSE"]._serialized_end = 453 + _globals["_METADATADATA"]._serialized_start = 455 + _globals["_METADATADATA"]._serialized_end = 492 + _globals["_COMPONENTMETADATARESULT"]._serialized_start = 495 + _globals["_COMPONENTMETADATARESULT"]._serialized_end = 835 + _globals["_COMPONENTMETADATARESULT_RESULT"]._serialized_start = 622 + _globals["_COMPONENTMETADATARESULT_RESULT"]._serialized_end = 835 + _globals["_REQUESTAUTOPILOTCOMPONENTREQUEST"]._serialized_start = 837 + _globals["_REQUESTAUTOPILOTCOMPONENTREQUEST"]._serialized_end = 871 + _globals["_REQUESTAUTOPILOTCOMPONENTRESPONSE"]._serialized_start = 873 + _globals["_REQUESTAUTOPILOTCOMPONENTRESPONSE"]._serialized_end = 908 + _globals["_SUBSCRIBEMETADATAAVAILABLEREQUEST"]._serialized_start = 910 + _globals["_SUBSCRIBEMETADATAAVAILABLEREQUEST"]._serialized_end = 945 + _globals["_METADATAAVAILABLERESPONSE"]._serialized_start = 947 + _globals["_METADATAAVAILABLERESPONSE"]._serialized_end = 1035 + _globals["_METADATAUPDATE"]._serialized_start = 1037 + _globals["_METADATAUPDATE"]._serialized_end = 1151 + _globals["_COMPONENTMETADATASERVICE"]._serialized_start = 1288 + _globals["_COMPONENTMETADATASERVICE"]._serialized_end = 1908 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/component_metadata_pb2_grpc.py b/mavsdk/component_metadata_pb2_grpc.py index 0dc7cf5e..c2186b5b 100644 --- a/mavsdk/component_metadata_pb2_grpc.py +++ b/mavsdk/component_metadata_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import component_metadata_pb2 as component__metadata_dot_component__metadata__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in component_metadata/component_metadata_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in component_metadata/component_metadata_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ComponentMetadataServiceStub(object): - """Access component metadata json definitions, such as parameters. - """ + """Access component metadata json definitions, such as parameters.""" def __init__(self, channel): """Constructor. @@ -36,30 +39,33 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.RequestComponent = channel.unary_unary( - '/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestComponent', - request_serializer=component__metadata_dot_component__metadata__pb2.RequestComponentRequest.SerializeToString, - response_deserializer=component__metadata_dot_component__metadata__pb2.RequestComponentResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestComponent", + request_serializer=component__metadata_dot_component__metadata__pb2.RequestComponentRequest.SerializeToString, + response_deserializer=component__metadata_dot_component__metadata__pb2.RequestComponentResponse.FromString, + _registered_method=True, + ) self.RequestAutopilotComponent = channel.unary_unary( - '/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestAutopilotComponent', - request_serializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentRequest.SerializeToString, - response_deserializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestAutopilotComponent", + request_serializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentRequest.SerializeToString, + response_deserializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentResponse.FromString, + _registered_method=True, + ) self.SubscribeMetadataAvailable = channel.unary_stream( - '/mavsdk.rpc.component_metadata.ComponentMetadataService/SubscribeMetadataAvailable', - request_serializer=component__metadata_dot_component__metadata__pb2.SubscribeMetadataAvailableRequest.SerializeToString, - response_deserializer=component__metadata_dot_component__metadata__pb2.MetadataAvailableResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.component_metadata.ComponentMetadataService/SubscribeMetadataAvailable", + request_serializer=component__metadata_dot_component__metadata__pb2.SubscribeMetadataAvailableRequest.SerializeToString, + response_deserializer=component__metadata_dot_component__metadata__pb2.MetadataAvailableResponse.FromString, + _registered_method=True, + ) self.GetMetadata = channel.unary_unary( - '/mavsdk.rpc.component_metadata.ComponentMetadataService/GetMetadata', - request_serializer=component__metadata_dot_component__metadata__pb2.GetMetadataRequest.SerializeToString, - response_deserializer=component__metadata_dot_component__metadata__pb2.GetMetadataResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.component_metadata.ComponentMetadataService/GetMetadata", + request_serializer=component__metadata_dot_component__metadata__pb2.GetMetadataRequest.SerializeToString, + response_deserializer=component__metadata_dot_component__metadata__pb2.GetMetadataResponse.FromString, + _registered_method=True, + ) class ComponentMetadataServiceServicer(object): - """Access component metadata json definitions, such as parameters. - """ + """Access component metadata json definitions, such as parameters.""" def RequestComponent(self, request, context): """ @@ -67,8 +73,8 @@ def RequestComponent(self, request, context): The metadata can later be accessed via subscription (see below) or GetMetadata. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RequestAutopilotComponent(self, request, context): """ @@ -76,16 +82,16 @@ def RequestAutopilotComponent(self, request, context): The metadata can later be accessed via subscription (see below) or GetMetadata. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeMetadataAvailable(self, request, context): """ Register a callback that gets called when metadata is available """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetMetadata(self, request, context): """ @@ -93,59 +99,63 @@ def GetMetadata(self, request, context): the subscription to get notified when it becomes available. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ComponentMetadataServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'RequestComponent': grpc.unary_unary_rpc_method_handler( - servicer.RequestComponent, - request_deserializer=component__metadata_dot_component__metadata__pb2.RequestComponentRequest.FromString, - response_serializer=component__metadata_dot_component__metadata__pb2.RequestComponentResponse.SerializeToString, - ), - 'RequestAutopilotComponent': grpc.unary_unary_rpc_method_handler( - servicer.RequestAutopilotComponent, - request_deserializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentRequest.FromString, - response_serializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentResponse.SerializeToString, - ), - 'SubscribeMetadataAvailable': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeMetadataAvailable, - request_deserializer=component__metadata_dot_component__metadata__pb2.SubscribeMetadataAvailableRequest.FromString, - response_serializer=component__metadata_dot_component__metadata__pb2.MetadataAvailableResponse.SerializeToString, - ), - 'GetMetadata': grpc.unary_unary_rpc_method_handler( - servicer.GetMetadata, - request_deserializer=component__metadata_dot_component__metadata__pb2.GetMetadataRequest.FromString, - response_serializer=component__metadata_dot_component__metadata__pb2.GetMetadataResponse.SerializeToString, - ), + "RequestComponent": grpc.unary_unary_rpc_method_handler( + servicer.RequestComponent, + request_deserializer=component__metadata_dot_component__metadata__pb2.RequestComponentRequest.FromString, + response_serializer=component__metadata_dot_component__metadata__pb2.RequestComponentResponse.SerializeToString, + ), + "RequestAutopilotComponent": grpc.unary_unary_rpc_method_handler( + servicer.RequestAutopilotComponent, + request_deserializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentRequest.FromString, + response_serializer=component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentResponse.SerializeToString, + ), + "SubscribeMetadataAvailable": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeMetadataAvailable, + request_deserializer=component__metadata_dot_component__metadata__pb2.SubscribeMetadataAvailableRequest.FromString, + response_serializer=component__metadata_dot_component__metadata__pb2.MetadataAvailableResponse.SerializeToString, + ), + "GetMetadata": grpc.unary_unary_rpc_method_handler( + servicer.GetMetadata, + request_deserializer=component__metadata_dot_component__metadata__pb2.GetMetadataRequest.FromString, + response_serializer=component__metadata_dot_component__metadata__pb2.GetMetadataResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.component_metadata.ComponentMetadataService', rpc_method_handlers) + "mavsdk.rpc.component_metadata.ComponentMetadataService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.component_metadata.ComponentMetadataService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.component_metadata.ComponentMetadataService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ComponentMetadataService(object): - """Access component metadata json definitions, such as parameters. - """ + """Access component metadata json definitions, such as parameters.""" @staticmethod - def RequestComponent(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RequestComponent( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestComponent', + "/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestComponent", component__metadata_dot_component__metadata__pb2.RequestComponentRequest.SerializeToString, component__metadata_dot_component__metadata__pb2.RequestComponentResponse.FromString, options, @@ -156,23 +166,26 @@ def RequestComponent(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RequestAutopilotComponent(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RequestAutopilotComponent( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestAutopilotComponent', + "/mavsdk.rpc.component_metadata.ComponentMetadataService/RequestAutopilotComponent", component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentRequest.SerializeToString, component__metadata_dot_component__metadata__pb2.RequestAutopilotComponentResponse.FromString, options, @@ -183,23 +196,26 @@ def RequestAutopilotComponent(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeMetadataAvailable(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeMetadataAvailable( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.component_metadata.ComponentMetadataService/SubscribeMetadataAvailable', + "/mavsdk.rpc.component_metadata.ComponentMetadataService/SubscribeMetadataAvailable", component__metadata_dot_component__metadata__pb2.SubscribeMetadataAvailableRequest.SerializeToString, component__metadata_dot_component__metadata__pb2.MetadataAvailableResponse.FromString, options, @@ -210,23 +226,26 @@ def SubscribeMetadataAvailable(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetMetadata(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetMetadata( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.component_metadata.ComponentMetadataService/GetMetadata', + "/mavsdk.rpc.component_metadata.ComponentMetadataService/GetMetadata", component__metadata_dot_component__metadata__pb2.GetMetadataRequest.SerializeToString, component__metadata_dot_component__metadata__pb2.GetMetadataResponse.FromString, options, @@ -237,4 +256,5 @@ def GetMetadata(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/component_metadata_server.py b/mavsdk/component_metadata_server.py index d495a0ac..e404e0e8 100644 --- a/mavsdk/component_metadata_server.py +++ b/mavsdk/component_metadata_server.py @@ -8,22 +8,21 @@ class MetadataType(Enum): """ - The metadata type + The metadata type - Values - ------ - PARAMETER - Parameter metadata + Values + ------ + PARAMETER + Parameter metadata - EVENTS - Event definitions + EVENTS + Event definitions - ACTUATORS - Actuator definitions + ACTUATORS + Actuator definitions - """ + """ - PARAMETER = 0 EVENTS = 1 ACTUATORS = 2 @@ -38,7 +37,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == component_metadata_server_pb2.METADATA_TYPE_PARAMETER: return MetadataType.PARAMETER if rpc_enum_value == component_metadata_server_pb2.METADATA_TYPE_EVENTS: @@ -52,120 +51,96 @@ def __str__(self): class Metadata: """ - The metadata type and content - - Parameters - ---------- - type : MetadataType - The metadata type + The metadata type and content - json_metadata : std::string - The JSON metadata + Parameters + ---------- + type : MetadataType + The metadata type - """ + json_metadata : std::string + The JSON metadata - + """ - def __init__( - self, - type, - json_metadata): - """ Initializes the Metadata object """ + def __init__(self, type, json_metadata): + """Initializes the Metadata object""" self.type = type self.json_metadata = json_metadata def __eq__(self, to_compare): - """ Checks if two Metadata are the same """ + """Checks if two Metadata are the same""" try: # Try to compare - this likely fails when it is compared to a non # Metadata object - return \ - (self.type == to_compare.type) and \ - (self.json_metadata == to_compare.json_metadata) + return (self.type == to_compare.type) and ( + self.json_metadata == to_compare.json_metadata + ) except AttributeError: return False def __str__(self): - """ Metadata in string representation """ - struct_repr = ", ".join([ - "type: " + str(self.type), - "json_metadata: " + str(self.json_metadata) - ]) + """Metadata in string representation""" + struct_repr = ", ".join( + ["type: " + str(self.type), "json_metadata: " + str(self.json_metadata)] + ) return f"Metadata: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMetadata): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Metadata( - - MetadataType.translate_from_rpc(rpcMetadata.type), - - - rpcMetadata.json_metadata - ) + MetadataType.translate_from_rpc(rpcMetadata.type), rpcMetadata.json_metadata + ) def translate_to_rpc(self, rpcMetadata): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMetadata.type = self.type.translate_to_rpc() - - - - - - rpcMetadata.json_metadata = self.json_metadata - - - - + rpcMetadata.json_metadata = self.json_metadata class ComponentMetadataServer(AsyncBase): """ - Provide component metadata json definitions, such as parameters. + Provide component metadata json definitions, such as parameters. - Generated by dcsdkgen - MAVSDK ComponentMetadataServer API + Generated by dcsdkgen - MAVSDK ComponentMetadataServer API """ # Plugin name name = "ComponentMetadataServer" def _setup_stub(self, channel): - """ Setups the api stub """ - self._stub = component_metadata_server_pb2_grpc.ComponentMetadataServerServiceStub(channel) - - + """Setups the api stub""" + self._stub = ( + component_metadata_server_pb2_grpc.ComponentMetadataServerServiceStub( + channel + ) + ) async def set_metadata(self, metadata): """ - Provide metadata (can only be called once) + Provide metadata (can only be called once) + + Parameters + ---------- + metadata : [Metadata] + List of metadata - Parameters - ---------- - metadata : [Metadata] - List of metadata - """ request = component_metadata_server_pb2.SetMetadataRequest() - + rpc_elems_list = [] for elem in metadata: - rpc_elem = component_metadata_server_pb2.Metadata() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + request.metadata.extend(rpc_elems_list) - - - response = await self._stub.SetMetadata(request) - \ No newline at end of file + response = await self._stub.SetMetadata(request) diff --git a/mavsdk/component_metadata_server_pb2.py b/mavsdk/component_metadata_server_pb2.py index d1ba756a..12e0f806 100644 --- a/mavsdk/component_metadata_server_pb2.py +++ b/mavsdk/component_metadata_server_pb2.py @@ -4,18 +4,20 @@ # source: component_metadata_server/component_metadata_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( _runtime_version.Domain.PUBLIC, 5, 29, 0, - '', - 'component_metadata_server/component_metadata_server.proto' + "", + "component_metadata_server/component_metadata_server.proto", ) # @@protoc_insertion_point(imports) @@ -25,24 +27,36 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'component_metadata_server.component_metadata_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "component_metadata_server.component_metadata_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n#io.mavsdk.component_metadata_serverB\034ComponentMetadataServerProto' - _globals['_COMPONENTMETADATASERVERSERVICE'].methods_by_name['SetMetadata']._loaded_options = None - _globals['_COMPONENTMETADATASERVERSERVICE'].methods_by_name['SetMetadata']._serialized_options = b'\200\265\030\001' - _globals['_METADATATYPE']._serialized_start=333 - _globals['_METADATATYPE']._serialized_end=431 - _globals['_SETMETADATAREQUEST']._serialized_start=121 - _globals['_SETMETADATAREQUEST']._serialized_end=207 - _globals['_SETMETADATARESPONSE']._serialized_start=209 - _globals['_SETMETADATARESPONSE']._serialized_end=230 - _globals['_METADATA']._serialized_start=232 - _globals['_METADATA']._serialized_end=331 - _globals['_COMPONENTMETADATASERVERSERVICE']._serialized_start=434 - _globals['_COMPONENTMETADATASERVERSERVICE']._serialized_end=605 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = ( + b"\n#io.mavsdk.component_metadata_serverB\034ComponentMetadataServerProto" + ) + _globals["_COMPONENTMETADATASERVERSERVICE"].methods_by_name[ + "SetMetadata" + ]._loaded_options = None + _globals["_COMPONENTMETADATASERVERSERVICE"].methods_by_name[ + "SetMetadata" + ]._serialized_options = b"\200\265\030\001" + _globals["_METADATATYPE"]._serialized_start = 333 + _globals["_METADATATYPE"]._serialized_end = 431 + _globals["_SETMETADATAREQUEST"]._serialized_start = 121 + _globals["_SETMETADATAREQUEST"]._serialized_end = 207 + _globals["_SETMETADATARESPONSE"]._serialized_start = 209 + _globals["_SETMETADATARESPONSE"]._serialized_end = 230 + _globals["_METADATA"]._serialized_start = 232 + _globals["_METADATA"]._serialized_end = 331 + _globals["_COMPONENTMETADATASERVERSERVICE"]._serialized_start = 434 + _globals["_COMPONENTMETADATASERVERSERVICE"]._serialized_end = 605 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/component_metadata_server_pb2_grpc.py b/mavsdk/component_metadata_server_pb2_grpc.py index df48d593..9bdb829b 100644 --- a/mavsdk/component_metadata_server_pb2_grpc.py +++ b/mavsdk/component_metadata_server_pb2_grpc.py @@ -1,33 +1,38 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings -from . import component_metadata_server_pb2 as component__metadata__server_dot_component__metadata__server__pb2 +from . import ( + component_metadata_server_pb2 as component__metadata__server_dot_component__metadata__server__pb2, +) -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in component_metadata_server/component_metadata_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in component_metadata_server/component_metadata_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ComponentMetadataServerServiceStub(object): - """Provide component metadata json definitions, such as parameters. - """ + """Provide component metadata json definitions, such as parameters.""" def __init__(self, channel): """Constructor. @@ -36,59 +41,65 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetMetadata = channel.unary_unary( - '/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata', - request_serializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.SerializeToString, - response_deserializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata", + request_serializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.SerializeToString, + response_deserializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.FromString, + _registered_method=True, + ) class ComponentMetadataServerServiceServicer(object): - """Provide component metadata json definitions, such as parameters. - """ + """Provide component metadata json definitions, such as parameters.""" def SetMetadata(self, request, context): """ Provide metadata (can only be called once) """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ComponentMetadataServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetMetadata': grpc.unary_unary_rpc_method_handler( - servicer.SetMetadata, - request_deserializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.FromString, - response_serializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.SerializeToString, - ), + "SetMetadata": grpc.unary_unary_rpc_method_handler( + servicer.SetMetadata, + request_deserializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.FromString, + response_serializer=component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.component_metadata_server.ComponentMetadataServerService', rpc_method_handlers) + "mavsdk.rpc.component_metadata_server.ComponentMetadataServerService", + rpc_method_handlers, + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.component_metadata_server.ComponentMetadataServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.component_metadata_server.ComponentMetadataServerService", + rpc_method_handlers, + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ComponentMetadataServerService(object): - """Provide component metadata json definitions, such as parameters. - """ + """Provide component metadata json definitions, such as parameters.""" @staticmethod - def SetMetadata(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetMetadata( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata', + "/mavsdk.rpc.component_metadata_server.ComponentMetadataServerService/SetMetadata", component__metadata__server_dot_component__metadata__server__pb2.SetMetadataRequest.SerializeToString, component__metadata__server_dot_component__metadata__server__pb2.SetMetadataResponse.FromString, options, @@ -99,4 +110,5 @@ def SetMetadata(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/core.py b/mavsdk/core.py index 7a2e2cec..0e2da796 100644 --- a/mavsdk/core.py +++ b/mavsdk/core.py @@ -8,90 +8,70 @@ class ConnectionState: """ - Connection state type. + Connection state type. - Parameters - ---------- - is_connected : bool - Whether the vehicle got connected or disconnected + Parameters + ---------- + is_connected : bool + Whether the vehicle got connected or disconnected - """ - - + """ - def __init__( - self, - is_connected): - """ Initializes the ConnectionState object """ + def __init__(self, is_connected): + """Initializes the ConnectionState object""" self.is_connected = is_connected def __eq__(self, to_compare): - """ Checks if two ConnectionState are the same """ + """Checks if two ConnectionState are the same""" try: # Try to compare - this likely fails when it is compared to a non # ConnectionState object - return \ - (self.is_connected == to_compare.is_connected) + return self.is_connected == to_compare.is_connected except AttributeError: return False def __str__(self): - """ ConnectionState in string representation """ - struct_repr = ", ".join([ - "is_connected: " + str(self.is_connected) - ]) + """ConnectionState in string representation""" + struct_repr = ", ".join(["is_connected: " + str(self.is_connected)]) return f"ConnectionState: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcConnectionState): - """ Translates a gRPC struct to the SDK equivalent """ - return ConnectionState( - - rpcConnectionState.is_connected - ) + """Translates a gRPC struct to the SDK equivalent""" + return ConnectionState(rpcConnectionState.is_connected) def translate_to_rpc(self, rpcConnectionState): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcConnectionState.is_connected = self.is_connected - - - - - class Core(AsyncBase): """ - Access to the connection state and core configurations + Access to the connection state and core configurations - Generated by dcsdkgen - MAVSDK Core API + Generated by dcsdkgen - MAVSDK Core API """ # Plugin name name = "Core" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = core_pb2_grpc.CoreServiceStub(channel) - - async def connection_state(self): """ - Subscribe to 'connection state' updates. + Subscribe to 'connection state' updates. + + Yields + ------- + connection_state : ConnectionState + Connection state - Yields - ------- - connection_state : ConnectionState - Connection state - """ request = core_pb2.SubscribeConnectionStateRequest() @@ -99,32 +79,27 @@ async def connection_state(self): try: async for response in connection_state_stream: - - - yield ConnectionState.translate_from_rpc(response.connection_state) finally: connection_state_stream.cancel() async def set_mavlink_timeout(self, timeout_s): """ - Set timeout of MAVLink transfers. + Set timeout of MAVLink transfers. - The default timeout used is generally (0.5 seconds) seconds. - If MAVSDK is used on the same host this timeout can be reduced, while - if MAVSDK has to communicate over links with high latency it might - need to be increased to prevent timeouts. + The default timeout used is generally (0.5 seconds) seconds. + If MAVSDK is used on the same host this timeout can be reduced, while + if MAVSDK has to communicate over links with high latency it might + need to be increased to prevent timeouts. + + Parameters + ---------- + timeout_s : double + Timeout in seconds - Parameters - ---------- - timeout_s : double - Timeout in seconds - """ request = core_pb2.SetMavlinkTimeoutRequest() request.timeout_s = timeout_s response = await self._stub.SetMavlinkTimeout(request) - - \ No newline at end of file diff --git a/mavsdk/core_pb2.py b/mavsdk/core_pb2.py index fbd16b99..d20b4821 100644 --- a/mavsdk/core_pb2.py +++ b/mavsdk/core_pb2.py @@ -4,44 +4,41 @@ # source: core/core.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'core/core.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "core/core.proto" ) # @@protoc_insertion_point(imports) _sym_db = _symbol_database.Default() - - -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'core.core_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "core.core_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\016io.mavsdk.coreB\tCoreProto' - _globals['_SUBSCRIBECONNECTIONSTATEREQUEST']._serialized_start=36 - _globals['_SUBSCRIBECONNECTIONSTATEREQUEST']._serialized_end=69 - _globals['_CONNECTIONSTATERESPONSE']._serialized_start=71 - _globals['_CONNECTIONSTATERESPONSE']._serialized_end=156 - _globals['_SETMAVLINKTIMEOUTREQUEST']._serialized_start=158 - _globals['_SETMAVLINKTIMEOUTREQUEST']._serialized_end=203 - _globals['_SETMAVLINKTIMEOUTRESPONSE']._serialized_start=205 - _globals['_SETMAVLINKTIMEOUTRESPONSE']._serialized_end=232 - _globals['_CONNECTIONSTATE']._serialized_start=234 - _globals['_CONNECTIONSTATE']._serialized_end=273 - _globals['_CORESERVICE']._serialized_start=276 - _globals['_CORESERVICE']._serialized_end=523 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\016io.mavsdk.coreB\tCoreProto" + _globals["_SUBSCRIBECONNECTIONSTATEREQUEST"]._serialized_start = 36 + _globals["_SUBSCRIBECONNECTIONSTATEREQUEST"]._serialized_end = 69 + _globals["_CONNECTIONSTATERESPONSE"]._serialized_start = 71 + _globals["_CONNECTIONSTATERESPONSE"]._serialized_end = 156 + _globals["_SETMAVLINKTIMEOUTREQUEST"]._serialized_start = 158 + _globals["_SETMAVLINKTIMEOUTREQUEST"]._serialized_end = 203 + _globals["_SETMAVLINKTIMEOUTRESPONSE"]._serialized_start = 205 + _globals["_SETMAVLINKTIMEOUTRESPONSE"]._serialized_end = 232 + _globals["_CONNECTIONSTATE"]._serialized_start = 234 + _globals["_CONNECTIONSTATE"]._serialized_end = 273 + _globals["_CORESERVICE"]._serialized_start = 276 + _globals["_CORESERVICE"]._serialized_end = 523 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/core_pb2_grpc.py b/mavsdk/core_pb2_grpc.py index 5ed878f6..54ce42a0 100644 --- a/mavsdk/core_pb2_grpc.py +++ b/mavsdk/core_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import core_pb2 as core_dot_core__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in core/core_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in core/core_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class CoreServiceStub(object): - """Access to the connection state and core configurations - """ + """Access to the connection state and core configurations""" def __init__(self, channel): """Constructor. @@ -36,28 +39,29 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeConnectionState = channel.unary_stream( - '/mavsdk.rpc.core.CoreService/SubscribeConnectionState', - request_serializer=core_dot_core__pb2.SubscribeConnectionStateRequest.SerializeToString, - response_deserializer=core_dot_core__pb2.ConnectionStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.core.CoreService/SubscribeConnectionState", + request_serializer=core_dot_core__pb2.SubscribeConnectionStateRequest.SerializeToString, + response_deserializer=core_dot_core__pb2.ConnectionStateResponse.FromString, + _registered_method=True, + ) self.SetMavlinkTimeout = channel.unary_unary( - '/mavsdk.rpc.core.CoreService/SetMavlinkTimeout', - request_serializer=core_dot_core__pb2.SetMavlinkTimeoutRequest.SerializeToString, - response_deserializer=core_dot_core__pb2.SetMavlinkTimeoutResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.core.CoreService/SetMavlinkTimeout", + request_serializer=core_dot_core__pb2.SetMavlinkTimeoutRequest.SerializeToString, + response_deserializer=core_dot_core__pb2.SetMavlinkTimeoutResponse.FromString, + _registered_method=True, + ) class CoreServiceServicer(object): - """Access to the connection state and core configurations - """ + """Access to the connection state and core configurations""" def SubscribeConnectionState(self, request, context): """ Subscribe to 'connection state' updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetMavlinkTimeout(self, request, context): """ @@ -69,49 +73,53 @@ def SetMavlinkTimeout(self, request, context): need to be increased to prevent timeouts. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_CoreServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeConnectionState': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeConnectionState, - request_deserializer=core_dot_core__pb2.SubscribeConnectionStateRequest.FromString, - response_serializer=core_dot_core__pb2.ConnectionStateResponse.SerializeToString, - ), - 'SetMavlinkTimeout': grpc.unary_unary_rpc_method_handler( - servicer.SetMavlinkTimeout, - request_deserializer=core_dot_core__pb2.SetMavlinkTimeoutRequest.FromString, - response_serializer=core_dot_core__pb2.SetMavlinkTimeoutResponse.SerializeToString, - ), + "SubscribeConnectionState": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeConnectionState, + request_deserializer=core_dot_core__pb2.SubscribeConnectionStateRequest.FromString, + response_serializer=core_dot_core__pb2.ConnectionStateResponse.SerializeToString, + ), + "SetMavlinkTimeout": grpc.unary_unary_rpc_method_handler( + servicer.SetMavlinkTimeout, + request_deserializer=core_dot_core__pb2.SetMavlinkTimeoutRequest.FromString, + response_serializer=core_dot_core__pb2.SetMavlinkTimeoutResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.core.CoreService', rpc_method_handlers) + "mavsdk.rpc.core.CoreService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.core.CoreService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.core.CoreService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class CoreService(object): - """Access to the connection state and core configurations - """ + """Access to the connection state and core configurations""" @staticmethod - def SubscribeConnectionState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeConnectionState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.core.CoreService/SubscribeConnectionState', + "/mavsdk.rpc.core.CoreService/SubscribeConnectionState", core_dot_core__pb2.SubscribeConnectionStateRequest.SerializeToString, core_dot_core__pb2.ConnectionStateResponse.FromString, options, @@ -122,23 +130,26 @@ def SubscribeConnectionState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetMavlinkTimeout(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetMavlinkTimeout( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.core.CoreService/SetMavlinkTimeout', + "/mavsdk.rpc.core.CoreService/SetMavlinkTimeout", core_dot_core__pb2.SetMavlinkTimeoutRequest.SerializeToString, core_dot_core__pb2.SetMavlinkTimeoutResponse.FromString, options, @@ -149,4 +160,5 @@ def SetMavlinkTimeout(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/events.py b/mavsdk/events.py index 403f7589..f557ddb3 100644 --- a/mavsdk/events.py +++ b/mavsdk/events.py @@ -8,37 +8,36 @@ class LogLevel(Enum): """ - Log level type + Log level type - Values - ------ - EMERGENCY - Emergency + Values + ------ + EMERGENCY + Emergency - ALERT - Alert + ALERT + Alert - CRITICAL - Critical + CRITICAL + Critical - ERROR - Error + ERROR + Error - WARNING - Warning + WARNING + Warning - NOTICE - Notice + NOTICE + Notice - INFO - Info + INFO + Info - DEBUG - Debug + DEBUG + Debug - """ + """ - EMERGENCY = 0 ALERT = 1 CRITICAL = 2 @@ -68,7 +67,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == events_pb2.LOG_LEVEL_EMERGENCY: return LogLevel.EMERGENCY if rpc_enum_value == events_pb2.LOG_LEVEL_ALERT: @@ -92,41 +91,34 @@ def __str__(self): class Event: """ - Event type - - Parameters - ---------- - compid : uint32_t - The source component ID of the event + Event type - message : std::string - Short, single-line message + Parameters + ---------- + compid : uint32_t + The source component ID of the event - description : std::string - Detailed description (optional, might be multiple lines) + message : std::string + Short, single-line message - log_level : LogLevel - Log level of message + description : std::string + Detailed description (optional, might be multiple lines) - event_namespace : std::string - Namespace, e.g. "px4" + log_level : LogLevel + Log level of message - event_name : std::string - Event name (unique within the namespace) + event_namespace : std::string + Namespace, e.g. "px4" - """ + event_name : std::string + Event name (unique within the namespace) - + """ def __init__( - self, - compid, - message, - description, - log_level, - event_namespace, - event_name): - """ Initializes the Event object """ + self, compid, message, description, log_level, event_namespace, event_name + ): + """Initializes the Event object""" self.compid = compid self.message = message self.description = description @@ -135,335 +127,246 @@ def __init__( self.event_name = event_name def __eq__(self, to_compare): - """ Checks if two Event are the same """ + """Checks if two Event are the same""" try: # Try to compare - this likely fails when it is compared to a non # Event object - return \ - (self.compid == to_compare.compid) and \ - (self.message == to_compare.message) and \ - (self.description == to_compare.description) and \ - (self.log_level == to_compare.log_level) and \ - (self.event_namespace == to_compare.event_namespace) and \ - (self.event_name == to_compare.event_name) + return ( + (self.compid == to_compare.compid) + and (self.message == to_compare.message) + and (self.description == to_compare.description) + and (self.log_level == to_compare.log_level) + and (self.event_namespace == to_compare.event_namespace) + and (self.event_name == to_compare.event_name) + ) except AttributeError: return False def __str__(self): - """ Event in string representation """ - struct_repr = ", ".join([ + """Event in string representation""" + struct_repr = ", ".join( + [ "compid: " + str(self.compid), "message: " + str(self.message), "description: " + str(self.description), "log_level: " + str(self.log_level), "event_namespace: " + str(self.event_namespace), - "event_name: " + str(self.event_name) - ]) + "event_name: " + str(self.event_name), + ] + ) return f"Event: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEvent): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Event( - - rpcEvent.compid, - - - rpcEvent.message, - - - rpcEvent.description, - - - LogLevel.translate_from_rpc(rpcEvent.log_level), - - - rpcEvent.event_namespace, - - - rpcEvent.event_name - ) + rpcEvent.compid, + rpcEvent.message, + rpcEvent.description, + LogLevel.translate_from_rpc(rpcEvent.log_level), + rpcEvent.event_namespace, + rpcEvent.event_name, + ) def translate_to_rpc(self, rpcEvent): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEvent.compid = self.compid - - - - - + rpcEvent.message = self.message - - - - - + rpcEvent.description = self.description - - - - - + rpcEvent.log_level = self.log_level.translate_to_rpc() - - - - - + rpcEvent.event_namespace = self.event_namespace - - - - - + rpcEvent.event_name = self.event_name - - - class HealthAndArmingCheckProblem: """ - Health and arming check problem type - - Parameters - ---------- - message : std::string - Short, single-line message + Health and arming check problem type - description : std::string - Detailed description (optional, might be multiple lines) + Parameters + ---------- + message : std::string + Short, single-line message - log_level : LogLevel - Log level of message + description : std::string + Detailed description (optional, might be multiple lines) - health_component : std::string - Associated health component, e.g. "gps" + log_level : LogLevel + Log level of message - """ + health_component : std::string + Associated health component, e.g. "gps" - + """ - def __init__( - self, - message, - description, - log_level, - health_component): - """ Initializes the HealthAndArmingCheckProblem object """ + def __init__(self, message, description, log_level, health_component): + """Initializes the HealthAndArmingCheckProblem object""" self.message = message self.description = description self.log_level = log_level self.health_component = health_component def __eq__(self, to_compare): - """ Checks if two HealthAndArmingCheckProblem are the same """ + """Checks if two HealthAndArmingCheckProblem are the same""" try: # Try to compare - this likely fails when it is compared to a non # HealthAndArmingCheckProblem object - return \ - (self.message == to_compare.message) and \ - (self.description == to_compare.description) and \ - (self.log_level == to_compare.log_level) and \ - (self.health_component == to_compare.health_component) + return ( + (self.message == to_compare.message) + and (self.description == to_compare.description) + and (self.log_level == to_compare.log_level) + and (self.health_component == to_compare.health_component) + ) except AttributeError: return False def __str__(self): - """ HealthAndArmingCheckProblem in string representation """ - struct_repr = ", ".join([ + """HealthAndArmingCheckProblem in string representation""" + struct_repr = ", ".join( + [ "message: " + str(self.message), "description: " + str(self.description), "log_level: " + str(self.log_level), - "health_component: " + str(self.health_component) - ]) + "health_component: " + str(self.health_component), + ] + ) return f"HealthAndArmingCheckProblem: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHealthAndArmingCheckProblem): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return HealthAndArmingCheckProblem( - - rpcHealthAndArmingCheckProblem.message, - - - rpcHealthAndArmingCheckProblem.description, - - - LogLevel.translate_from_rpc(rpcHealthAndArmingCheckProblem.log_level), - - - rpcHealthAndArmingCheckProblem.health_component - ) + rpcHealthAndArmingCheckProblem.message, + rpcHealthAndArmingCheckProblem.description, + LogLevel.translate_from_rpc(rpcHealthAndArmingCheckProblem.log_level), + rpcHealthAndArmingCheckProblem.health_component, + ) def translate_to_rpc(self, rpcHealthAndArmingCheckProblem): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcHealthAndArmingCheckProblem.message = self.message - - - - - + rpcHealthAndArmingCheckProblem.description = self.description - - - - - + rpcHealthAndArmingCheckProblem.log_level = self.log_level.translate_to_rpc() - - - - - + rpcHealthAndArmingCheckProblem.health_component = self.health_component - - - class HealthAndArmingCheckMode: """ - Arming checks for a specific mode + Arming checks for a specific mode - Parameters - ---------- - mode_name : std::string - Mode name, e.g. "Position" + Parameters + ---------- + mode_name : std::string + Mode name, e.g. "Position" - can_arm_or_run : bool - If disarmed: indicates if arming is possible. If armed: indicates if the mode can be selected + can_arm_or_run : bool + If disarmed: indicates if arming is possible. If armed: indicates if the mode can be selected - problems : [HealthAndArmingCheckProblem] - List of reported problems for the mode + problems : [HealthAndArmingCheckProblem] + List of reported problems for the mode - """ - - + """ - def __init__( - self, - mode_name, - can_arm_or_run, - problems): - """ Initializes the HealthAndArmingCheckMode object """ + def __init__(self, mode_name, can_arm_or_run, problems): + """Initializes the HealthAndArmingCheckMode object""" self.mode_name = mode_name self.can_arm_or_run = can_arm_or_run self.problems = problems def __eq__(self, to_compare): - """ Checks if two HealthAndArmingCheckMode are the same """ + """Checks if two HealthAndArmingCheckMode are the same""" try: # Try to compare - this likely fails when it is compared to a non # HealthAndArmingCheckMode object - return \ - (self.mode_name == to_compare.mode_name) and \ - (self.can_arm_or_run == to_compare.can_arm_or_run) and \ - (self.problems == to_compare.problems) + return ( + (self.mode_name == to_compare.mode_name) + and (self.can_arm_or_run == to_compare.can_arm_or_run) + and (self.problems == to_compare.problems) + ) except AttributeError: return False def __str__(self): - """ HealthAndArmingCheckMode in string representation """ - struct_repr = ", ".join([ + """HealthAndArmingCheckMode in string representation""" + struct_repr = ", ".join( + [ "mode_name: " + str(self.mode_name), "can_arm_or_run: " + str(self.can_arm_or_run), - "problems: " + str(self.problems) - ]) + "problems: " + str(self.problems), + ] + ) return f"HealthAndArmingCheckMode: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHealthAndArmingCheckMode): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return HealthAndArmingCheckMode( - - rpcHealthAndArmingCheckMode.mode_name, - - - rpcHealthAndArmingCheckMode.can_arm_or_run, - - - list(map(lambda elem: HealthAndArmingCheckProblem.translate_from_rpc(elem), rpcHealthAndArmingCheckMode.problems)) + rpcHealthAndArmingCheckMode.mode_name, + rpcHealthAndArmingCheckMode.can_arm_or_run, + list( + map( + lambda elem: HealthAndArmingCheckProblem.translate_from_rpc(elem), + rpcHealthAndArmingCheckMode.problems, ) + ), + ) def translate_to_rpc(self, rpcHealthAndArmingCheckMode): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcHealthAndArmingCheckMode.mode_name = self.mode_name - - - - - + rpcHealthAndArmingCheckMode.can_arm_or_run = self.can_arm_or_run - - - - - + rpc_elems_list = [] for elem in self.problems: - rpc_elem = events_pb2.HealthAndArmingCheckProblem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcHealthAndArmingCheckMode.problems.extend(rpc_elems_list) - - - class HealthComponentReport: """ - Health component report type + Health component report type - Parameters - ---------- - name : std::string - Unique component name, e.g. "gps" + Parameters + ---------- + name : std::string + Unique component name, e.g. "gps" - label : std::string - Human readable label of the component, e.g. "GPS" or "Accelerometer" + label : std::string + Human readable label of the component, e.g. "GPS" or "Accelerometer" - is_present : bool - If the component is present + is_present : bool + If the component is present - has_error : bool - If the component has errors + has_error : bool + If the component has errors - has_warning : bool - If the component has warnings + has_warning : bool + If the component has warnings - """ - - + """ - def __init__( - self, - name, - label, - is_present, - has_error, - has_warning): - """ Initializes the HealthComponentReport object """ + def __init__(self, name, label, is_present, has_error, has_warning): + """Initializes the HealthComponentReport object""" self.name = name self.label = label self.is_present = is_present @@ -471,244 +374,203 @@ def __init__( self.has_warning = has_warning def __eq__(self, to_compare): - """ Checks if two HealthComponentReport are the same """ + """Checks if two HealthComponentReport are the same""" try: # Try to compare - this likely fails when it is compared to a non # HealthComponentReport object - return \ - (self.name == to_compare.name) and \ - (self.label == to_compare.label) and \ - (self.is_present == to_compare.is_present) and \ - (self.has_error == to_compare.has_error) and \ - (self.has_warning == to_compare.has_warning) + return ( + (self.name == to_compare.name) + and (self.label == to_compare.label) + and (self.is_present == to_compare.is_present) + and (self.has_error == to_compare.has_error) + and (self.has_warning == to_compare.has_warning) + ) except AttributeError: return False def __str__(self): - """ HealthComponentReport in string representation """ - struct_repr = ", ".join([ + """HealthComponentReport in string representation""" + struct_repr = ", ".join( + [ "name: " + str(self.name), "label: " + str(self.label), "is_present: " + str(self.is_present), "has_error: " + str(self.has_error), - "has_warning: " + str(self.has_warning) - ]) + "has_warning: " + str(self.has_warning), + ] + ) return f"HealthComponentReport: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHealthComponentReport): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return HealthComponentReport( - - rpcHealthComponentReport.name, - - - rpcHealthComponentReport.label, - - - rpcHealthComponentReport.is_present, - - - rpcHealthComponentReport.has_error, - - - rpcHealthComponentReport.has_warning - ) + rpcHealthComponentReport.name, + rpcHealthComponentReport.label, + rpcHealthComponentReport.is_present, + rpcHealthComponentReport.has_error, + rpcHealthComponentReport.has_warning, + ) def translate_to_rpc(self, rpcHealthComponentReport): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcHealthComponentReport.name = self.name - - - - - + rpcHealthComponentReport.label = self.label - - - - - + rpcHealthComponentReport.is_present = self.is_present - - - - - + rpcHealthComponentReport.has_error = self.has_error - - - - - + rpcHealthComponentReport.has_warning = self.has_warning - - - class HealthAndArmingCheckReport: """ - Health and arming check report type - - Parameters - ---------- - current_mode_intention : HealthAndArmingCheckMode - Report for currently intended mode + Health and arming check report type - health_components : [HealthComponentReport] - Health components list (e.g. for "gps") + Parameters + ---------- + current_mode_intention : HealthAndArmingCheckMode + Report for currently intended mode - all_problems : [HealthAndArmingCheckProblem] - Complete list of problems + health_components : [HealthComponentReport] + Health components list (e.g. for "gps") - """ + all_problems : [HealthAndArmingCheckProblem] + Complete list of problems - + """ - def __init__( - self, - current_mode_intention, - health_components, - all_problems): - """ Initializes the HealthAndArmingCheckReport object """ + def __init__(self, current_mode_intention, health_components, all_problems): + """Initializes the HealthAndArmingCheckReport object""" self.current_mode_intention = current_mode_intention self.health_components = health_components self.all_problems = all_problems def __eq__(self, to_compare): - """ Checks if two HealthAndArmingCheckReport are the same """ + """Checks if two HealthAndArmingCheckReport are the same""" try: # Try to compare - this likely fails when it is compared to a non # HealthAndArmingCheckReport object - return \ - (self.current_mode_intention == to_compare.current_mode_intention) and \ - (self.health_components == to_compare.health_components) and \ - (self.all_problems == to_compare.all_problems) + return ( + (self.current_mode_intention == to_compare.current_mode_intention) + and (self.health_components == to_compare.health_components) + and (self.all_problems == to_compare.all_problems) + ) except AttributeError: return False def __str__(self): - """ HealthAndArmingCheckReport in string representation """ - struct_repr = ", ".join([ + """HealthAndArmingCheckReport in string representation""" + struct_repr = ", ".join( + [ "current_mode_intention: " + str(self.current_mode_intention), "health_components: " + str(self.health_components), - "all_problems: " + str(self.all_problems) - ]) + "all_problems: " + str(self.all_problems), + ] + ) return f"HealthAndArmingCheckReport: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHealthAndArmingCheckReport): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return HealthAndArmingCheckReport( - - HealthAndArmingCheckMode.translate_from_rpc(rpcHealthAndArmingCheckReport.current_mode_intention), - - - list(map(lambda elem: HealthComponentReport.translate_from_rpc(elem), rpcHealthAndArmingCheckReport.health_components)), - - - list(map(lambda elem: HealthAndArmingCheckProblem.translate_from_rpc(elem), rpcHealthAndArmingCheckReport.all_problems)) + HealthAndArmingCheckMode.translate_from_rpc( + rpcHealthAndArmingCheckReport.current_mode_intention + ), + list( + map( + lambda elem: HealthComponentReport.translate_from_rpc(elem), + rpcHealthAndArmingCheckReport.health_components, + ) + ), + list( + map( + lambda elem: HealthAndArmingCheckProblem.translate_from_rpc(elem), + rpcHealthAndArmingCheckReport.all_problems, ) + ), + ) def translate_to_rpc(self, rpcHealthAndArmingCheckReport): - """ Translates this SDK object into its gRPC equivalent """ - - - - - self.current_mode_intention.translate_to_rpc(rpcHealthAndArmingCheckReport.current_mode_intention) - - - - - + """Translates this SDK object into its gRPC equivalent""" + + self.current_mode_intention.translate_to_rpc( + rpcHealthAndArmingCheckReport.current_mode_intention + ) + rpc_elems_list = [] for elem in self.health_components: - rpc_elem = events_pb2.HealthComponentReport() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcHealthAndArmingCheckReport.health_components.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.all_problems: - rpc_elem = events_pb2.HealthAndArmingCheckProblem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcHealthAndArmingCheckReport.all_problems.extend(rpc_elems_list) - - - class EventsResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned + Possible results returned - Values - ------ - SUCCESS - Successful result + Values + ------ + SUCCESS + Successful result - NOT_AVAILABLE - Not available + NOT_AVAILABLE + Not available - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - UNSUPPORTED - Unsupported + UNSUPPORTED + Unsupported - DENIED - Denied + DENIED + Denied - FAILED - Failed + FAILED + Failed - TIMEOUT - Timeout + TIMEOUT + Timeout - NO_SYSTEM - No system available + NO_SYSTEM + No system available - UNKNOWN - Unknown result + UNKNOWN + Unknown result - """ + """ - SUCCESS = 0 NOT_AVAILABLE = 1 CONNECTION_ERROR = 2 @@ -741,7 +603,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == events_pb2.EventsResult.RESULT_SUCCESS: return EventsResult.Result.SUCCESS if rpc_enum_value == events_pb2.EventsResult.RESULT_NOT_AVAILABLE: @@ -763,69 +625,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the EventsResult object """ + def __init__(self, result, result_str): + """Initializes the EventsResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two EventsResult are the same """ + """Checks if two EventsResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # EventsResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ EventsResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """EventsResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"EventsResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEventsResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return EventsResult( - - EventsResult.Result.translate_from_rpc(rpcEventsResult.result), - - - rpcEventsResult.result_str - ) + EventsResult.Result.translate_from_rpc(rpcEventsResult.result), + rpcEventsResult.result_str, + ) def translate_to_rpc(self, rpcEventsResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEventsResult.result = self.result.translate_to_rpc() - - - - - - rpcEventsResult.result_str = self.result_str - - - + rpcEventsResult.result_str = self.result_str class EventsError(Exception): - """ Raised when a EventsResult is a fail code """ + """Raised when a EventsResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -838,34 +681,32 @@ def __str__(self): class Events(AsyncBase): """ - Get event notifications, such as takeoff, or arming checks + Get event notifications, such as takeoff, or arming checks - Generated by dcsdkgen - MAVSDK Events API + Generated by dcsdkgen - MAVSDK Events API """ # Plugin name name = "Events" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = events_pb2_grpc.EventsServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return EventsResult.translate_from_rpc(response.events_result) - async def events(self): """ - Subscribe to event updates. + Subscribe to event updates. + + Yields + ------- + event : Event + The event - Yields - ------- - event : Event - The event - """ request = events_pb2.SubscribeEventsRequest() @@ -873,61 +714,54 @@ async def events(self): try: async for response in events_stream: - - - yield Event.translate_from_rpc(response.event) finally: events_stream.cancel() async def health_and_arming_checks(self): """ - Subscribe to arming check updates. + Subscribe to arming check updates. + + Yields + ------- + report : HealthAndArmingCheckReport + The report - Yields - ------- - report : HealthAndArmingCheckReport - The report - """ request = events_pb2.SubscribeHealthAndArmingChecksRequest() - health_and_arming_checks_stream = self._stub.SubscribeHealthAndArmingChecks(request) + health_and_arming_checks_stream = self._stub.SubscribeHealthAndArmingChecks( + request + ) try: async for response in health_and_arming_checks_stream: - - - yield HealthAndArmingCheckReport.translate_from_rpc(response.report) finally: health_and_arming_checks_stream.cancel() async def get_health_and_arming_checks_report(self): """ - Get the latest report. + Get the latest report. - Returns - ------- - report : HealthAndArmingCheckReport - The report + Returns + ------- + report : HealthAndArmingCheckReport + The report - Raises - ------ - EventsError - If the request fails. The error contains the reason for the failure. + Raises + ------ + EventsError + If the request fails. The error contains the reason for the failure. """ request = events_pb2.GetHealthAndArmingChecksReportRequest() response = await self._stub.GetHealthAndArmingChecksReport(request) - result = self._extract_result(response) if result.result != EventsResult.Result.SUCCESS: raise EventsError(result, "get_health_and_arming_checks_report()") - return HealthAndArmingCheckReport.translate_from_rpc(response.report) - \ No newline at end of file diff --git a/mavsdk/events_pb2.py b/mavsdk/events_pb2.py index 522c00a1..71dcfd36 100644 --- a/mavsdk/events_pb2.py +++ b/mavsdk/events_pb2.py @@ -4,18 +4,15 @@ # source: events/events.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'events/events.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "events/events.proto" ) # @@protoc_insertion_point(imports) @@ -25,48 +22,62 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13\x65vents/events.proto\x12\x11mavsdk.rpc.events\x1a\x14mavsdk_options.proto\"\x9a\x01\n\x05\x45vent\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\x12\x0f\n\x07message\x18\x02 \x01(\t\x12\x13\n\x0b\x64\x65scription\x18\x03 \x01(\t\x12.\n\tlog_level\x18\x04 \x01(\x0e\x32\x1b.mavsdk.rpc.events.LogLevel\x12\x17\n\x0f\x65vent_namespace\x18\x05 \x01(\t\x12\x12\n\nevent_name\x18\x06 \x01(\t\"\x8d\x01\n\x1bHealthAndArmingCheckProblem\x12\x0f\n\x07message\x18\x01 \x01(\t\x12\x13\n\x0b\x64\x65scription\x18\x02 \x01(\t\x12.\n\tlog_level\x18\x03 \x01(\x0e\x32\x1b.mavsdk.rpc.events.LogLevel\x12\x18\n\x10health_component\x18\x04 \x01(\t\"\x87\x01\n\x18HealthAndArmingCheckMode\x12\x11\n\tmode_name\x18\x01 \x01(\t\x12\x16\n\x0e\x63\x61n_arm_or_run\x18\x02 \x01(\x08\x12@\n\x08problems\x18\x03 \x03(\x0b\x32..mavsdk.rpc.events.HealthAndArmingCheckProblem\"p\n\x15HealthComponentReport\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05label\x18\x02 \x01(\t\x12\x12\n\nis_present\x18\x03 \x01(\x08\x12\x11\n\thas_error\x18\x04 \x01(\x08\x12\x13\n\x0bhas_warning\x18\x05 \x01(\x08\"\xf4\x01\n\x1aHealthAndArmingCheckReport\x12K\n\x16\x63urrent_mode_intention\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.events.HealthAndArmingCheckMode\x12\x43\n\x11health_components\x18\x02 \x03(\x0b\x32(.mavsdk.rpc.events.HealthComponentReport\x12\x44\n\x0c\x61ll_problems\x18\x03 \x03(\x0b\x32..mavsdk.rpc.events.HealthAndArmingCheckProblem\"\xac\x02\n\x0c\x45ventsResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.events.EventsResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xcf\x01\n\x06Result\x12\x12\n\x0eRESULT_SUCCESS\x10\x00\x12\x18\n\x14RESULT_NOT_AVAILABLE\x10\x01\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x02\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x11\n\rRESULT_FAILED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07\x12\x12\n\x0eRESULT_UNKNOWN\x10\x08\"\x18\n\x16SubscribeEventsRequest\"9\n\x0e\x45ventsResponse\x12\'\n\x05\x65vent\x18\x01 \x01(\x0b\x32\x18.mavsdk.rpc.events.Event\"\'\n%SubscribeHealthAndArmingChecksRequest\"^\n\x1dHealthAndArmingChecksResponse\x12=\n\x06report\x18\x01 \x01(\x0b\x32-.mavsdk.rpc.events.HealthAndArmingCheckReport\"\'\n%GetHealthAndArmingChecksReportRequest\"\x9f\x01\n&GetHealthAndArmingChecksReportResponse\x12\x36\n\revents_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.events.EventsResult\x12=\n\x06report\x18\x02 \x01(\x0b\x32-.mavsdk.rpc.events.HealthAndArmingCheckReport*\xbb\x01\n\x08LogLevel\x12\x17\n\x13LOG_LEVEL_EMERGENCY\x10\x00\x12\x13\n\x0fLOG_LEVEL_ALERT\x10\x01\x12\x16\n\x12LOG_LEVEL_CRITICAL\x10\x02\x12\x13\n\x0fLOG_LEVEL_ERROR\x10\x03\x12\x15\n\x11LOG_LEVEL_WARNING\x10\x04\x12\x14\n\x10LOG_LEVEL_NOTICE\x10\x05\x12\x12\n\x0eLOG_LEVEL_INFO\x10\x06\x12\x13\n\x0fLOG_LEVEL_DEBUG\x10\x07\x32\xad\x03\n\rEventsService\x12g\n\x0fSubscribeEvents\x12).mavsdk.rpc.events.SubscribeEventsRequest\x1a!.mavsdk.rpc.events.EventsResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x94\x01\n\x1eSubscribeHealthAndArmingChecks\x12\x38.mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest\x1a\x30.mavsdk.rpc.events.HealthAndArmingChecksResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9b\x01\n\x1eGetHealthAndArmingChecksReport\x12\x38.mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest\x1a\x39.mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse\"\x04\x80\xb5\x18\x01\x42\x1f\n\x10io.mavsdk.eventsB\x0b\x45ventsProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x13\x65vents/events.proto\x12\x11mavsdk.rpc.events\x1a\x14mavsdk_options.proto"\x9a\x01\n\x05\x45vent\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\x12\x0f\n\x07message\x18\x02 \x01(\t\x12\x13\n\x0b\x64\x65scription\x18\x03 \x01(\t\x12.\n\tlog_level\x18\x04 \x01(\x0e\x32\x1b.mavsdk.rpc.events.LogLevel\x12\x17\n\x0f\x65vent_namespace\x18\x05 \x01(\t\x12\x12\n\nevent_name\x18\x06 \x01(\t"\x8d\x01\n\x1bHealthAndArmingCheckProblem\x12\x0f\n\x07message\x18\x01 \x01(\t\x12\x13\n\x0b\x64\x65scription\x18\x02 \x01(\t\x12.\n\tlog_level\x18\x03 \x01(\x0e\x32\x1b.mavsdk.rpc.events.LogLevel\x12\x18\n\x10health_component\x18\x04 \x01(\t"\x87\x01\n\x18HealthAndArmingCheckMode\x12\x11\n\tmode_name\x18\x01 \x01(\t\x12\x16\n\x0e\x63\x61n_arm_or_run\x18\x02 \x01(\x08\x12@\n\x08problems\x18\x03 \x03(\x0b\x32..mavsdk.rpc.events.HealthAndArmingCheckProblem"p\n\x15HealthComponentReport\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05label\x18\x02 \x01(\t\x12\x12\n\nis_present\x18\x03 \x01(\x08\x12\x11\n\thas_error\x18\x04 \x01(\x08\x12\x13\n\x0bhas_warning\x18\x05 \x01(\x08"\xf4\x01\n\x1aHealthAndArmingCheckReport\x12K\n\x16\x63urrent_mode_intention\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.events.HealthAndArmingCheckMode\x12\x43\n\x11health_components\x18\x02 \x03(\x0b\x32(.mavsdk.rpc.events.HealthComponentReport\x12\x44\n\x0c\x61ll_problems\x18\x03 \x03(\x0b\x32..mavsdk.rpc.events.HealthAndArmingCheckProblem"\xac\x02\n\x0c\x45ventsResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.events.EventsResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xcf\x01\n\x06Result\x12\x12\n\x0eRESULT_SUCCESS\x10\x00\x12\x18\n\x14RESULT_NOT_AVAILABLE\x10\x01\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x02\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x03\x12\x11\n\rRESULT_DENIED\x10\x04\x12\x11\n\rRESULT_FAILED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07\x12\x12\n\x0eRESULT_UNKNOWN\x10\x08"\x18\n\x16SubscribeEventsRequest"9\n\x0e\x45ventsResponse\x12\'\n\x05\x65vent\x18\x01 \x01(\x0b\x32\x18.mavsdk.rpc.events.Event"\'\n%SubscribeHealthAndArmingChecksRequest"^\n\x1dHealthAndArmingChecksResponse\x12=\n\x06report\x18\x01 \x01(\x0b\x32-.mavsdk.rpc.events.HealthAndArmingCheckReport"\'\n%GetHealthAndArmingChecksReportRequest"\x9f\x01\n&GetHealthAndArmingChecksReportResponse\x12\x36\n\revents_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.events.EventsResult\x12=\n\x06report\x18\x02 \x01(\x0b\x32-.mavsdk.rpc.events.HealthAndArmingCheckReport*\xbb\x01\n\x08LogLevel\x12\x17\n\x13LOG_LEVEL_EMERGENCY\x10\x00\x12\x13\n\x0fLOG_LEVEL_ALERT\x10\x01\x12\x16\n\x12LOG_LEVEL_CRITICAL\x10\x02\x12\x13\n\x0fLOG_LEVEL_ERROR\x10\x03\x12\x15\n\x11LOG_LEVEL_WARNING\x10\x04\x12\x14\n\x10LOG_LEVEL_NOTICE\x10\x05\x12\x12\n\x0eLOG_LEVEL_INFO\x10\x06\x12\x13\n\x0fLOG_LEVEL_DEBUG\x10\x07\x32\xad\x03\n\rEventsService\x12g\n\x0fSubscribeEvents\x12).mavsdk.rpc.events.SubscribeEventsRequest\x1a!.mavsdk.rpc.events.EventsResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x94\x01\n\x1eSubscribeHealthAndArmingChecks\x12\x38.mavsdk.rpc.events.SubscribeHealthAndArmingChecksRequest\x1a\x30.mavsdk.rpc.events.HealthAndArmingChecksResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9b\x01\n\x1eGetHealthAndArmingChecksReport\x12\x38.mavsdk.rpc.events.GetHealthAndArmingChecksReportRequest\x1a\x39.mavsdk.rpc.events.GetHealthAndArmingChecksReportResponse"\x04\x80\xb5\x18\x01\x42\x1f\n\x10io.mavsdk.eventsB\x0b\x45ventsProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'events.events_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "events.events_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\020io.mavsdk.eventsB\013EventsProto' - _globals['_EVENTSSERVICE'].methods_by_name['SubscribeEvents']._loaded_options = None - _globals['_EVENTSSERVICE'].methods_by_name['SubscribeEvents']._serialized_options = b'\200\265\030\000' - _globals['_EVENTSSERVICE'].methods_by_name['SubscribeHealthAndArmingChecks']._loaded_options = None - _globals['_EVENTSSERVICE'].methods_by_name['SubscribeHealthAndArmingChecks']._serialized_options = b'\200\265\030\000' - _globals['_EVENTSSERVICE'].methods_by_name['GetHealthAndArmingChecksReport']._loaded_options = None - _globals['_EVENTSSERVICE'].methods_by_name['GetHealthAndArmingChecksReport']._serialized_options = b'\200\265\030\001' - _globals['_LOGLEVEL']._serialized_start=1593 - _globals['_LOGLEVEL']._serialized_end=1780 - _globals['_EVENT']._serialized_start=65 - _globals['_EVENT']._serialized_end=219 - _globals['_HEALTHANDARMINGCHECKPROBLEM']._serialized_start=222 - _globals['_HEALTHANDARMINGCHECKPROBLEM']._serialized_end=363 - _globals['_HEALTHANDARMINGCHECKMODE']._serialized_start=366 - _globals['_HEALTHANDARMINGCHECKMODE']._serialized_end=501 - _globals['_HEALTHCOMPONENTREPORT']._serialized_start=503 - _globals['_HEALTHCOMPONENTREPORT']._serialized_end=615 - _globals['_HEALTHANDARMINGCHECKREPORT']._serialized_start=618 - _globals['_HEALTHANDARMINGCHECKREPORT']._serialized_end=862 - _globals['_EVENTSRESULT']._serialized_start=865 - _globals['_EVENTSRESULT']._serialized_end=1165 - _globals['_EVENTSRESULT_RESULT']._serialized_start=958 - _globals['_EVENTSRESULT_RESULT']._serialized_end=1165 - _globals['_SUBSCRIBEEVENTSREQUEST']._serialized_start=1167 - _globals['_SUBSCRIBEEVENTSREQUEST']._serialized_end=1191 - _globals['_EVENTSRESPONSE']._serialized_start=1193 - _globals['_EVENTSRESPONSE']._serialized_end=1250 - _globals['_SUBSCRIBEHEALTHANDARMINGCHECKSREQUEST']._serialized_start=1252 - _globals['_SUBSCRIBEHEALTHANDARMINGCHECKSREQUEST']._serialized_end=1291 - _globals['_HEALTHANDARMINGCHECKSRESPONSE']._serialized_start=1293 - _globals['_HEALTHANDARMINGCHECKSRESPONSE']._serialized_end=1387 - _globals['_GETHEALTHANDARMINGCHECKSREPORTREQUEST']._serialized_start=1389 - _globals['_GETHEALTHANDARMINGCHECKSREPORTREQUEST']._serialized_end=1428 - _globals['_GETHEALTHANDARMINGCHECKSREPORTRESPONSE']._serialized_start=1431 - _globals['_GETHEALTHANDARMINGCHECKSREPORTRESPONSE']._serialized_end=1590 - _globals['_EVENTSSERVICE']._serialized_start=1783 - _globals['_EVENTSSERVICE']._serialized_end=2212 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\020io.mavsdk.eventsB\013EventsProto" + _globals["_EVENTSSERVICE"].methods_by_name["SubscribeEvents"]._loaded_options = None + _globals["_EVENTSSERVICE"].methods_by_name[ + "SubscribeEvents" + ]._serialized_options = b"\200\265\030\000" + _globals["_EVENTSSERVICE"].methods_by_name[ + "SubscribeHealthAndArmingChecks" + ]._loaded_options = None + _globals["_EVENTSSERVICE"].methods_by_name[ + "SubscribeHealthAndArmingChecks" + ]._serialized_options = b"\200\265\030\000" + _globals["_EVENTSSERVICE"].methods_by_name[ + "GetHealthAndArmingChecksReport" + ]._loaded_options = None + _globals["_EVENTSSERVICE"].methods_by_name[ + "GetHealthAndArmingChecksReport" + ]._serialized_options = b"\200\265\030\001" + _globals["_LOGLEVEL"]._serialized_start = 1593 + _globals["_LOGLEVEL"]._serialized_end = 1780 + _globals["_EVENT"]._serialized_start = 65 + _globals["_EVENT"]._serialized_end = 219 + _globals["_HEALTHANDARMINGCHECKPROBLEM"]._serialized_start = 222 + _globals["_HEALTHANDARMINGCHECKPROBLEM"]._serialized_end = 363 + _globals["_HEALTHANDARMINGCHECKMODE"]._serialized_start = 366 + _globals["_HEALTHANDARMINGCHECKMODE"]._serialized_end = 501 + _globals["_HEALTHCOMPONENTREPORT"]._serialized_start = 503 + _globals["_HEALTHCOMPONENTREPORT"]._serialized_end = 615 + _globals["_HEALTHANDARMINGCHECKREPORT"]._serialized_start = 618 + _globals["_HEALTHANDARMINGCHECKREPORT"]._serialized_end = 862 + _globals["_EVENTSRESULT"]._serialized_start = 865 + _globals["_EVENTSRESULT"]._serialized_end = 1165 + _globals["_EVENTSRESULT_RESULT"]._serialized_start = 958 + _globals["_EVENTSRESULT_RESULT"]._serialized_end = 1165 + _globals["_SUBSCRIBEEVENTSREQUEST"]._serialized_start = 1167 + _globals["_SUBSCRIBEEVENTSREQUEST"]._serialized_end = 1191 + _globals["_EVENTSRESPONSE"]._serialized_start = 1193 + _globals["_EVENTSRESPONSE"]._serialized_end = 1250 + _globals["_SUBSCRIBEHEALTHANDARMINGCHECKSREQUEST"]._serialized_start = 1252 + _globals["_SUBSCRIBEHEALTHANDARMINGCHECKSREQUEST"]._serialized_end = 1291 + _globals["_HEALTHANDARMINGCHECKSRESPONSE"]._serialized_start = 1293 + _globals["_HEALTHANDARMINGCHECKSRESPONSE"]._serialized_end = 1387 + _globals["_GETHEALTHANDARMINGCHECKSREPORTREQUEST"]._serialized_start = 1389 + _globals["_GETHEALTHANDARMINGCHECKSREPORTREQUEST"]._serialized_end = 1428 + _globals["_GETHEALTHANDARMINGCHECKSREPORTRESPONSE"]._serialized_start = 1431 + _globals["_GETHEALTHANDARMINGCHECKSREPORTRESPONSE"]._serialized_end = 1590 + _globals["_EVENTSSERVICE"]._serialized_start = 1783 + _globals["_EVENTSSERVICE"]._serialized_end = 2212 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/events_pb2_grpc.py b/mavsdk/events_pb2_grpc.py index 6dd9ddc8..4f1dad8f 100644 --- a/mavsdk/events_pb2_grpc.py +++ b/mavsdk/events_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import events_pb2 as events_dot_events__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in events/events_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in events/events_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class EventsServiceStub(object): - """Get event notifications, such as takeoff, or arming checks - """ + """Get event notifications, such as takeoff, or arming checks""" def __init__(self, channel): """Constructor. @@ -36,95 +39,101 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeEvents = channel.unary_stream( - '/mavsdk.rpc.events.EventsService/SubscribeEvents', - request_serializer=events_dot_events__pb2.SubscribeEventsRequest.SerializeToString, - response_deserializer=events_dot_events__pb2.EventsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.events.EventsService/SubscribeEvents", + request_serializer=events_dot_events__pb2.SubscribeEventsRequest.SerializeToString, + response_deserializer=events_dot_events__pb2.EventsResponse.FromString, + _registered_method=True, + ) self.SubscribeHealthAndArmingChecks = channel.unary_stream( - '/mavsdk.rpc.events.EventsService/SubscribeHealthAndArmingChecks', - request_serializer=events_dot_events__pb2.SubscribeHealthAndArmingChecksRequest.SerializeToString, - response_deserializer=events_dot_events__pb2.HealthAndArmingChecksResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.events.EventsService/SubscribeHealthAndArmingChecks", + request_serializer=events_dot_events__pb2.SubscribeHealthAndArmingChecksRequest.SerializeToString, + response_deserializer=events_dot_events__pb2.HealthAndArmingChecksResponse.FromString, + _registered_method=True, + ) self.GetHealthAndArmingChecksReport = channel.unary_unary( - '/mavsdk.rpc.events.EventsService/GetHealthAndArmingChecksReport', - request_serializer=events_dot_events__pb2.GetHealthAndArmingChecksReportRequest.SerializeToString, - response_deserializer=events_dot_events__pb2.GetHealthAndArmingChecksReportResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.events.EventsService/GetHealthAndArmingChecksReport", + request_serializer=events_dot_events__pb2.GetHealthAndArmingChecksReportRequest.SerializeToString, + response_deserializer=events_dot_events__pb2.GetHealthAndArmingChecksReportResponse.FromString, + _registered_method=True, + ) class EventsServiceServicer(object): - """Get event notifications, such as takeoff, or arming checks - """ + """Get event notifications, such as takeoff, or arming checks""" def SubscribeEvents(self, request, context): """ Subscribe to event updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeHealthAndArmingChecks(self, request, context): """ Subscribe to arming check updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetHealthAndArmingChecksReport(self, request, context): """ Get the latest report. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_EventsServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeEvents': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeEvents, - request_deserializer=events_dot_events__pb2.SubscribeEventsRequest.FromString, - response_serializer=events_dot_events__pb2.EventsResponse.SerializeToString, - ), - 'SubscribeHealthAndArmingChecks': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeHealthAndArmingChecks, - request_deserializer=events_dot_events__pb2.SubscribeHealthAndArmingChecksRequest.FromString, - response_serializer=events_dot_events__pb2.HealthAndArmingChecksResponse.SerializeToString, - ), - 'GetHealthAndArmingChecksReport': grpc.unary_unary_rpc_method_handler( - servicer.GetHealthAndArmingChecksReport, - request_deserializer=events_dot_events__pb2.GetHealthAndArmingChecksReportRequest.FromString, - response_serializer=events_dot_events__pb2.GetHealthAndArmingChecksReportResponse.SerializeToString, - ), + "SubscribeEvents": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeEvents, + request_deserializer=events_dot_events__pb2.SubscribeEventsRequest.FromString, + response_serializer=events_dot_events__pb2.EventsResponse.SerializeToString, + ), + "SubscribeHealthAndArmingChecks": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeHealthAndArmingChecks, + request_deserializer=events_dot_events__pb2.SubscribeHealthAndArmingChecksRequest.FromString, + response_serializer=events_dot_events__pb2.HealthAndArmingChecksResponse.SerializeToString, + ), + "GetHealthAndArmingChecksReport": grpc.unary_unary_rpc_method_handler( + servicer.GetHealthAndArmingChecksReport, + request_deserializer=events_dot_events__pb2.GetHealthAndArmingChecksReportRequest.FromString, + response_serializer=events_dot_events__pb2.GetHealthAndArmingChecksReportResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.events.EventsService', rpc_method_handlers) + "mavsdk.rpc.events.EventsService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.events.EventsService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.events.EventsService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class EventsService(object): - """Get event notifications, such as takeoff, or arming checks - """ + """Get event notifications, such as takeoff, or arming checks""" @staticmethod - def SubscribeEvents(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeEvents( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.events.EventsService/SubscribeEvents', + "/mavsdk.rpc.events.EventsService/SubscribeEvents", events_dot_events__pb2.SubscribeEventsRequest.SerializeToString, events_dot_events__pb2.EventsResponse.FromString, options, @@ -135,23 +144,26 @@ def SubscribeEvents(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeHealthAndArmingChecks(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeHealthAndArmingChecks( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.events.EventsService/SubscribeHealthAndArmingChecks', + "/mavsdk.rpc.events.EventsService/SubscribeHealthAndArmingChecks", events_dot_events__pb2.SubscribeHealthAndArmingChecksRequest.SerializeToString, events_dot_events__pb2.HealthAndArmingChecksResponse.FromString, options, @@ -162,23 +174,26 @@ def SubscribeHealthAndArmingChecks(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetHealthAndArmingChecksReport(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetHealthAndArmingChecksReport( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.events.EventsService/GetHealthAndArmingChecksReport', + "/mavsdk.rpc.events.EventsService/GetHealthAndArmingChecksReport", events_dot_events__pb2.GetHealthAndArmingChecksReportRequest.SerializeToString, events_dot_events__pb2.GetHealthAndArmingChecksReportResponse.FromString, options, @@ -189,4 +204,5 @@ def GetHealthAndArmingChecksReport(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/failure.py b/mavsdk/failure.py index 6b7da425..d764b00b 100644 --- a/mavsdk/failure.py +++ b/mavsdk/failure.py @@ -8,58 +8,57 @@ class FailureUnit(Enum): """ - A failure unit. + A failure unit. - Values - ------ - SENSOR_GYRO - Gyro + Values + ------ + SENSOR_GYRO + Gyro - SENSOR_ACCEL - Accelerometer + SENSOR_ACCEL + Accelerometer - SENSOR_MAG - Magnetometer + SENSOR_MAG + Magnetometer - SENSOR_BARO - Barometer + SENSOR_BARO + Barometer - SENSOR_GPS - GPS + SENSOR_GPS + GPS - SENSOR_OPTICAL_FLOW - Optical flow + SENSOR_OPTICAL_FLOW + Optical flow - SENSOR_VIO - Visual inertial odometry + SENSOR_VIO + Visual inertial odometry - SENSOR_DISTANCE_SENSOR - Distance sensor + SENSOR_DISTANCE_SENSOR + Distance sensor - SENSOR_AIRSPEED - Airspeed + SENSOR_AIRSPEED + Airspeed - SYSTEM_BATTERY - Battery + SYSTEM_BATTERY + Battery - SYSTEM_MOTOR - Motor + SYSTEM_MOTOR + Motor - SYSTEM_SERVO - Servo + SYSTEM_SERVO + Servo - SYSTEM_AVOIDANCE - Avoidance + SYSTEM_AVOIDANCE + Avoidance - SYSTEM_RC_SIGNAL - RC signal + SYSTEM_RC_SIGNAL + RC signal - SYSTEM_MAVLINK_SIGNAL - MAVLink signal + SYSTEM_MAVLINK_SIGNAL + MAVLink signal - """ + """ - SENSOR_GYRO = 0 SENSOR_ACCEL = 1 SENSOR_MAG = 2 @@ -110,7 +109,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_GYRO: return FailureUnit.SENSOR_GYRO if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_ACCEL: @@ -148,37 +147,36 @@ def __str__(self): class FailureType(Enum): """ - A failure type + A failure type - Values - ------ - OK - No failure injected, used to reset a previous failure + Values + ------ + OK + No failure injected, used to reset a previous failure - OFF - Sets unit off, so completely non-responsive + OFF + Sets unit off, so completely non-responsive - STUCK - Unit is stuck e.g. keeps reporting the same value + STUCK + Unit is stuck e.g. keeps reporting the same value - GARBAGE - Unit is reporting complete garbage + GARBAGE + Unit is reporting complete garbage - WRONG - Unit is consistently wrong + WRONG + Unit is consistently wrong - SLOW - Unit is slow, so e.g. reporting at slower than expected rate + SLOW + Unit is slow, so e.g. reporting at slower than expected rate - DELAYED - Data of unit is delayed in time + DELAYED + Data of unit is delayed in time - INTERMITTENT - Unit is sometimes working, sometimes not + INTERMITTENT + Unit is sometimes working, sometimes not - """ + """ - OK = 0 OFF = 1 STUCK = 2 @@ -208,7 +206,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == failure_pb2.FAILURE_TYPE_OK: return FailureType.OK if rpc_enum_value == failure_pb2.FAILURE_TYPE_OFF: @@ -232,53 +230,50 @@ def __str__(self): class FailureResult: """ - - Parameters - ---------- - result : Result - Result enum value - result_str : std::string - Human-readable English string describing the result + Parameters + ---------- + result : Result + Result enum value - """ + result_str : std::string + Human-readable English string describing the result + + """ - - class Result(Enum): """ - Possible results returned for failure requests. + Possible results returned for failure requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - UNSUPPORTED - Failure not supported + UNSUPPORTED + Failure not supported - DENIED - Failure injection denied + DENIED + Failure injection denied - DISABLED - Failure injection is disabled + DISABLED + Failure injection is disabled - TIMEOUT - Request timed out + TIMEOUT + Request timed out - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -308,7 +303,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == failure_pb2.FailureResult.RESULT_UNKNOWN: return FailureResult.Result.UNKNOWN if rpc_enum_value == failure_pb2.FailureResult.RESULT_SUCCESS: @@ -328,69 +323,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the FailureResult object """ + def __init__(self, result, result_str): + """Initializes the FailureResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two FailureResult are the same """ + """Checks if two FailureResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # FailureResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ FailureResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """FailureResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"FailureResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFailureResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FailureResult( - - FailureResult.Result.translate_from_rpc(rpcFailureResult.result), - - - rpcFailureResult.result_str - ) + FailureResult.Result.translate_from_rpc(rpcFailureResult.result), + rpcFailureResult.result_str, + ) def translate_to_rpc(self, rpcFailureResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFailureResult.result = self.result.translate_to_rpc() - - - - - - rpcFailureResult.result_str = self.result_str - - - + rpcFailureResult.result_str = self.result_str class FailureError(Exception): - """ Raised when a FailureResult is a fail code """ + """Raised when a FailureResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -403,60 +379,53 @@ def __str__(self): class Failure(AsyncBase): """ - Inject failures into system to test failsafes. + Inject failures into system to test failsafes. - Generated by dcsdkgen - MAVSDK Failure API + Generated by dcsdkgen - MAVSDK Failure API """ # Plugin name name = "Failure" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = failure_pb2_grpc.FailureServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return FailureResult.translate_from_rpc(response.failure_result) - async def inject(self, failure_unit, failure_type, instance): """ - Injects a failure. + Injects a failure. - Parameters - ---------- - failure_unit : FailureUnit - The failure unit to send + Parameters + ---------- + failure_unit : FailureUnit + The failure unit to send - failure_type : FailureType - The failure type to send + failure_type : FailureType + The failure type to send - instance : int32_t - Instance to affect (0 for all) + instance : int32_t + Instance to affect (0 for all) - Raises - ------ - FailureError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FailureError + If the request fails. The error contains the reason for the failure. """ request = failure_pb2.InjectRequest() - + request.failure_unit = failure_unit.translate_to_rpc() - - - + request.failure_type = failure_type.translate_to_rpc() - - + request.instance = instance response = await self._stub.Inject(request) - result = self._extract_result(response) if result.result != FailureResult.Result.SUCCESS: raise FailureError(result, "inject()", failure_unit, failure_type, instance) - \ No newline at end of file diff --git a/mavsdk/failure_pb2.py b/mavsdk/failure_pb2.py index cac2c4b9..024a74a6 100644 --- a/mavsdk/failure_pb2.py +++ b/mavsdk/failure_pb2.py @@ -4,18 +4,15 @@ # source: failure/failure.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'failure/failure.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "failure/failure.proto" ) # @@protoc_insertion_point(imports) @@ -25,28 +22,34 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'failure.failure_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "failure.failure_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\021io.mavsdk.failureB\014FailureProto' - _globals['_FAILURESERVICE'].methods_by_name['Inject']._loaded_options = None - _globals['_FAILURESERVICE'].methods_by_name['Inject']._serialized_options = b'\200\265\030\001' - _globals['_FAILUREUNIT']._serialized_start=573 - _globals['_FAILUREUNIT']._serialized_end=1082 - _globals['_FAILURETYPE']._serialized_start=1085 - _globals['_FAILURETYPE']._serialized_end=1295 - _globals['_INJECTREQUEST']._serialized_start=68 - _globals['_INJECTREQUEST']._serialized_end=211 - _globals['_INJECTRESPONSE']._serialized_start=213 - _globals['_INJECTRESPONSE']._serialized_end=288 - _globals['_FAILURERESULT']._serialized_start=291 - _globals['_FAILURERESULT']._serialized_end=570 - _globals['_FAILURERESULT_RESULT']._serialized_start=387 - _globals['_FAILURERESULT_RESULT']._serialized_end=570 - _globals['_FAILURESERVICE']._serialized_start=1297 - _globals['_FAILURESERVICE']._serialized_end=1400 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\021io.mavsdk.failureB\014FailureProto" + _globals["_FAILURESERVICE"].methods_by_name["Inject"]._loaded_options = None + _globals["_FAILURESERVICE"].methods_by_name[ + "Inject" + ]._serialized_options = b"\200\265\030\001" + _globals["_FAILUREUNIT"]._serialized_start = 573 + _globals["_FAILUREUNIT"]._serialized_end = 1082 + _globals["_FAILURETYPE"]._serialized_start = 1085 + _globals["_FAILURETYPE"]._serialized_end = 1295 + _globals["_INJECTREQUEST"]._serialized_start = 68 + _globals["_INJECTREQUEST"]._serialized_end = 211 + _globals["_INJECTRESPONSE"]._serialized_start = 213 + _globals["_INJECTRESPONSE"]._serialized_end = 288 + _globals["_FAILURERESULT"]._serialized_start = 291 + _globals["_FAILURERESULT"]._serialized_end = 570 + _globals["_FAILURERESULT_RESULT"]._serialized_start = 387 + _globals["_FAILURERESULT_RESULT"]._serialized_end = 570 + _globals["_FAILURESERVICE"]._serialized_start = 1297 + _globals["_FAILURESERVICE"]._serialized_end = 1400 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/failure_pb2_grpc.py b/mavsdk/failure_pb2_grpc.py index 86b3098d..34b2eb7f 100644 --- a/mavsdk/failure_pb2_grpc.py +++ b/mavsdk/failure_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import failure_pb2 as failure_dot_failure__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in failure/failure_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in failure/failure_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class FailureServiceStub(object): - """Inject failures into system to test failsafes. - """ + """Inject failures into system to test failsafes.""" def __init__(self, channel): """Constructor. @@ -36,58 +39,61 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.Inject = channel.unary_unary( - '/mavsdk.rpc.failure.FailureService/Inject', - request_serializer=failure_dot_failure__pb2.InjectRequest.SerializeToString, - response_deserializer=failure_dot_failure__pb2.InjectResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.failure.FailureService/Inject", + request_serializer=failure_dot_failure__pb2.InjectRequest.SerializeToString, + response_deserializer=failure_dot_failure__pb2.InjectResponse.FromString, + _registered_method=True, + ) class FailureServiceServicer(object): - """Inject failures into system to test failsafes. - """ + """Inject failures into system to test failsafes.""" def Inject(self, request, context): - """Injects a failure. - """ + """Injects a failure.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_FailureServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'Inject': grpc.unary_unary_rpc_method_handler( - servicer.Inject, - request_deserializer=failure_dot_failure__pb2.InjectRequest.FromString, - response_serializer=failure_dot_failure__pb2.InjectResponse.SerializeToString, - ), + "Inject": grpc.unary_unary_rpc_method_handler( + servicer.Inject, + request_deserializer=failure_dot_failure__pb2.InjectRequest.FromString, + response_serializer=failure_dot_failure__pb2.InjectResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.failure.FailureService', rpc_method_handlers) + "mavsdk.rpc.failure.FailureService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.failure.FailureService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.failure.FailureService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class FailureService(object): - """Inject failures into system to test failsafes. - """ + """Inject failures into system to test failsafes.""" @staticmethod - def Inject(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Inject( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.failure.FailureService/Inject', + "/mavsdk.rpc.failure.FailureService/Inject", failure_dot_failure__pb2.InjectRequest.SerializeToString, failure_dot_failure__pb2.InjectResponse.FromString, options, @@ -98,4 +104,5 @@ def Inject(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/follow_me.py b/mavsdk/follow_me.py index 168fbc1e..c89cf5df 100644 --- a/mavsdk/follow_me.py +++ b/mavsdk/follow_me.py @@ -8,50 +8,47 @@ class Config: """ - Configuration type. + Configuration type. - Parameters - ---------- - follow_height_m : float - [m] Follow height in meters (recommended minimum 8 meters) + Parameters + ---------- + follow_height_m : float + [m] Follow height in meters (recommended minimum 8 meters) - follow_distance_m : float - [m] Follow distance to target in meters (recommended minimum 4 meter) + follow_distance_m : float + [m] Follow distance to target in meters (recommended minimum 4 meter) - responsiveness : float - How responsive the vehicle is to the motion of the target, Lower value = More responsive (range 0.0 to 1.0) + responsiveness : float + How responsive the vehicle is to the motion of the target, Lower value = More responsive (range 0.0 to 1.0) - altitude_mode : FollowAltitudeMode - Follow Altitude control mode + altitude_mode : FollowAltitudeMode + Follow Altitude control mode - max_tangential_vel_m_s : float - [m/s] Maximum orbit tangential velocity relative to the target, in meters per second. Higher value = More aggressive follow angle tracking. + max_tangential_vel_m_s : float + [m/s] Maximum orbit tangential velocity relative to the target, in meters per second. Higher value = More aggressive follow angle tracking. - follow_angle_deg : float - [deg] Follow Angle relative to the target. 0 equals following in front of the target's direction. Angle increases in Clockwise direction, so following from right would be 90 degrees, from the left is -90 degrees, and so on. + follow_angle_deg : float + [deg] Follow Angle relative to the target. 0 equals following in front of the target's direction. Angle increases in Clockwise direction, so following from right would be 90 degrees, from the left is -90 degrees, and so on. - """ + """ - - class FollowAltitudeMode(Enum): """ - Altitude mode to configure which altitude the follow me will assume the target to be at. + Altitude mode to configure which altitude the follow me will assume the target to be at. - Values - ------ - CONSTANT - Target assumed to be mobing at a constant altitude of home position (where the vehicle armed) + Values + ------ + CONSTANT + Target assumed to be mobing at a constant altitude of home position (where the vehicle armed) - TERRAIN - Target assumed to be at the terrain level sensed by the distance sensor + TERRAIN + Target assumed to be at the terrain level sensed by the distance sensor - TARGET_GPS - Target GPS altitude taken into account to do 3D tracking + TARGET_GPS + Target GPS altitude taken into account to do 3D tracking - """ + """ - CONSTANT = 0 TERRAIN = 1 TARGET_GPS = 2 @@ -66,7 +63,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == follow_me_pb2.Config.FOLLOW_ALTITUDE_MODE_CONSTANT: return Config.FollowAltitudeMode.CONSTANT if rpc_enum_value == follow_me_pb2.Config.FOLLOW_ALTITUDE_MODE_TERRAIN: @@ -76,17 +73,17 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - def __init__( - self, - follow_height_m, - follow_distance_m, - responsiveness, - altitude_mode, - max_tangential_vel_m_s, - follow_angle_deg): - """ Initializes the Config object """ + self, + follow_height_m, + follow_distance_m, + responsiveness, + altitude_mode, + max_tangential_vel_m_s, + follow_angle_deg, + ): + """Initializes the Config object""" self.follow_height_m = follow_height_m self.follow_distance_m = follow_distance_m self.responsiveness = responsiveness @@ -95,136 +92,101 @@ def __init__( self.follow_angle_deg = follow_angle_deg def __eq__(self, to_compare): - """ Checks if two Config are the same """ + """Checks if two Config are the same""" try: # Try to compare - this likely fails when it is compared to a non # Config object - return \ - (self.follow_height_m == to_compare.follow_height_m) and \ - (self.follow_distance_m == to_compare.follow_distance_m) and \ - (self.responsiveness == to_compare.responsiveness) and \ - (self.altitude_mode == to_compare.altitude_mode) and \ - (self.max_tangential_vel_m_s == to_compare.max_tangential_vel_m_s) and \ - (self.follow_angle_deg == to_compare.follow_angle_deg) + return ( + (self.follow_height_m == to_compare.follow_height_m) + and (self.follow_distance_m == to_compare.follow_distance_m) + and (self.responsiveness == to_compare.responsiveness) + and (self.altitude_mode == to_compare.altitude_mode) + and (self.max_tangential_vel_m_s == to_compare.max_tangential_vel_m_s) + and (self.follow_angle_deg == to_compare.follow_angle_deg) + ) except AttributeError: return False def __str__(self): - """ Config in string representation """ - struct_repr = ", ".join([ + """Config in string representation""" + struct_repr = ", ".join( + [ "follow_height_m: " + str(self.follow_height_m), "follow_distance_m: " + str(self.follow_distance_m), "responsiveness: " + str(self.responsiveness), "altitude_mode: " + str(self.altitude_mode), "max_tangential_vel_m_s: " + str(self.max_tangential_vel_m_s), - "follow_angle_deg: " + str(self.follow_angle_deg) - ]) + "follow_angle_deg: " + str(self.follow_angle_deg), + ] + ) return f"Config: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcConfig): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Config( - - rpcConfig.follow_height_m, - - - rpcConfig.follow_distance_m, - - - rpcConfig.responsiveness, - - - Config.FollowAltitudeMode.translate_from_rpc(rpcConfig.altitude_mode), - - - rpcConfig.max_tangential_vel_m_s, - - - rpcConfig.follow_angle_deg - ) + rpcConfig.follow_height_m, + rpcConfig.follow_distance_m, + rpcConfig.responsiveness, + Config.FollowAltitudeMode.translate_from_rpc(rpcConfig.altitude_mode), + rpcConfig.max_tangential_vel_m_s, + rpcConfig.follow_angle_deg, + ) def translate_to_rpc(self, rpcConfig): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcConfig.follow_height_m = self.follow_height_m - - - - - + rpcConfig.follow_distance_m = self.follow_distance_m - - - - - + rpcConfig.responsiveness = self.responsiveness - - - - - + rpcConfig.altitude_mode = self.altitude_mode.translate_to_rpc() - - - - - + rpcConfig.max_tangential_vel_m_s = self.max_tangential_vel_m_s - - - - - + rpcConfig.follow_angle_deg = self.follow_angle_deg - - - class TargetLocation: """ - Target location for the vehicle to follow - - Parameters - ---------- - latitude_deg : double - Target latitude in degrees + Target location for the vehicle to follow - longitude_deg : double - Target longitude in degrees + Parameters + ---------- + latitude_deg : double + Target latitude in degrees - absolute_altitude_m : float - Target altitude in meters above MSL + longitude_deg : double + Target longitude in degrees - velocity_x_m_s : float - Target velocity in X axis, in meters per second + absolute_altitude_m : float + Target altitude in meters above MSL - velocity_y_m_s : float - Target velocity in Y axis, in meters per second + velocity_x_m_s : float + Target velocity in X axis, in meters per second - velocity_z_m_s : float - Target velocity in Z axis, in meters per second + velocity_y_m_s : float + Target velocity in Y axis, in meters per second - """ + velocity_z_m_s : float + Target velocity in Z axis, in meters per second - + """ def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m, - velocity_x_m_s, - velocity_y_m_s, - velocity_z_m_s): - """ Initializes the TargetLocation object """ + self, + latitude_deg, + longitude_deg, + absolute_altitude_m, + velocity_x_m_s, + velocity_y_m_s, + velocity_z_m_s, + ): + """Initializes the TargetLocation object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m @@ -233,151 +195,114 @@ def __init__( self.velocity_z_m_s = velocity_z_m_s def __eq__(self, to_compare): - """ Checks if two TargetLocation are the same """ + """Checks if two TargetLocation are the same""" try: # Try to compare - this likely fails when it is compared to a non # TargetLocation object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.velocity_x_m_s == to_compare.velocity_x_m_s) and \ - (self.velocity_y_m_s == to_compare.velocity_y_m_s) and \ - (self.velocity_z_m_s == to_compare.velocity_z_m_s) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.velocity_x_m_s == to_compare.velocity_x_m_s) + and (self.velocity_y_m_s == to_compare.velocity_y_m_s) + and (self.velocity_z_m_s == to_compare.velocity_z_m_s) + ) except AttributeError: return False def __str__(self): - """ TargetLocation in string representation """ - struct_repr = ", ".join([ + """TargetLocation in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), "absolute_altitude_m: " + str(self.absolute_altitude_m), "velocity_x_m_s: " + str(self.velocity_x_m_s), "velocity_y_m_s: " + str(self.velocity_y_m_s), - "velocity_z_m_s: " + str(self.velocity_z_m_s) - ]) + "velocity_z_m_s: " + str(self.velocity_z_m_s), + ] + ) return f"TargetLocation: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTargetLocation): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TargetLocation( - - rpcTargetLocation.latitude_deg, - - - rpcTargetLocation.longitude_deg, - - - rpcTargetLocation.absolute_altitude_m, - - - rpcTargetLocation.velocity_x_m_s, - - - rpcTargetLocation.velocity_y_m_s, - - - rpcTargetLocation.velocity_z_m_s - ) + rpcTargetLocation.latitude_deg, + rpcTargetLocation.longitude_deg, + rpcTargetLocation.absolute_altitude_m, + rpcTargetLocation.velocity_x_m_s, + rpcTargetLocation.velocity_y_m_s, + rpcTargetLocation.velocity_z_m_s, + ) def translate_to_rpc(self, rpcTargetLocation): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTargetLocation.latitude_deg = self.latitude_deg - - - - - + rpcTargetLocation.longitude_deg = self.longitude_deg - - - - - + rpcTargetLocation.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcTargetLocation.velocity_x_m_s = self.velocity_x_m_s - - - - - + rpcTargetLocation.velocity_y_m_s = self.velocity_y_m_s - - - - - + rpcTargetLocation.velocity_z_m_s = self.velocity_z_m_s - - - class FollowMeResult: """ - - Parameters - ---------- - result : Result - Result enum value - result_str : std::string - Human-readable English string describing the result + Parameters + ---------- + result : Result + Result enum value + + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for followme operations + Possible results returned for followme operations - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command denied + COMMAND_DENIED + Command denied - TIMEOUT - Request timed out + TIMEOUT + Request timed out - NOT_ACTIVE - FollowMe is not active + NOT_ACTIVE + FollowMe is not active - SET_CONFIG_FAILED - Failed to set FollowMe configuration + SET_CONFIG_FAILED + Failed to set FollowMe configuration - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -410,7 +335,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == follow_me_pb2.FollowMeResult.RESULT_UNKNOWN: return FollowMeResult.Result.UNKNOWN if rpc_enum_value == follow_me_pb2.FollowMeResult.RESULT_SUCCESS: @@ -432,69 +357,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the FollowMeResult object """ + def __init__(self, result, result_str): + """Initializes the FollowMeResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two FollowMeResult are the same """ + """Checks if two FollowMeResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # FollowMeResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ FollowMeResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """FollowMeResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"FollowMeResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFollowMeResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FollowMeResult( - - FollowMeResult.Result.translate_from_rpc(rpcFollowMeResult.result), - - - rpcFollowMeResult.result_str - ) + FollowMeResult.Result.translate_from_rpc(rpcFollowMeResult.result), + rpcFollowMeResult.result_str, + ) def translate_to_rpc(self, rpcFollowMeResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFollowMeResult.result = self.result.translate_to_rpc() - - - - - - rpcFollowMeResult.result_str = self.result_str - - - + rpcFollowMeResult.result_str = self.result_str class FollowMeError(Exception): - """ Raised when a FollowMeResult is a fail code """ + """Raised when a FollowMeResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -507,179 +413,158 @@ def __str__(self): class FollowMe(AsyncBase): """ - Allow users to command the vehicle to follow a specific target. - The target is provided as a GPS coordinate and altitude. + Allow users to command the vehicle to follow a specific target. + The target is provided as a GPS coordinate and altitude. - Generated by dcsdkgen - MAVSDK FollowMe API + Generated by dcsdkgen - MAVSDK FollowMe API """ # Plugin name name = "FollowMe" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = follow_me_pb2_grpc.FollowMeServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return FollowMeResult.translate_from_rpc(response.follow_me_result) - async def get_config(self): """ - Get current configuration. + Get current configuration. + + Returns + ------- + config : Config + The current configuration - Returns - ------- - config : Config - The current configuration - """ request = follow_me_pb2.GetConfigRequest() response = await self._stub.GetConfig(request) - - return Config.translate_from_rpc(response.config) - async def set_config(self, config): """ - Apply configuration by sending it to the system. + Apply configuration by sending it to the system. - Parameters - ---------- - config : Config - The new configuration to be set + Parameters + ---------- + config : Config + The new configuration to be set - Raises - ------ - FollowMeError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FollowMeError + If the request fails. The error contains the reason for the failure. """ request = follow_me_pb2.SetConfigRequest() - + config.translate_to_rpc(request.config) - - + response = await self._stub.SetConfig(request) - result = self._extract_result(response) if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "set_config()", config) - async def is_active(self): """ - Check if FollowMe is active. + Check if FollowMe is active. + + Returns + ------- + is_active : bool + Whether follow me is active or not - Returns - ------- - is_active : bool - Whether follow me is active or not - """ request = follow_me_pb2.IsActiveRequest() response = await self._stub.IsActive(request) - - return response.is_active - async def set_target_location(self, location): """ - Set location of the moving target. + Set location of the moving target. - Parameters - ---------- - location : TargetLocation - The new TargetLocation to follow + Parameters + ---------- + location : TargetLocation + The new TargetLocation to follow - Raises - ------ - FollowMeError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FollowMeError + If the request fails. The error contains the reason for the failure. """ request = follow_me_pb2.SetTargetLocationRequest() - + location.translate_to_rpc(request.location) - - + response = await self._stub.SetTargetLocation(request) - result = self._extract_result(response) if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "set_target_location()", location) - async def get_last_location(self): """ - Get the last location of the target. + Get the last location of the target. + + Returns + ------- + location : TargetLocation + The last target location that was set - Returns - ------- - location : TargetLocation - The last target location that was set - """ request = follow_me_pb2.GetLastLocationRequest() response = await self._stub.GetLastLocation(request) - - return TargetLocation.translate_from_rpc(response.location) - async def start(self): """ - Start FollowMe mode. + Start FollowMe mode. - Raises - ------ - FollowMeError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FollowMeError + If the request fails. The error contains the reason for the failure. """ request = follow_me_pb2.StartRequest() response = await self._stub.Start(request) - result = self._extract_result(response) if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "start()") - async def stop(self): """ - Stop FollowMe mode. + Stop FollowMe mode. - Raises - ------ - FollowMeError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FollowMeError + If the request fails. The error contains the reason for the failure. """ request = follow_me_pb2.StopRequest() response = await self._stub.Stop(request) - result = self._extract_result(response) if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "stop()") - \ No newline at end of file diff --git a/mavsdk/follow_me_pb2.py b/mavsdk/follow_me_pb2.py index d124da65..bc108229 100644 --- a/mavsdk/follow_me_pb2.py +++ b/mavsdk/follow_me_pb2.py @@ -4,18 +4,15 @@ # source: follow_me/follow_me.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'follow_me/follow_me.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "follow_me/follow_me.proto" ) # @@protoc_insertion_point(imports) @@ -25,88 +22,134 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x19\x66ollow_me/follow_me.proto\x12\x14mavsdk.rpc.follow_me\x1a\x14mavsdk_options.proto\"\x8a\x03\n\x06\x43onfig\x12!\n\x0f\x66ollow_height_m\x18\x01 \x01(\x02\x42\x08\x82\xb5\x18\x04\x38.0f\x12#\n\x11\x66ollow_distance_m\x18\x02 \x01(\x02\x42\x08\x82\xb5\x18\x04\x38.0f\x12 \n\x0eresponsiveness\x18\x04 \x01(\x02\x42\x08\x82\xb5\x18\x04\x30.1f\x12\x46\n\raltitude_mode\x18\x05 \x01(\x0e\x32/.mavsdk.rpc.follow_me.Config.FollowAltitudeMode\x12(\n\x16max_tangential_vel_m_s\x18\x06 \x01(\x02\x42\x08\x82\xb5\x18\x04\x38.0f\x12$\n\x10\x66ollow_angle_deg\x18\x07 \x01(\x02\x42\n\x82\xb5\x18\x06\x31\x38\x30.0f\"~\n\x12\x46ollowAltitudeMode\x12!\n\x1d\x46OLLOW_ALTITUDE_MODE_CONSTANT\x10\x00\x12 \n\x1c\x46OLLOW_ALTITUDE_MODE_TERRAIN\x10\x01\x12#\n\x1f\x46OLLOW_ALTITUDE_MODE_TARGET_GPS\x10\x02\"\xd8\x01\n\x0eTargetLocation\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0evelocity_x_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0evelocity_y_m_s\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0evelocity_z_m_s\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\x12\n\x10GetConfigRequest\"A\n\x11GetConfigResponse\x12,\n\x06\x63onfig\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.follow_me.Config\"@\n\x10SetConfigRequest\x12,\n\x06\x63onfig\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.follow_me.Config\"S\n\x11SetConfigResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult\"\x11\n\x0fIsActiveRequest\"%\n\x10IsActiveResponse\x12\x11\n\tis_active\x18\x01 \x01(\x08\"R\n\x18SetTargetLocationRequest\x12\x36\n\x08location\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.TargetLocation\"[\n\x19SetTargetLocationResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult\"\x18\n\x16GetLastLocationRequest\"Q\n\x17GetLastLocationResponse\x12\x36\n\x08location\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.TargetLocation\"\x0e\n\x0cStartRequest\"O\n\rStartResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult\"\r\n\x0bStopRequest\"N\n\x0cStopResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult\"\xbc\x02\n\x0e\x46ollowMeResult\x12;\n\x06result\x18\x01 \x01(\x0e\x32+.mavsdk.rpc.follow_me.FollowMeResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xd8\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\x15\n\x11RESULT_NOT_ACTIVE\x10\x07\x12\x1c\n\x18RESULT_SET_CONFIG_FAILED\x10\x08\x32\xd9\x05\n\x0f\x46ollowMeService\x12\x62\n\tGetConfig\x12&.mavsdk.rpc.follow_me.GetConfigRequest\x1a\'.mavsdk.rpc.follow_me.GetConfigResponse\"\x04\x80\xb5\x18\x01\x12\x62\n\tSetConfig\x12&.mavsdk.rpc.follow_me.SetConfigRequest\x1a\'.mavsdk.rpc.follow_me.SetConfigResponse\"\x04\x80\xb5\x18\x01\x12_\n\x08IsActive\x12%.mavsdk.rpc.follow_me.IsActiveRequest\x1a&.mavsdk.rpc.follow_me.IsActiveResponse\"\x04\x80\xb5\x18\x01\x12z\n\x11SetTargetLocation\x12..mavsdk.rpc.follow_me.SetTargetLocationRequest\x1a/.mavsdk.rpc.follow_me.SetTargetLocationResponse\"\x04\x80\xb5\x18\x01\x12t\n\x0fGetLastLocation\x12,.mavsdk.rpc.follow_me.GetLastLocationRequest\x1a-.mavsdk.rpc.follow_me.GetLastLocationResponse\"\x04\x80\xb5\x18\x01\x12V\n\x05Start\x12\".mavsdk.rpc.follow_me.StartRequest\x1a#.mavsdk.rpc.follow_me.StartResponse\"\x04\x80\xb5\x18\x01\x12S\n\x04Stop\x12!.mavsdk.rpc.follow_me.StopRequest\x1a\".mavsdk.rpc.follow_me.StopResponse\"\x04\x80\xb5\x18\x01\x42$\n\x13io.mavsdk.follow_meB\rFollowMeProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x19\x66ollow_me/follow_me.proto\x12\x14mavsdk.rpc.follow_me\x1a\x14mavsdk_options.proto"\x8a\x03\n\x06\x43onfig\x12!\n\x0f\x66ollow_height_m\x18\x01 \x01(\x02\x42\x08\x82\xb5\x18\x04\x38.0f\x12#\n\x11\x66ollow_distance_m\x18\x02 \x01(\x02\x42\x08\x82\xb5\x18\x04\x38.0f\x12 \n\x0eresponsiveness\x18\x04 \x01(\x02\x42\x08\x82\xb5\x18\x04\x30.1f\x12\x46\n\raltitude_mode\x18\x05 \x01(\x0e\x32/.mavsdk.rpc.follow_me.Config.FollowAltitudeMode\x12(\n\x16max_tangential_vel_m_s\x18\x06 \x01(\x02\x42\x08\x82\xb5\x18\x04\x38.0f\x12$\n\x10\x66ollow_angle_deg\x18\x07 \x01(\x02\x42\n\x82\xb5\x18\x06\x31\x38\x30.0f"~\n\x12\x46ollowAltitudeMode\x12!\n\x1d\x46OLLOW_ALTITUDE_MODE_CONSTANT\x10\x00\x12 \n\x1c\x46OLLOW_ALTITUDE_MODE_TERRAIN\x10\x01\x12#\n\x1f\x46OLLOW_ALTITUDE_MODE_TARGET_GPS\x10\x02"\xd8\x01\n\x0eTargetLocation\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0evelocity_x_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0evelocity_y_m_s\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0evelocity_z_m_s\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\x12\n\x10GetConfigRequest"A\n\x11GetConfigResponse\x12,\n\x06\x63onfig\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.follow_me.Config"@\n\x10SetConfigRequest\x12,\n\x06\x63onfig\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.follow_me.Config"S\n\x11SetConfigResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult"\x11\n\x0fIsActiveRequest"%\n\x10IsActiveResponse\x12\x11\n\tis_active\x18\x01 \x01(\x08"R\n\x18SetTargetLocationRequest\x12\x36\n\x08location\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.TargetLocation"[\n\x19SetTargetLocationResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult"\x18\n\x16GetLastLocationRequest"Q\n\x17GetLastLocationResponse\x12\x36\n\x08location\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.TargetLocation"\x0e\n\x0cStartRequest"O\n\rStartResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult"\r\n\x0bStopRequest"N\n\x0cStopResponse\x12>\n\x10\x66ollow_me_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.follow_me.FollowMeResult"\xbc\x02\n\x0e\x46ollowMeResult\x12;\n\x06result\x18\x01 \x01(\x0e\x32+.mavsdk.rpc.follow_me.FollowMeResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xd8\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\x15\n\x11RESULT_NOT_ACTIVE\x10\x07\x12\x1c\n\x18RESULT_SET_CONFIG_FAILED\x10\x08\x32\xd9\x05\n\x0f\x46ollowMeService\x12\x62\n\tGetConfig\x12&.mavsdk.rpc.follow_me.GetConfigRequest\x1a\'.mavsdk.rpc.follow_me.GetConfigResponse"\x04\x80\xb5\x18\x01\x12\x62\n\tSetConfig\x12&.mavsdk.rpc.follow_me.SetConfigRequest\x1a\'.mavsdk.rpc.follow_me.SetConfigResponse"\x04\x80\xb5\x18\x01\x12_\n\x08IsActive\x12%.mavsdk.rpc.follow_me.IsActiveRequest\x1a&.mavsdk.rpc.follow_me.IsActiveResponse"\x04\x80\xb5\x18\x01\x12z\n\x11SetTargetLocation\x12..mavsdk.rpc.follow_me.SetTargetLocationRequest\x1a/.mavsdk.rpc.follow_me.SetTargetLocationResponse"\x04\x80\xb5\x18\x01\x12t\n\x0fGetLastLocation\x12,.mavsdk.rpc.follow_me.GetLastLocationRequest\x1a-.mavsdk.rpc.follow_me.GetLastLocationResponse"\x04\x80\xb5\x18\x01\x12V\n\x05Start\x12".mavsdk.rpc.follow_me.StartRequest\x1a#.mavsdk.rpc.follow_me.StartResponse"\x04\x80\xb5\x18\x01\x12S\n\x04Stop\x12!.mavsdk.rpc.follow_me.StopRequest\x1a".mavsdk.rpc.follow_me.StopResponse"\x04\x80\xb5\x18\x01\x42$\n\x13io.mavsdk.follow_meB\rFollowMeProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'follow_me.follow_me_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "follow_me.follow_me_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\023io.mavsdk.follow_meB\rFollowMeProto' - _globals['_CONFIG'].fields_by_name['follow_height_m']._loaded_options = None - _globals['_CONFIG'].fields_by_name['follow_height_m']._serialized_options = b'\202\265\030\0048.0f' - _globals['_CONFIG'].fields_by_name['follow_distance_m']._loaded_options = None - _globals['_CONFIG'].fields_by_name['follow_distance_m']._serialized_options = b'\202\265\030\0048.0f' - _globals['_CONFIG'].fields_by_name['responsiveness']._loaded_options = None - _globals['_CONFIG'].fields_by_name['responsiveness']._serialized_options = b'\202\265\030\0040.1f' - _globals['_CONFIG'].fields_by_name['max_tangential_vel_m_s']._loaded_options = None - _globals['_CONFIG'].fields_by_name['max_tangential_vel_m_s']._serialized_options = b'\202\265\030\0048.0f' - _globals['_CONFIG'].fields_by_name['follow_angle_deg']._loaded_options = None - _globals['_CONFIG'].fields_by_name['follow_angle_deg']._serialized_options = b'\202\265\030\006180.0f' - _globals['_TARGETLOCATION'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_TARGETLOCATION'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_TARGETLOCATION'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_TARGETLOCATION'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_TARGETLOCATION'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_TARGETLOCATION'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_TARGETLOCATION'].fields_by_name['velocity_x_m_s']._loaded_options = None - _globals['_TARGETLOCATION'].fields_by_name['velocity_x_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_TARGETLOCATION'].fields_by_name['velocity_y_m_s']._loaded_options = None - _globals['_TARGETLOCATION'].fields_by_name['velocity_y_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_TARGETLOCATION'].fields_by_name['velocity_z_m_s']._loaded_options = None - _globals['_TARGETLOCATION'].fields_by_name['velocity_z_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FOLLOWMESERVICE'].methods_by_name['GetConfig']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['GetConfig']._serialized_options = b'\200\265\030\001' - _globals['_FOLLOWMESERVICE'].methods_by_name['SetConfig']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['SetConfig']._serialized_options = b'\200\265\030\001' - _globals['_FOLLOWMESERVICE'].methods_by_name['IsActive']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['IsActive']._serialized_options = b'\200\265\030\001' - _globals['_FOLLOWMESERVICE'].methods_by_name['SetTargetLocation']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['SetTargetLocation']._serialized_options = b'\200\265\030\001' - _globals['_FOLLOWMESERVICE'].methods_by_name['GetLastLocation']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['GetLastLocation']._serialized_options = b'\200\265\030\001' - _globals['_FOLLOWMESERVICE'].methods_by_name['Start']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['Start']._serialized_options = b'\200\265\030\001' - _globals['_FOLLOWMESERVICE'].methods_by_name['Stop']._loaded_options = None - _globals['_FOLLOWMESERVICE'].methods_by_name['Stop']._serialized_options = b'\200\265\030\001' - _globals['_CONFIG']._serialized_start=74 - _globals['_CONFIG']._serialized_end=468 - _globals['_CONFIG_FOLLOWALTITUDEMODE']._serialized_start=342 - _globals['_CONFIG_FOLLOWALTITUDEMODE']._serialized_end=468 - _globals['_TARGETLOCATION']._serialized_start=471 - _globals['_TARGETLOCATION']._serialized_end=687 - _globals['_GETCONFIGREQUEST']._serialized_start=689 - _globals['_GETCONFIGREQUEST']._serialized_end=707 - _globals['_GETCONFIGRESPONSE']._serialized_start=709 - _globals['_GETCONFIGRESPONSE']._serialized_end=774 - _globals['_SETCONFIGREQUEST']._serialized_start=776 - _globals['_SETCONFIGREQUEST']._serialized_end=840 - _globals['_SETCONFIGRESPONSE']._serialized_start=842 - _globals['_SETCONFIGRESPONSE']._serialized_end=925 - _globals['_ISACTIVEREQUEST']._serialized_start=927 - _globals['_ISACTIVEREQUEST']._serialized_end=944 - _globals['_ISACTIVERESPONSE']._serialized_start=946 - _globals['_ISACTIVERESPONSE']._serialized_end=983 - _globals['_SETTARGETLOCATIONREQUEST']._serialized_start=985 - _globals['_SETTARGETLOCATIONREQUEST']._serialized_end=1067 - _globals['_SETTARGETLOCATIONRESPONSE']._serialized_start=1069 - _globals['_SETTARGETLOCATIONRESPONSE']._serialized_end=1160 - _globals['_GETLASTLOCATIONREQUEST']._serialized_start=1162 - _globals['_GETLASTLOCATIONREQUEST']._serialized_end=1186 - _globals['_GETLASTLOCATIONRESPONSE']._serialized_start=1188 - _globals['_GETLASTLOCATIONRESPONSE']._serialized_end=1269 - _globals['_STARTREQUEST']._serialized_start=1271 - _globals['_STARTREQUEST']._serialized_end=1285 - _globals['_STARTRESPONSE']._serialized_start=1287 - _globals['_STARTRESPONSE']._serialized_end=1366 - _globals['_STOPREQUEST']._serialized_start=1368 - _globals['_STOPREQUEST']._serialized_end=1381 - _globals['_STOPRESPONSE']._serialized_start=1383 - _globals['_STOPRESPONSE']._serialized_end=1461 - _globals['_FOLLOWMERESULT']._serialized_start=1464 - _globals['_FOLLOWMERESULT']._serialized_end=1780 - _globals['_FOLLOWMERESULT_RESULT']._serialized_start=1564 - _globals['_FOLLOWMERESULT_RESULT']._serialized_end=1780 - _globals['_FOLLOWMESERVICE']._serialized_start=1783 - _globals['_FOLLOWMESERVICE']._serialized_end=2512 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\023io.mavsdk.follow_meB\rFollowMeProto" + _globals["_CONFIG"].fields_by_name["follow_height_m"]._loaded_options = None + _globals["_CONFIG"].fields_by_name[ + "follow_height_m" + ]._serialized_options = b"\202\265\030\0048.0f" + _globals["_CONFIG"].fields_by_name["follow_distance_m"]._loaded_options = None + _globals["_CONFIG"].fields_by_name[ + "follow_distance_m" + ]._serialized_options = b"\202\265\030\0048.0f" + _globals["_CONFIG"].fields_by_name["responsiveness"]._loaded_options = None + _globals["_CONFIG"].fields_by_name[ + "responsiveness" + ]._serialized_options = b"\202\265\030\0040.1f" + _globals["_CONFIG"].fields_by_name["max_tangential_vel_m_s"]._loaded_options = None + _globals["_CONFIG"].fields_by_name[ + "max_tangential_vel_m_s" + ]._serialized_options = b"\202\265\030\0048.0f" + _globals["_CONFIG"].fields_by_name["follow_angle_deg"]._loaded_options = None + _globals["_CONFIG"].fields_by_name[ + "follow_angle_deg" + ]._serialized_options = b"\202\265\030\006180.0f" + _globals["_TARGETLOCATION"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_TARGETLOCATION"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_TARGETLOCATION"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_TARGETLOCATION"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_TARGETLOCATION"].fields_by_name[ + "absolute_altitude_m" + ]._loaded_options = None + _globals["_TARGETLOCATION"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_TARGETLOCATION"].fields_by_name["velocity_x_m_s"]._loaded_options = None + _globals["_TARGETLOCATION"].fields_by_name[ + "velocity_x_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_TARGETLOCATION"].fields_by_name["velocity_y_m_s"]._loaded_options = None + _globals["_TARGETLOCATION"].fields_by_name[ + "velocity_y_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_TARGETLOCATION"].fields_by_name["velocity_z_m_s"]._loaded_options = None + _globals["_TARGETLOCATION"].fields_by_name[ + "velocity_z_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FOLLOWMESERVICE"].methods_by_name["GetConfig"]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "GetConfig" + ]._serialized_options = b"\200\265\030\001" + _globals["_FOLLOWMESERVICE"].methods_by_name["SetConfig"]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "SetConfig" + ]._serialized_options = b"\200\265\030\001" + _globals["_FOLLOWMESERVICE"].methods_by_name["IsActive"]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "IsActive" + ]._serialized_options = b"\200\265\030\001" + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "SetTargetLocation" + ]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "SetTargetLocation" + ]._serialized_options = b"\200\265\030\001" + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "GetLastLocation" + ]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "GetLastLocation" + ]._serialized_options = b"\200\265\030\001" + _globals["_FOLLOWMESERVICE"].methods_by_name["Start"]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "Start" + ]._serialized_options = b"\200\265\030\001" + _globals["_FOLLOWMESERVICE"].methods_by_name["Stop"]._loaded_options = None + _globals["_FOLLOWMESERVICE"].methods_by_name[ + "Stop" + ]._serialized_options = b"\200\265\030\001" + _globals["_CONFIG"]._serialized_start = 74 + _globals["_CONFIG"]._serialized_end = 468 + _globals["_CONFIG_FOLLOWALTITUDEMODE"]._serialized_start = 342 + _globals["_CONFIG_FOLLOWALTITUDEMODE"]._serialized_end = 468 + _globals["_TARGETLOCATION"]._serialized_start = 471 + _globals["_TARGETLOCATION"]._serialized_end = 687 + _globals["_GETCONFIGREQUEST"]._serialized_start = 689 + _globals["_GETCONFIGREQUEST"]._serialized_end = 707 + _globals["_GETCONFIGRESPONSE"]._serialized_start = 709 + _globals["_GETCONFIGRESPONSE"]._serialized_end = 774 + _globals["_SETCONFIGREQUEST"]._serialized_start = 776 + _globals["_SETCONFIGREQUEST"]._serialized_end = 840 + _globals["_SETCONFIGRESPONSE"]._serialized_start = 842 + _globals["_SETCONFIGRESPONSE"]._serialized_end = 925 + _globals["_ISACTIVEREQUEST"]._serialized_start = 927 + _globals["_ISACTIVEREQUEST"]._serialized_end = 944 + _globals["_ISACTIVERESPONSE"]._serialized_start = 946 + _globals["_ISACTIVERESPONSE"]._serialized_end = 983 + _globals["_SETTARGETLOCATIONREQUEST"]._serialized_start = 985 + _globals["_SETTARGETLOCATIONREQUEST"]._serialized_end = 1067 + _globals["_SETTARGETLOCATIONRESPONSE"]._serialized_start = 1069 + _globals["_SETTARGETLOCATIONRESPONSE"]._serialized_end = 1160 + _globals["_GETLASTLOCATIONREQUEST"]._serialized_start = 1162 + _globals["_GETLASTLOCATIONREQUEST"]._serialized_end = 1186 + _globals["_GETLASTLOCATIONRESPONSE"]._serialized_start = 1188 + _globals["_GETLASTLOCATIONRESPONSE"]._serialized_end = 1269 + _globals["_STARTREQUEST"]._serialized_start = 1271 + _globals["_STARTREQUEST"]._serialized_end = 1285 + _globals["_STARTRESPONSE"]._serialized_start = 1287 + _globals["_STARTRESPONSE"]._serialized_end = 1366 + _globals["_STOPREQUEST"]._serialized_start = 1368 + _globals["_STOPREQUEST"]._serialized_end = 1381 + _globals["_STOPRESPONSE"]._serialized_start = 1383 + _globals["_STOPRESPONSE"]._serialized_end = 1461 + _globals["_FOLLOWMERESULT"]._serialized_start = 1464 + _globals["_FOLLOWMERESULT"]._serialized_end = 1780 + _globals["_FOLLOWMERESULT_RESULT"]._serialized_start = 1564 + _globals["_FOLLOWMERESULT_RESULT"]._serialized_end = 1780 + _globals["_FOLLOWMESERVICE"]._serialized_start = 1783 + _globals["_FOLLOWMESERVICE"]._serialized_end = 2512 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/follow_me_pb2_grpc.py b/mavsdk/follow_me_pb2_grpc.py index 919ee52c..f8ba9aab 100644 --- a/mavsdk/follow_me_pb2_grpc.py +++ b/mavsdk/follow_me_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import follow_me_pb2 as follow__me_dot_follow__me__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in follow_me/follow_me_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in follow_me/follow_me_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -38,40 +42,47 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.GetConfig = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/GetConfig', - request_serializer=follow__me_dot_follow__me__pb2.GetConfigRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.GetConfigResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/GetConfig", + request_serializer=follow__me_dot_follow__me__pb2.GetConfigRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.GetConfigResponse.FromString, + _registered_method=True, + ) self.SetConfig = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/SetConfig', - request_serializer=follow__me_dot_follow__me__pb2.SetConfigRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.SetConfigResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/SetConfig", + request_serializer=follow__me_dot_follow__me__pb2.SetConfigRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.SetConfigResponse.FromString, + _registered_method=True, + ) self.IsActive = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/IsActive', - request_serializer=follow__me_dot_follow__me__pb2.IsActiveRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.IsActiveResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/IsActive", + request_serializer=follow__me_dot_follow__me__pb2.IsActiveRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.IsActiveResponse.FromString, + _registered_method=True, + ) self.SetTargetLocation = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/SetTargetLocation', - request_serializer=follow__me_dot_follow__me__pb2.SetTargetLocationRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.SetTargetLocationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/SetTargetLocation", + request_serializer=follow__me_dot_follow__me__pb2.SetTargetLocationRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.SetTargetLocationResponse.FromString, + _registered_method=True, + ) self.GetLastLocation = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/GetLastLocation', - request_serializer=follow__me_dot_follow__me__pb2.GetLastLocationRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.GetLastLocationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/GetLastLocation", + request_serializer=follow__me_dot_follow__me__pb2.GetLastLocationRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.GetLastLocationResponse.FromString, + _registered_method=True, + ) self.Start = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/Start', - request_serializer=follow__me_dot_follow__me__pb2.StartRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.StartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/Start", + request_serializer=follow__me_dot_follow__me__pb2.StartRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.StartResponse.FromString, + _registered_method=True, + ) self.Stop = channel.unary_unary( - '/mavsdk.rpc.follow_me.FollowMeService/Stop', - request_serializer=follow__me_dot_follow__me__pb2.StopRequest.SerializeToString, - response_deserializer=follow__me_dot_follow__me__pb2.StopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.follow_me.FollowMeService/Stop", + request_serializer=follow__me_dot_follow__me__pb2.StopRequest.SerializeToString, + response_deserializer=follow__me_dot_follow__me__pb2.StopResponse.FromString, + _registered_method=True, + ) class FollowMeServiceServicer(object): @@ -81,100 +92,96 @@ class FollowMeServiceServicer(object): """ def GetConfig(self, request, context): - """Get current configuration. - """ + """Get current configuration.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetConfig(self, request, context): - """Apply configuration by sending it to the system. - """ + """Apply configuration by sending it to the system.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def IsActive(self, request, context): - """Check if FollowMe is active. - """ + """Check if FollowMe is active.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTargetLocation(self, request, context): - """Set location of the moving target. - """ + """Set location of the moving target.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetLastLocation(self, request, context): - """Get the last location of the target. - """ + """Get the last location of the target.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Start(self, request, context): - """Start FollowMe mode. - """ + """Start FollowMe mode.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Stop(self, request, context): - """Stop FollowMe mode. - """ + """Stop FollowMe mode.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_FollowMeServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'GetConfig': grpc.unary_unary_rpc_method_handler( - servicer.GetConfig, - request_deserializer=follow__me_dot_follow__me__pb2.GetConfigRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.GetConfigResponse.SerializeToString, - ), - 'SetConfig': grpc.unary_unary_rpc_method_handler( - servicer.SetConfig, - request_deserializer=follow__me_dot_follow__me__pb2.SetConfigRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.SetConfigResponse.SerializeToString, - ), - 'IsActive': grpc.unary_unary_rpc_method_handler( - servicer.IsActive, - request_deserializer=follow__me_dot_follow__me__pb2.IsActiveRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.IsActiveResponse.SerializeToString, - ), - 'SetTargetLocation': grpc.unary_unary_rpc_method_handler( - servicer.SetTargetLocation, - request_deserializer=follow__me_dot_follow__me__pb2.SetTargetLocationRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.SetTargetLocationResponse.SerializeToString, - ), - 'GetLastLocation': grpc.unary_unary_rpc_method_handler( - servicer.GetLastLocation, - request_deserializer=follow__me_dot_follow__me__pb2.GetLastLocationRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.GetLastLocationResponse.SerializeToString, - ), - 'Start': grpc.unary_unary_rpc_method_handler( - servicer.Start, - request_deserializer=follow__me_dot_follow__me__pb2.StartRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.StartResponse.SerializeToString, - ), - 'Stop': grpc.unary_unary_rpc_method_handler( - servicer.Stop, - request_deserializer=follow__me_dot_follow__me__pb2.StopRequest.FromString, - response_serializer=follow__me_dot_follow__me__pb2.StopResponse.SerializeToString, - ), + "GetConfig": grpc.unary_unary_rpc_method_handler( + servicer.GetConfig, + request_deserializer=follow__me_dot_follow__me__pb2.GetConfigRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.GetConfigResponse.SerializeToString, + ), + "SetConfig": grpc.unary_unary_rpc_method_handler( + servicer.SetConfig, + request_deserializer=follow__me_dot_follow__me__pb2.SetConfigRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.SetConfigResponse.SerializeToString, + ), + "IsActive": grpc.unary_unary_rpc_method_handler( + servicer.IsActive, + request_deserializer=follow__me_dot_follow__me__pb2.IsActiveRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.IsActiveResponse.SerializeToString, + ), + "SetTargetLocation": grpc.unary_unary_rpc_method_handler( + servicer.SetTargetLocation, + request_deserializer=follow__me_dot_follow__me__pb2.SetTargetLocationRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.SetTargetLocationResponse.SerializeToString, + ), + "GetLastLocation": grpc.unary_unary_rpc_method_handler( + servicer.GetLastLocation, + request_deserializer=follow__me_dot_follow__me__pb2.GetLastLocationRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.GetLastLocationResponse.SerializeToString, + ), + "Start": grpc.unary_unary_rpc_method_handler( + servicer.Start, + request_deserializer=follow__me_dot_follow__me__pb2.StartRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.StartResponse.SerializeToString, + ), + "Stop": grpc.unary_unary_rpc_method_handler( + servicer.Stop, + request_deserializer=follow__me_dot_follow__me__pb2.StopRequest.FromString, + response_serializer=follow__me_dot_follow__me__pb2.StopResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.follow_me.FollowMeService', rpc_method_handlers) + "mavsdk.rpc.follow_me.FollowMeService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.follow_me.FollowMeService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.follow_me.FollowMeService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class FollowMeService(object): """ Allow users to command the vehicle to follow a specific target. @@ -182,20 +189,22 @@ class FollowMeService(object): """ @staticmethod - def GetConfig(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetConfig( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/GetConfig', + "/mavsdk.rpc.follow_me.FollowMeService/GetConfig", follow__me_dot_follow__me__pb2.GetConfigRequest.SerializeToString, follow__me_dot_follow__me__pb2.GetConfigResponse.FromString, options, @@ -206,23 +215,26 @@ def GetConfig(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetConfig(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetConfig( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/SetConfig', + "/mavsdk.rpc.follow_me.FollowMeService/SetConfig", follow__me_dot_follow__me__pb2.SetConfigRequest.SerializeToString, follow__me_dot_follow__me__pb2.SetConfigResponse.FromString, options, @@ -233,23 +245,26 @@ def SetConfig(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def IsActive(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def IsActive( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/IsActive', + "/mavsdk.rpc.follow_me.FollowMeService/IsActive", follow__me_dot_follow__me__pb2.IsActiveRequest.SerializeToString, follow__me_dot_follow__me__pb2.IsActiveResponse.FromString, options, @@ -260,23 +275,26 @@ def IsActive(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetTargetLocation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetTargetLocation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/SetTargetLocation', + "/mavsdk.rpc.follow_me.FollowMeService/SetTargetLocation", follow__me_dot_follow__me__pb2.SetTargetLocationRequest.SerializeToString, follow__me_dot_follow__me__pb2.SetTargetLocationResponse.FromString, options, @@ -287,23 +305,26 @@ def SetTargetLocation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetLastLocation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetLastLocation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/GetLastLocation', + "/mavsdk.rpc.follow_me.FollowMeService/GetLastLocation", follow__me_dot_follow__me__pb2.GetLastLocationRequest.SerializeToString, follow__me_dot_follow__me__pb2.GetLastLocationResponse.FromString, options, @@ -314,23 +335,26 @@ def GetLastLocation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Start(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Start( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/Start', + "/mavsdk.rpc.follow_me.FollowMeService/Start", follow__me_dot_follow__me__pb2.StartRequest.SerializeToString, follow__me_dot_follow__me__pb2.StartResponse.FromString, options, @@ -341,23 +365,26 @@ def Start(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Stop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Stop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.follow_me.FollowMeService/Stop', + "/mavsdk.rpc.follow_me.FollowMeService/Stop", follow__me_dot_follow__me__pb2.StopRequest.SerializeToString, follow__me_dot_follow__me__pb2.StopResponse.FromString, options, @@ -368,4 +395,5 @@ def Stop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/ftp.py b/mavsdk/ftp.py index 336bb671..ea950b1a 100644 --- a/mavsdk/ftp.py +++ b/mavsdk/ftp.py @@ -8,218 +8,174 @@ class ListDirectoryData: """ - The output of a directory list + The output of a directory list - Parameters - ---------- - dirs : [std::string] - The found directories. + Parameters + ---------- + dirs : [std::string] + The found directories. - files : [std::string] - The found files. + files : [std::string] + The found files. - """ - - + """ - def __init__( - self, - dirs, - files): - """ Initializes the ListDirectoryData object """ + def __init__(self, dirs, files): + """Initializes the ListDirectoryData object""" self.dirs = dirs self.files = files def __eq__(self, to_compare): - """ Checks if two ListDirectoryData are the same """ + """Checks if two ListDirectoryData are the same""" try: # Try to compare - this likely fails when it is compared to a non # ListDirectoryData object - return \ - (self.dirs == to_compare.dirs) and \ - (self.files == to_compare.files) + return (self.dirs == to_compare.dirs) and (self.files == to_compare.files) except AttributeError: return False def __str__(self): - """ ListDirectoryData in string representation """ - struct_repr = ", ".join([ - "dirs: " + str(self.dirs), - "files: " + str(self.files) - ]) + """ListDirectoryData in string representation""" + struct_repr = ", ".join( + ["dirs: " + str(self.dirs), "files: " + str(self.files)] + ) return f"ListDirectoryData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcListDirectoryData): - """ Translates a gRPC struct to the SDK equivalent """ - return ListDirectoryData( - - rpcListDirectoryData.dirs, - - - rpcListDirectoryData.files - ) + """Translates a gRPC struct to the SDK equivalent""" + return ListDirectoryData(rpcListDirectoryData.dirs, rpcListDirectoryData.files) def translate_to_rpc(self, rpcListDirectoryData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - for elem in self.dirs: - rpcListDirectoryData.dirs.append(elem) - - - - - + rpcListDirectoryData.dirs.append(elem) + for elem in self.files: - rpcListDirectoryData.files.append(elem) - - - + rpcListDirectoryData.files.append(elem) class ProgressData: """ - Progress data type for file transfer. - - Parameters - ---------- - bytes_transferred : uint32_t - The number of bytes already transferred. + Progress data type for file transfer. - total_bytes : uint32_t - The total bytes to transfer. + Parameters + ---------- + bytes_transferred : uint32_t + The number of bytes already transferred. - """ + total_bytes : uint32_t + The total bytes to transfer. - + """ - def __init__( - self, - bytes_transferred, - total_bytes): - """ Initializes the ProgressData object """ + def __init__(self, bytes_transferred, total_bytes): + """Initializes the ProgressData object""" self.bytes_transferred = bytes_transferred self.total_bytes = total_bytes def __eq__(self, to_compare): - """ Checks if two ProgressData are the same """ + """Checks if two ProgressData are the same""" try: # Try to compare - this likely fails when it is compared to a non # ProgressData object - return \ - (self.bytes_transferred == to_compare.bytes_transferred) and \ - (self.total_bytes == to_compare.total_bytes) + return (self.bytes_transferred == to_compare.bytes_transferred) and ( + self.total_bytes == to_compare.total_bytes + ) except AttributeError: return False def __str__(self): - """ ProgressData in string representation """ - struct_repr = ", ".join([ + """ProgressData in string representation""" + struct_repr = ", ".join( + [ "bytes_transferred: " + str(self.bytes_transferred), - "total_bytes: " + str(self.total_bytes) - ]) + "total_bytes: " + str(self.total_bytes), + ] + ) return f"ProgressData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcProgressData): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ProgressData( - - rpcProgressData.bytes_transferred, - - - rpcProgressData.total_bytes - ) + rpcProgressData.bytes_transferred, rpcProgressData.total_bytes + ) def translate_to_rpc(self, rpcProgressData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcProgressData.bytes_transferred = self.bytes_transferred - - - - - + rpcProgressData.total_bytes = self.total_bytes - - - class FtpResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for FTP commands + Possible results returned for FTP commands - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Success + SUCCESS + Success - NEXT - Intermediate message showing progress + NEXT + Intermediate message showing progress - TIMEOUT - Timeout + TIMEOUT + Timeout - BUSY - Operation is already in progress + BUSY + Operation is already in progress - FILE_IO_ERROR - File IO operation error + FILE_IO_ERROR + File IO operation error - FILE_EXISTS - File exists already + FILE_EXISTS + File exists already - FILE_DOES_NOT_EXIST - File does not exist + FILE_DOES_NOT_EXIST + File does not exist - FILE_PROTECTED - File is write protected + FILE_PROTECTED + File is write protected - INVALID_PARAMETER - Invalid parameter + INVALID_PARAMETER + Invalid parameter - UNSUPPORTED - Unsupported command + UNSUPPORTED + Unsupported command - PROTOCOL_ERROR - General protocol error + PROTOCOL_ERROR + General protocol error - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 NEXT = 2 @@ -264,7 +220,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == ftp_pb2.FtpResult.RESULT_UNKNOWN: return FtpResult.Result.UNKNOWN if rpc_enum_value == ftp_pb2.FtpResult.RESULT_SUCCESS: @@ -294,69 +250,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the FtpResult object """ + def __init__(self, result, result_str): + """Initializes the FtpResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two FtpResult are the same """ + """Checks if two FtpResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # FtpResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ FtpResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """FtpResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"FtpResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFtpResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FtpResult( - - FtpResult.Result.translate_from_rpc(rpcFtpResult.result), - - - rpcFtpResult.result_str - ) + FtpResult.Result.translate_from_rpc(rpcFtpResult.result), + rpcFtpResult.result_str, + ) def translate_to_rpc(self, rpcFtpResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFtpResult.result = self.result.translate_to_rpc() - - - - - - rpcFtpResult.result_str = self.result_str - - - + rpcFtpResult.result_str = self.result_str class FtpError(Exception): - """ Raised when a FtpResult is a fail code """ + """Raised when a FtpResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -369,48 +306,46 @@ def __str__(self): class Ftp(AsyncBase): """ - Implements file transfer functionality using MAVLink FTP. + Implements file transfer functionality using MAVLink FTP. - Generated by dcsdkgen - MAVSDK Ftp API + Generated by dcsdkgen - MAVSDK Ftp API """ # Plugin name name = "Ftp" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = ftp_pb2_grpc.FtpServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return FtpResult.translate_from_rpc(response.ftp_result) - async def download(self, remote_file_path, local_dir, use_burst): """ - Downloads a file to local directory. + Downloads a file to local directory. - Parameters - ---------- - remote_file_path : std::string - The path of the remote file to download. + Parameters + ---------- + remote_file_path : std::string + The path of the remote file to download. - local_dir : std::string - The local directory to download to. + local_dir : std::string + The local directory to download to. - use_burst : bool - Use burst for faster downloading. + use_burst : bool + Use burst for faster downloading. - Yields - ------- - progress_data : ProgressData - The progress data if result is next + Yields + ------- + progress_data : ProgressData + The progress data if result is next - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.SubscribeDownloadRequest() @@ -421,47 +356,46 @@ async def download(self, remote_file_path, local_dir, use_burst): try: async for response in download_stream: - result = self._extract_result(response) success_codes = [FtpResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in FtpResult.Result]: + if "NEXT" in [return_code.name for return_code in FtpResult.Result]: success_codes.append(FtpResult.Result.NEXT) if result.result not in success_codes: - raise FtpError(result, "download()", remote_file_path, local_dir, use_burst) + raise FtpError( + result, "download()", remote_file_path, local_dir, use_burst + ) if result.result == FtpResult.Result.SUCCESS: - download_stream.cancel(); + download_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: download_stream.cancel() async def upload(self, local_file_path, remote_dir): """ - Uploads local file to remote directory. + Uploads local file to remote directory. - Parameters - ---------- - local_file_path : std::string - The local file path to upload. + Parameters + ---------- + local_file_path : std::string + The local file path to upload. - remote_dir : std::string - The remote directory to upload to. + remote_dir : std::string + The remote directory to upload to. - Yields - ------- - progress_data : ProgressData - The progress data if result is next + Yields + ------- + progress_data : ProgressData + The progress data if result is next - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.SubscribeUploadRequest() @@ -471,157 +405,144 @@ async def upload(self, local_file_path, remote_dir): try: async for response in upload_stream: - result = self._extract_result(response) success_codes = [FtpResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in FtpResult.Result]: + if "NEXT" in [return_code.name for return_code in FtpResult.Result]: success_codes.append(FtpResult.Result.NEXT) if result.result not in success_codes: raise FtpError(result, "upload()", local_file_path, remote_dir) if result.result == FtpResult.Result.SUCCESS: - upload_stream.cancel(); + upload_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: upload_stream.cancel() async def list_directory(self, remote_dir): """ - Lists items from a remote directory. - - Parameters - ---------- - remote_dir : std::string - The remote directory to list the contents for. - - Returns - ------- - data : ListDirectoryData - The found directories and files. - - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Lists items from a remote directory. + + Parameters + ---------- + remote_dir : std::string + The remote directory to list the contents for. + + Returns + ------- + data : ListDirectoryData + The found directories and files. + + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.ListDirectoryRequest() - - + request.remote_dir = remote_dir - + response = await self._stub.ListDirectory(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "list_directory()", remote_dir) - return ListDirectoryData.translate_from_rpc(response.data) - async def create_directory(self, remote_dir): """ - Creates a remote directory. + Creates a remote directory. - Parameters - ---------- - remote_dir : std::string - The remote directory to create. + Parameters + ---------- + remote_dir : std::string + The remote directory to create. - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.CreateDirectoryRequest() request.remote_dir = remote_dir response = await self._stub.CreateDirectory(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "create_directory()", remote_dir) - async def remove_directory(self, remote_dir): """ - Removes a remote directory. + Removes a remote directory. - Parameters - ---------- - remote_dir : std::string - The remote directory to remove. + Parameters + ---------- + remote_dir : std::string + The remote directory to remove. - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.RemoveDirectoryRequest() request.remote_dir = remote_dir response = await self._stub.RemoveDirectory(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "remove_directory()", remote_dir) - async def remove_file(self, remote_file_path): """ - Removes a remote file. + Removes a remote file. - Parameters - ---------- - remote_file_path : std::string - The path of the remote file to remove. + Parameters + ---------- + remote_file_path : std::string + The path of the remote file to remove. - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.RemoveFileRequest() request.remote_file_path = remote_file_path response = await self._stub.RemoveFile(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "remove_file()", remote_file_path) - async def rename(self, remote_from_path, remote_to_path): """ - Renames a remote file or remote directory. + Renames a remote file or remote directory. - Parameters - ---------- - remote_from_path : std::string - The remote source path. + Parameters + ---------- + remote_from_path : std::string + The remote source path. - remote_to_path : std::string - The remote destination path. + remote_to_path : std::string + The remote destination path. - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.RenameRequest() @@ -629,79 +550,71 @@ async def rename(self, remote_from_path, remote_to_path): request.remote_to_path = remote_to_path response = await self._stub.Rename(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "rename()", remote_from_path, remote_to_path) - async def are_files_identical(self, local_file_path, remote_file_path): """ - Compares a local file to a remote file using a CRC32 checksum. + Compares a local file to a remote file using a CRC32 checksum. - Parameters - ---------- - local_file_path : std::string - The path of the local file. + Parameters + ---------- + local_file_path : std::string + The path of the local file. - remote_file_path : std::string - The path of the remote file. + remote_file_path : std::string + The path of the remote file. - Returns - ------- - are_identical : bool - Whether the files are identical. + Returns + ------- + are_identical : bool + Whether the files are identical. - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.AreFilesIdenticalRequest() - - + request.local_file_path = local_file_path - - - + request.remote_file_path = remote_file_path - + response = await self._stub.AreFilesIdentical(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: - raise FtpError(result, "are_files_identical()", local_file_path, remote_file_path) - + raise FtpError( + result, "are_files_identical()", local_file_path, remote_file_path + ) return response.are_identical - async def set_target_compid(self, compid): """ - Set target component ID. By default it is the autopilot. + Set target component ID. By default it is the autopilot. - Parameters - ---------- - compid : uint32_t - The component ID to set. + Parameters + ---------- + compid : uint32_t + The component ID to set. - Raises - ------ - FtpError - If the request fails. The error contains the reason for the failure. + Raises + ------ + FtpError + If the request fails. The error contains the reason for the failure. """ request = ftp_pb2.SetTargetCompidRequest() request.compid = compid response = await self._stub.SetTargetCompid(request) - result = self._extract_result(response) if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "set_target_compid()", compid) - \ No newline at end of file diff --git a/mavsdk/ftp_pb2.py b/mavsdk/ftp_pb2.py index badb5c63..e0b55450 100644 --- a/mavsdk/ftp_pb2.py +++ b/mavsdk/ftp_pb2.py @@ -4,18 +4,15 @@ # source: ftp/ftp.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'ftp/ftp.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "ftp/ftp.proto" ) # @@protoc_insertion_point(imports) @@ -25,64 +22,72 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\rftp/ftp.proto\x12\x0emavsdk.rpc.ftp\x1a\x14mavsdk_options.proto\"Z\n\x18SubscribeDownloadRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\x12\x11\n\tlocal_dir\x18\x02 \x01(\t\x12\x11\n\tuse_burst\x18\x03 \x01(\x08\"v\n\x10\x44ownloadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData\"E\n\x16SubscribeUploadRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x12\n\nremote_dir\x18\x02 \x01(\t\"t\n\x0eUploadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData\"*\n\x14ListDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"0\n\x11ListDirectoryData\x12\x0c\n\x04\x64irs\x18\x01 \x03(\t\x12\r\n\x05\x66iles\x18\x02 \x03(\t\"w\n\x15ListDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12/\n\x04\x64\x61ta\x18\x02 \x01(\x0b\x32!.mavsdk.rpc.ftp.ListDirectoryData\",\n\x16\x43reateDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"H\n\x17\x43reateDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\",\n\x16RemoveDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"H\n\x17RemoveDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"-\n\x11RemoveFileRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\"C\n\x12RemoveFileResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"A\n\rRenameRequest\x12\x18\n\x10remote_from_path\x18\x01 \x01(\t\x12\x16\n\x0eremote_to_path\x18\x02 \x01(\t\"?\n\x0eRenameResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"M\n\x18\x41reFilesIdenticalRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x18\n\x10remote_file_path\x18\x02 \x01(\t\"a\n\x19\x41reFilesIdenticalResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x15\n\rare_identical\x18\x02 \x01(\x08\"(\n\x16SetTargetCompidRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\"H\n\x17SetTargetCompidResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\">\n\x0cProgressData\x12\x19\n\x11\x62ytes_transferred\x18\x01 \x01(\r\x12\x13\n\x0btotal_bytes\x18\x02 \x01(\r\"\x8e\x03\n\tFtpResult\x12\x30\n\x06result\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.ftp.FtpResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xba\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x18\n\x14RESULT_FILE_IO_ERROR\x10\x05\x12\x16\n\x12RESULT_FILE_EXISTS\x10\x06\x12\x1e\n\x1aRESULT_FILE_DOES_NOT_EXIST\x10\x07\x12\x19\n\x15RESULT_FILE_PROTECTED\x10\x08\x12\x1c\n\x18RESULT_INVALID_PARAMETER\x10\t\x12\x16\n\x12RESULT_UNSUPPORTED\x10\n\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x0b\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x0c\x32\x84\x07\n\nFtpService\x12k\n\x11SubscribeDownload\x12(.mavsdk.rpc.ftp.SubscribeDownloadRequest\x1a .mavsdk.rpc.ftp.DownloadResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\x65\n\x0fSubscribeUpload\x12&.mavsdk.rpc.ftp.SubscribeUploadRequest\x1a\x1e.mavsdk.rpc.ftp.UploadResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12^\n\rListDirectory\x12$.mavsdk.rpc.ftp.ListDirectoryRequest\x1a%.mavsdk.rpc.ftp.ListDirectoryResponse\"\x00\x12\x64\n\x0f\x43reateDirectory\x12&.mavsdk.rpc.ftp.CreateDirectoryRequest\x1a\'.mavsdk.rpc.ftp.CreateDirectoryResponse\"\x00\x12\x64\n\x0fRemoveDirectory\x12&.mavsdk.rpc.ftp.RemoveDirectoryRequest\x1a\'.mavsdk.rpc.ftp.RemoveDirectoryResponse\"\x00\x12U\n\nRemoveFile\x12!.mavsdk.rpc.ftp.RemoveFileRequest\x1a\".mavsdk.rpc.ftp.RemoveFileResponse\"\x00\x12I\n\x06Rename\x12\x1d.mavsdk.rpc.ftp.RenameRequest\x1a\x1e.mavsdk.rpc.ftp.RenameResponse\"\x00\x12j\n\x11\x41reFilesIdentical\x12(.mavsdk.rpc.ftp.AreFilesIdenticalRequest\x1a).mavsdk.rpc.ftp.AreFilesIdenticalResponse\"\x00\x12h\n\x0fSetTargetCompid\x12&.mavsdk.rpc.ftp.SetTargetCompidRequest\x1a\'.mavsdk.rpc.ftp.SetTargetCompidResponse\"\x04\x80\xb5\x18\x01\x42\x19\n\rio.mavsdk.ftpB\x08\x46tpProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\rftp/ftp.proto\x12\x0emavsdk.rpc.ftp\x1a\x14mavsdk_options.proto"Z\n\x18SubscribeDownloadRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\x12\x11\n\tlocal_dir\x18\x02 \x01(\t\x12\x11\n\tuse_burst\x18\x03 \x01(\x08"v\n\x10\x44ownloadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData"E\n\x16SubscribeUploadRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x12\n\nremote_dir\x18\x02 \x01(\t"t\n\x0eUploadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData"*\n\x14ListDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t"0\n\x11ListDirectoryData\x12\x0c\n\x04\x64irs\x18\x01 \x03(\t\x12\r\n\x05\x66iles\x18\x02 \x03(\t"w\n\x15ListDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12/\n\x04\x64\x61ta\x18\x02 \x01(\x0b\x32!.mavsdk.rpc.ftp.ListDirectoryData",\n\x16\x43reateDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t"H\n\x17\x43reateDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult",\n\x16RemoveDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t"H\n\x17RemoveDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult"-\n\x11RemoveFileRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t"C\n\x12RemoveFileResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult"A\n\rRenameRequest\x12\x18\n\x10remote_from_path\x18\x01 \x01(\t\x12\x16\n\x0eremote_to_path\x18\x02 \x01(\t"?\n\x0eRenameResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult"M\n\x18\x41reFilesIdenticalRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x18\n\x10remote_file_path\x18\x02 \x01(\t"a\n\x19\x41reFilesIdenticalResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x15\n\rare_identical\x18\x02 \x01(\x08"(\n\x16SetTargetCompidRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r"H\n\x17SetTargetCompidResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult">\n\x0cProgressData\x12\x19\n\x11\x62ytes_transferred\x18\x01 \x01(\r\x12\x13\n\x0btotal_bytes\x18\x02 \x01(\r"\x8e\x03\n\tFtpResult\x12\x30\n\x06result\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.ftp.FtpResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xba\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x18\n\x14RESULT_FILE_IO_ERROR\x10\x05\x12\x16\n\x12RESULT_FILE_EXISTS\x10\x06\x12\x1e\n\x1aRESULT_FILE_DOES_NOT_EXIST\x10\x07\x12\x19\n\x15RESULT_FILE_PROTECTED\x10\x08\x12\x1c\n\x18RESULT_INVALID_PARAMETER\x10\t\x12\x16\n\x12RESULT_UNSUPPORTED\x10\n\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x0b\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x0c\x32\x84\x07\n\nFtpService\x12k\n\x11SubscribeDownload\x12(.mavsdk.rpc.ftp.SubscribeDownloadRequest\x1a .mavsdk.rpc.ftp.DownloadResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\x65\n\x0fSubscribeUpload\x12&.mavsdk.rpc.ftp.SubscribeUploadRequest\x1a\x1e.mavsdk.rpc.ftp.UploadResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12^\n\rListDirectory\x12$.mavsdk.rpc.ftp.ListDirectoryRequest\x1a%.mavsdk.rpc.ftp.ListDirectoryResponse"\x00\x12\x64\n\x0f\x43reateDirectory\x12&.mavsdk.rpc.ftp.CreateDirectoryRequest\x1a\'.mavsdk.rpc.ftp.CreateDirectoryResponse"\x00\x12\x64\n\x0fRemoveDirectory\x12&.mavsdk.rpc.ftp.RemoveDirectoryRequest\x1a\'.mavsdk.rpc.ftp.RemoveDirectoryResponse"\x00\x12U\n\nRemoveFile\x12!.mavsdk.rpc.ftp.RemoveFileRequest\x1a".mavsdk.rpc.ftp.RemoveFileResponse"\x00\x12I\n\x06Rename\x12\x1d.mavsdk.rpc.ftp.RenameRequest\x1a\x1e.mavsdk.rpc.ftp.RenameResponse"\x00\x12j\n\x11\x41reFilesIdentical\x12(.mavsdk.rpc.ftp.AreFilesIdenticalRequest\x1a).mavsdk.rpc.ftp.AreFilesIdenticalResponse"\x00\x12h\n\x0fSetTargetCompid\x12&.mavsdk.rpc.ftp.SetTargetCompidRequest\x1a\'.mavsdk.rpc.ftp.SetTargetCompidResponse"\x04\x80\xb5\x18\x01\x42\x19\n\rio.mavsdk.ftpB\x08\x46tpProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'ftp.ftp_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "ftp.ftp_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\rio.mavsdk.ftpB\010FtpProto' - _globals['_FTPSERVICE'].methods_by_name['SubscribeDownload']._loaded_options = None - _globals['_FTPSERVICE'].methods_by_name['SubscribeDownload']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_FTPSERVICE'].methods_by_name['SubscribeUpload']._loaded_options = None - _globals['_FTPSERVICE'].methods_by_name['SubscribeUpload']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_FTPSERVICE'].methods_by_name['SetTargetCompid']._loaded_options = None - _globals['_FTPSERVICE'].methods_by_name['SetTargetCompid']._serialized_options = b'\200\265\030\001' - _globals['_SUBSCRIBEDOWNLOADREQUEST']._serialized_start=55 - _globals['_SUBSCRIBEDOWNLOADREQUEST']._serialized_end=145 - _globals['_DOWNLOADRESPONSE']._serialized_start=147 - _globals['_DOWNLOADRESPONSE']._serialized_end=265 - _globals['_SUBSCRIBEUPLOADREQUEST']._serialized_start=267 - _globals['_SUBSCRIBEUPLOADREQUEST']._serialized_end=336 - _globals['_UPLOADRESPONSE']._serialized_start=338 - _globals['_UPLOADRESPONSE']._serialized_end=454 - _globals['_LISTDIRECTORYREQUEST']._serialized_start=456 - _globals['_LISTDIRECTORYREQUEST']._serialized_end=498 - _globals['_LISTDIRECTORYDATA']._serialized_start=500 - _globals['_LISTDIRECTORYDATA']._serialized_end=548 - _globals['_LISTDIRECTORYRESPONSE']._serialized_start=550 - _globals['_LISTDIRECTORYRESPONSE']._serialized_end=669 - _globals['_CREATEDIRECTORYREQUEST']._serialized_start=671 - _globals['_CREATEDIRECTORYREQUEST']._serialized_end=715 - _globals['_CREATEDIRECTORYRESPONSE']._serialized_start=717 - _globals['_CREATEDIRECTORYRESPONSE']._serialized_end=789 - _globals['_REMOVEDIRECTORYREQUEST']._serialized_start=791 - _globals['_REMOVEDIRECTORYREQUEST']._serialized_end=835 - _globals['_REMOVEDIRECTORYRESPONSE']._serialized_start=837 - _globals['_REMOVEDIRECTORYRESPONSE']._serialized_end=909 - _globals['_REMOVEFILEREQUEST']._serialized_start=911 - _globals['_REMOVEFILEREQUEST']._serialized_end=956 - _globals['_REMOVEFILERESPONSE']._serialized_start=958 - _globals['_REMOVEFILERESPONSE']._serialized_end=1025 - _globals['_RENAMEREQUEST']._serialized_start=1027 - _globals['_RENAMEREQUEST']._serialized_end=1092 - _globals['_RENAMERESPONSE']._serialized_start=1094 - _globals['_RENAMERESPONSE']._serialized_end=1157 - _globals['_AREFILESIDENTICALREQUEST']._serialized_start=1159 - _globals['_AREFILESIDENTICALREQUEST']._serialized_end=1236 - _globals['_AREFILESIDENTICALRESPONSE']._serialized_start=1238 - _globals['_AREFILESIDENTICALRESPONSE']._serialized_end=1335 - _globals['_SETTARGETCOMPIDREQUEST']._serialized_start=1337 - _globals['_SETTARGETCOMPIDREQUEST']._serialized_end=1377 - _globals['_SETTARGETCOMPIDRESPONSE']._serialized_start=1379 - _globals['_SETTARGETCOMPIDRESPONSE']._serialized_end=1451 - _globals['_PROGRESSDATA']._serialized_start=1453 - _globals['_PROGRESSDATA']._serialized_end=1515 - _globals['_FTPRESULT']._serialized_start=1518 - _globals['_FTPRESULT']._serialized_end=1916 - _globals['_FTPRESULT_RESULT']._serialized_start=1602 - _globals['_FTPRESULT_RESULT']._serialized_end=1916 - _globals['_FTPSERVICE']._serialized_start=1919 - _globals['_FTPSERVICE']._serialized_end=2819 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\rio.mavsdk.ftpB\010FtpProto" + _globals["_FTPSERVICE"].methods_by_name["SubscribeDownload"]._loaded_options = None + _globals["_FTPSERVICE"].methods_by_name[ + "SubscribeDownload" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_FTPSERVICE"].methods_by_name["SubscribeUpload"]._loaded_options = None + _globals["_FTPSERVICE"].methods_by_name[ + "SubscribeUpload" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_FTPSERVICE"].methods_by_name["SetTargetCompid"]._loaded_options = None + _globals["_FTPSERVICE"].methods_by_name[ + "SetTargetCompid" + ]._serialized_options = b"\200\265\030\001" + _globals["_SUBSCRIBEDOWNLOADREQUEST"]._serialized_start = 55 + _globals["_SUBSCRIBEDOWNLOADREQUEST"]._serialized_end = 145 + _globals["_DOWNLOADRESPONSE"]._serialized_start = 147 + _globals["_DOWNLOADRESPONSE"]._serialized_end = 265 + _globals["_SUBSCRIBEUPLOADREQUEST"]._serialized_start = 267 + _globals["_SUBSCRIBEUPLOADREQUEST"]._serialized_end = 336 + _globals["_UPLOADRESPONSE"]._serialized_start = 338 + _globals["_UPLOADRESPONSE"]._serialized_end = 454 + _globals["_LISTDIRECTORYREQUEST"]._serialized_start = 456 + _globals["_LISTDIRECTORYREQUEST"]._serialized_end = 498 + _globals["_LISTDIRECTORYDATA"]._serialized_start = 500 + _globals["_LISTDIRECTORYDATA"]._serialized_end = 548 + _globals["_LISTDIRECTORYRESPONSE"]._serialized_start = 550 + _globals["_LISTDIRECTORYRESPONSE"]._serialized_end = 669 + _globals["_CREATEDIRECTORYREQUEST"]._serialized_start = 671 + _globals["_CREATEDIRECTORYREQUEST"]._serialized_end = 715 + _globals["_CREATEDIRECTORYRESPONSE"]._serialized_start = 717 + _globals["_CREATEDIRECTORYRESPONSE"]._serialized_end = 789 + _globals["_REMOVEDIRECTORYREQUEST"]._serialized_start = 791 + _globals["_REMOVEDIRECTORYREQUEST"]._serialized_end = 835 + _globals["_REMOVEDIRECTORYRESPONSE"]._serialized_start = 837 + _globals["_REMOVEDIRECTORYRESPONSE"]._serialized_end = 909 + _globals["_REMOVEFILEREQUEST"]._serialized_start = 911 + _globals["_REMOVEFILEREQUEST"]._serialized_end = 956 + _globals["_REMOVEFILERESPONSE"]._serialized_start = 958 + _globals["_REMOVEFILERESPONSE"]._serialized_end = 1025 + _globals["_RENAMEREQUEST"]._serialized_start = 1027 + _globals["_RENAMEREQUEST"]._serialized_end = 1092 + _globals["_RENAMERESPONSE"]._serialized_start = 1094 + _globals["_RENAMERESPONSE"]._serialized_end = 1157 + _globals["_AREFILESIDENTICALREQUEST"]._serialized_start = 1159 + _globals["_AREFILESIDENTICALREQUEST"]._serialized_end = 1236 + _globals["_AREFILESIDENTICALRESPONSE"]._serialized_start = 1238 + _globals["_AREFILESIDENTICALRESPONSE"]._serialized_end = 1335 + _globals["_SETTARGETCOMPIDREQUEST"]._serialized_start = 1337 + _globals["_SETTARGETCOMPIDREQUEST"]._serialized_end = 1377 + _globals["_SETTARGETCOMPIDRESPONSE"]._serialized_start = 1379 + _globals["_SETTARGETCOMPIDRESPONSE"]._serialized_end = 1451 + _globals["_PROGRESSDATA"]._serialized_start = 1453 + _globals["_PROGRESSDATA"]._serialized_end = 1515 + _globals["_FTPRESULT"]._serialized_start = 1518 + _globals["_FTPRESULT"]._serialized_end = 1916 + _globals["_FTPRESULT_RESULT"]._serialized_start = 1602 + _globals["_FTPRESULT_RESULT"]._serialized_end = 1916 + _globals["_FTPSERVICE"]._serialized_start = 1919 + _globals["_FTPSERVICE"]._serialized_end = 2819 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/ftp_pb2_grpc.py b/mavsdk/ftp_pb2_grpc.py index b7b94c8c..0ee00263 100644 --- a/mavsdk/ftp_pb2_grpc.py +++ b/mavsdk/ftp_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import ftp_pb2 as ftp_dot_ftp__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in ftp/ftp_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in ftp/ftp_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -37,50 +41,59 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeDownload = channel.unary_stream( - '/mavsdk.rpc.ftp.FtpService/SubscribeDownload', - request_serializer=ftp_dot_ftp__pb2.SubscribeDownloadRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.DownloadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/SubscribeDownload", + request_serializer=ftp_dot_ftp__pb2.SubscribeDownloadRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.DownloadResponse.FromString, + _registered_method=True, + ) self.SubscribeUpload = channel.unary_stream( - '/mavsdk.rpc.ftp.FtpService/SubscribeUpload', - request_serializer=ftp_dot_ftp__pb2.SubscribeUploadRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.UploadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/SubscribeUpload", + request_serializer=ftp_dot_ftp__pb2.SubscribeUploadRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.UploadResponse.FromString, + _registered_method=True, + ) self.ListDirectory = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/ListDirectory', - request_serializer=ftp_dot_ftp__pb2.ListDirectoryRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.ListDirectoryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/ListDirectory", + request_serializer=ftp_dot_ftp__pb2.ListDirectoryRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.ListDirectoryResponse.FromString, + _registered_method=True, + ) self.CreateDirectory = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/CreateDirectory', - request_serializer=ftp_dot_ftp__pb2.CreateDirectoryRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.CreateDirectoryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/CreateDirectory", + request_serializer=ftp_dot_ftp__pb2.CreateDirectoryRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.CreateDirectoryResponse.FromString, + _registered_method=True, + ) self.RemoveDirectory = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/RemoveDirectory', - request_serializer=ftp_dot_ftp__pb2.RemoveDirectoryRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.RemoveDirectoryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/RemoveDirectory", + request_serializer=ftp_dot_ftp__pb2.RemoveDirectoryRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.RemoveDirectoryResponse.FromString, + _registered_method=True, + ) self.RemoveFile = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/RemoveFile', - request_serializer=ftp_dot_ftp__pb2.RemoveFileRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.RemoveFileResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/RemoveFile", + request_serializer=ftp_dot_ftp__pb2.RemoveFileRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.RemoveFileResponse.FromString, + _registered_method=True, + ) self.Rename = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/Rename', - request_serializer=ftp_dot_ftp__pb2.RenameRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.RenameResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/Rename", + request_serializer=ftp_dot_ftp__pb2.RenameRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.RenameResponse.FromString, + _registered_method=True, + ) self.AreFilesIdentical = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/AreFilesIdentical', - request_serializer=ftp_dot_ftp__pb2.AreFilesIdenticalRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.AreFilesIdenticalResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/AreFilesIdentical", + request_serializer=ftp_dot_ftp__pb2.AreFilesIdenticalRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.AreFilesIdenticalResponse.FromString, + _registered_method=True, + ) self.SetTargetCompid = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/SetTargetCompid', - request_serializer=ftp_dot_ftp__pb2.SetTargetCompidRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.SetTargetCompidResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp.FtpService/SetTargetCompid", + request_serializer=ftp_dot_ftp__pb2.SetTargetCompidRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.SetTargetCompidResponse.FromString, + _registered_method=True, + ) class FtpServiceServicer(object): @@ -93,149 +106,154 @@ def SubscribeDownload(self, request, context): Downloads a file to local directory. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeUpload(self, request, context): """ Uploads local file to remote directory. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ListDirectory(self, request, context): """ Lists items from a remote directory. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def CreateDirectory(self, request, context): """ Creates a remote directory. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RemoveDirectory(self, request, context): """ Removes a remote directory. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RemoveFile(self, request, context): """ Removes a remote file. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Rename(self, request, context): """ Renames a remote file or remote directory. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def AreFilesIdentical(self, request, context): """ Compares a local file to a remote file using a CRC32 checksum. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTargetCompid(self, request, context): """ Set target component ID. By default it is the autopilot. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_FtpServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeDownload': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeDownload, - request_deserializer=ftp_dot_ftp__pb2.SubscribeDownloadRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.DownloadResponse.SerializeToString, - ), - 'SubscribeUpload': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeUpload, - request_deserializer=ftp_dot_ftp__pb2.SubscribeUploadRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.UploadResponse.SerializeToString, - ), - 'ListDirectory': grpc.unary_unary_rpc_method_handler( - servicer.ListDirectory, - request_deserializer=ftp_dot_ftp__pb2.ListDirectoryRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.ListDirectoryResponse.SerializeToString, - ), - 'CreateDirectory': grpc.unary_unary_rpc_method_handler( - servicer.CreateDirectory, - request_deserializer=ftp_dot_ftp__pb2.CreateDirectoryRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.CreateDirectoryResponse.SerializeToString, - ), - 'RemoveDirectory': grpc.unary_unary_rpc_method_handler( - servicer.RemoveDirectory, - request_deserializer=ftp_dot_ftp__pb2.RemoveDirectoryRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.RemoveDirectoryResponse.SerializeToString, - ), - 'RemoveFile': grpc.unary_unary_rpc_method_handler( - servicer.RemoveFile, - request_deserializer=ftp_dot_ftp__pb2.RemoveFileRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.RemoveFileResponse.SerializeToString, - ), - 'Rename': grpc.unary_unary_rpc_method_handler( - servicer.Rename, - request_deserializer=ftp_dot_ftp__pb2.RenameRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.RenameResponse.SerializeToString, - ), - 'AreFilesIdentical': grpc.unary_unary_rpc_method_handler( - servicer.AreFilesIdentical, - request_deserializer=ftp_dot_ftp__pb2.AreFilesIdenticalRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.AreFilesIdenticalResponse.SerializeToString, - ), - 'SetTargetCompid': grpc.unary_unary_rpc_method_handler( - servicer.SetTargetCompid, - request_deserializer=ftp_dot_ftp__pb2.SetTargetCompidRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.SetTargetCompidResponse.SerializeToString, - ), + "SubscribeDownload": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeDownload, + request_deserializer=ftp_dot_ftp__pb2.SubscribeDownloadRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.DownloadResponse.SerializeToString, + ), + "SubscribeUpload": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeUpload, + request_deserializer=ftp_dot_ftp__pb2.SubscribeUploadRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.UploadResponse.SerializeToString, + ), + "ListDirectory": grpc.unary_unary_rpc_method_handler( + servicer.ListDirectory, + request_deserializer=ftp_dot_ftp__pb2.ListDirectoryRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.ListDirectoryResponse.SerializeToString, + ), + "CreateDirectory": grpc.unary_unary_rpc_method_handler( + servicer.CreateDirectory, + request_deserializer=ftp_dot_ftp__pb2.CreateDirectoryRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.CreateDirectoryResponse.SerializeToString, + ), + "RemoveDirectory": grpc.unary_unary_rpc_method_handler( + servicer.RemoveDirectory, + request_deserializer=ftp_dot_ftp__pb2.RemoveDirectoryRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.RemoveDirectoryResponse.SerializeToString, + ), + "RemoveFile": grpc.unary_unary_rpc_method_handler( + servicer.RemoveFile, + request_deserializer=ftp_dot_ftp__pb2.RemoveFileRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.RemoveFileResponse.SerializeToString, + ), + "Rename": grpc.unary_unary_rpc_method_handler( + servicer.Rename, + request_deserializer=ftp_dot_ftp__pb2.RenameRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.RenameResponse.SerializeToString, + ), + "AreFilesIdentical": grpc.unary_unary_rpc_method_handler( + servicer.AreFilesIdentical, + request_deserializer=ftp_dot_ftp__pb2.AreFilesIdenticalRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.AreFilesIdenticalResponse.SerializeToString, + ), + "SetTargetCompid": grpc.unary_unary_rpc_method_handler( + servicer.SetTargetCompid, + request_deserializer=ftp_dot_ftp__pb2.SetTargetCompidRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.SetTargetCompidResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.ftp.FtpService', rpc_method_handlers) + "mavsdk.rpc.ftp.FtpService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.ftp.FtpService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.ftp.FtpService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class FtpService(object): """ Implements file transfer functionality using MAVLink FTP. """ @staticmethod - def SubscribeDownload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeDownload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.ftp.FtpService/SubscribeDownload', + "/mavsdk.rpc.ftp.FtpService/SubscribeDownload", ftp_dot_ftp__pb2.SubscribeDownloadRequest.SerializeToString, ftp_dot_ftp__pb2.DownloadResponse.FromString, options, @@ -246,23 +264,26 @@ def SubscribeDownload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeUpload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeUpload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.ftp.FtpService/SubscribeUpload', + "/mavsdk.rpc.ftp.FtpService/SubscribeUpload", ftp_dot_ftp__pb2.SubscribeUploadRequest.SerializeToString, ftp_dot_ftp__pb2.UploadResponse.FromString, options, @@ -273,23 +294,26 @@ def SubscribeUpload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ListDirectory(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ListDirectory( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/ListDirectory', + "/mavsdk.rpc.ftp.FtpService/ListDirectory", ftp_dot_ftp__pb2.ListDirectoryRequest.SerializeToString, ftp_dot_ftp__pb2.ListDirectoryResponse.FromString, options, @@ -300,23 +324,26 @@ def ListDirectory(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def CreateDirectory(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def CreateDirectory( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/CreateDirectory', + "/mavsdk.rpc.ftp.FtpService/CreateDirectory", ftp_dot_ftp__pb2.CreateDirectoryRequest.SerializeToString, ftp_dot_ftp__pb2.CreateDirectoryResponse.FromString, options, @@ -327,23 +354,26 @@ def CreateDirectory(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RemoveDirectory(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RemoveDirectory( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/RemoveDirectory', + "/mavsdk.rpc.ftp.FtpService/RemoveDirectory", ftp_dot_ftp__pb2.RemoveDirectoryRequest.SerializeToString, ftp_dot_ftp__pb2.RemoveDirectoryResponse.FromString, options, @@ -354,23 +384,26 @@ def RemoveDirectory(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RemoveFile(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RemoveFile( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/RemoveFile', + "/mavsdk.rpc.ftp.FtpService/RemoveFile", ftp_dot_ftp__pb2.RemoveFileRequest.SerializeToString, ftp_dot_ftp__pb2.RemoveFileResponse.FromString, options, @@ -381,23 +414,26 @@ def RemoveFile(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Rename(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Rename( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/Rename', + "/mavsdk.rpc.ftp.FtpService/Rename", ftp_dot_ftp__pb2.RenameRequest.SerializeToString, ftp_dot_ftp__pb2.RenameResponse.FromString, options, @@ -408,23 +444,26 @@ def Rename(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def AreFilesIdentical(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def AreFilesIdentical( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/AreFilesIdentical', + "/mavsdk.rpc.ftp.FtpService/AreFilesIdentical", ftp_dot_ftp__pb2.AreFilesIdenticalRequest.SerializeToString, ftp_dot_ftp__pb2.AreFilesIdenticalResponse.FromString, options, @@ -435,23 +474,26 @@ def AreFilesIdentical(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetTargetCompid(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetTargetCompid( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp.FtpService/SetTargetCompid', + "/mavsdk.rpc.ftp.FtpService/SetTargetCompid", ftp_dot_ftp__pb2.SetTargetCompidRequest.SerializeToString, ftp_dot_ftp__pb2.SetTargetCompidResponse.FromString, options, @@ -462,4 +504,5 @@ def SetTargetCompid(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/ftp_server.py b/mavsdk/ftp_server.py index 32dfd82d..09b7efe3 100644 --- a/mavsdk/ftp_server.py +++ b/mavsdk/ftp_server.py @@ -8,41 +8,38 @@ class FtpServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for FTP server requests. + Possible results returned for FTP server requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - DOES_NOT_EXIST - Directory does not exist + DOES_NOT_EXIST + Directory does not exist - BUSY - Operations in progress + BUSY + Operations in progress - """ + """ - UNKNOWN = 0 SUCCESS = 1 DOES_NOT_EXIST = 2 @@ -60,7 +57,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == ftp_server_pb2.FtpServerResult.RESULT_UNKNOWN: return FtpServerResult.Result.UNKNOWN if rpc_enum_value == ftp_server_pb2.FtpServerResult.RESULT_SUCCESS: @@ -72,69 +69,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the FtpServerResult object """ + def __init__(self, result, result_str): + """Initializes the FtpServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two FtpServerResult are the same """ + """Checks if two FtpServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # FtpServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ FtpServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """FtpServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"FtpServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFtpServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FtpServerResult( - - FtpServerResult.Result.translate_from_rpc(rpcFtpServerResult.result), - - - rpcFtpServerResult.result_str - ) + FtpServerResult.Result.translate_from_rpc(rpcFtpServerResult.result), + rpcFtpServerResult.result_str, + ) def translate_to_rpc(self, rpcFtpServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFtpServerResult.result = self.result.translate_to_rpc() - - - - - - rpcFtpServerResult.result_str = self.result_str - - - + rpcFtpServerResult.result_str = self.result_str class FtpServerError(Exception): - """ Raised when a FtpServerResult is a fail code """ + """Raised when a FtpServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -147,51 +125,47 @@ def __str__(self): class FtpServer(AsyncBase): """ - Provide files or directories to transfer. + Provide files or directories to transfer. - Generated by dcsdkgen - MAVSDK FtpServer API + Generated by dcsdkgen - MAVSDK FtpServer API """ # Plugin name name = "FtpServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = ftp_server_pb2_grpc.FtpServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return FtpServerResult.translate_from_rpc(response.ftp_server_result) - async def set_root_dir(self, path): """ - Set root directory. - - This is the directory that can then be accessed by a client. - The directory needs to exist when this is called. - The permissions are the same as the file permission for the user running the server. - The root directory can't be changed while an FTP process is in progress. - - Parameters - ---------- - path : std::string - Absolute path of folder - - Raises - ------ - FtpServerError - If the request fails. The error contains the reason for the failure. + Set root directory. + + This is the directory that can then be accessed by a client. + The directory needs to exist when this is called. + The permissions are the same as the file permission for the user running the server. + The root directory can't be changed while an FTP process is in progress. + + Parameters + ---------- + path : std::string + Absolute path of folder + + Raises + ------ + FtpServerError + If the request fails. The error contains the reason for the failure. """ request = ftp_server_pb2.SetRootDirRequest() request.path = path response = await self._stub.SetRootDir(request) - result = self._extract_result(response) if result.result != FtpServerResult.Result.SUCCESS: raise FtpServerError(result, "set_root_dir()", path) - \ No newline at end of file diff --git a/mavsdk/ftp_server_pb2.py b/mavsdk/ftp_server_pb2.py index 569d51f8..d68a1c95 100644 --- a/mavsdk/ftp_server_pb2.py +++ b/mavsdk/ftp_server_pb2.py @@ -4,18 +4,15 @@ # source: ftp_server/ftp_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'ftp_server/ftp_server.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "ftp_server/ftp_server.proto" ) # @@protoc_insertion_point(imports) @@ -25,24 +22,32 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'ftp_server.ftp_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "ftp_server.ftp_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\024io.mavsdk.ftp_serverB\016FtpServerProto' - _globals['_FTPSERVERSERVICE'].methods_by_name['SetRootDir']._loaded_options = None - _globals['_FTPSERVERSERVICE'].methods_by_name['SetRootDir']._serialized_options = b'\200\265\030\001' - _globals['_SETROOTDIRREQUEST']._serialized_start=76 - _globals['_SETROOTDIRREQUEST']._serialized_end=109 - _globals['_SETROOTDIRRESPONSE']._serialized_start=111 - _globals['_SETROOTDIRRESPONSE']._serialized_end=198 - _globals['_FTPSERVERRESULT']._serialized_start=201 - _globals['_FTPSERVERRESULT']._serialized_end=395 - _globals['_FTPSERVERRESULT_RESULT']._serialized_start=303 - _globals['_FTPSERVERRESULT_RESULT']._serialized_end=395 - _globals['_FTPSERVERSERVICE']._serialized_start=397 - _globals['_FTPSERVERSERVICE']._serialized_end=520 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\024io.mavsdk.ftp_serverB\016FtpServerProto" + _globals["_FTPSERVERSERVICE"].methods_by_name["SetRootDir"]._loaded_options = None + _globals["_FTPSERVERSERVICE"].methods_by_name[ + "SetRootDir" + ]._serialized_options = b"\200\265\030\001" + _globals["_SETROOTDIRREQUEST"]._serialized_start = 76 + _globals["_SETROOTDIRREQUEST"]._serialized_end = 109 + _globals["_SETROOTDIRRESPONSE"]._serialized_start = 111 + _globals["_SETROOTDIRRESPONSE"]._serialized_end = 198 + _globals["_FTPSERVERRESULT"]._serialized_start = 201 + _globals["_FTPSERVERRESULT"]._serialized_end = 395 + _globals["_FTPSERVERRESULT_RESULT"]._serialized_start = 303 + _globals["_FTPSERVERRESULT_RESULT"]._serialized_end = 395 + _globals["_FTPSERVERSERVICE"]._serialized_start = 397 + _globals["_FTPSERVERSERVICE"]._serialized_end = 520 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/ftp_server_pb2_grpc.py b/mavsdk/ftp_server_pb2_grpc.py index 0393b3fc..bf8af674 100644 --- a/mavsdk/ftp_server_pb2_grpc.py +++ b/mavsdk/ftp_server_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import ftp_server_pb2 as ftp__server_dot_ftp__server__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in ftp_server/ftp_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in ftp_server/ftp_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class FtpServerServiceStub(object): - """Provide files or directories to transfer. - """ + """Provide files or directories to transfer.""" def __init__(self, channel): """Constructor. @@ -36,15 +39,15 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetRootDir = channel.unary_unary( - '/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir', - request_serializer=ftp__server_dot_ftp__server__pb2.SetRootDirRequest.SerializeToString, - response_deserializer=ftp__server_dot_ftp__server__pb2.SetRootDirResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir", + request_serializer=ftp__server_dot_ftp__server__pb2.SetRootDirRequest.SerializeToString, + response_deserializer=ftp__server_dot_ftp__server__pb2.SetRootDirResponse.FromString, + _registered_method=True, + ) class FtpServerServiceServicer(object): - """Provide files or directories to transfer. - """ + """Provide files or directories to transfer.""" def SetRootDir(self, request, context): """ @@ -56,44 +59,48 @@ def SetRootDir(self, request, context): The root directory can't be changed while an FTP process is in progress. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_FtpServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetRootDir': grpc.unary_unary_rpc_method_handler( - servicer.SetRootDir, - request_deserializer=ftp__server_dot_ftp__server__pb2.SetRootDirRequest.FromString, - response_serializer=ftp__server_dot_ftp__server__pb2.SetRootDirResponse.SerializeToString, - ), + "SetRootDir": grpc.unary_unary_rpc_method_handler( + servicer.SetRootDir, + request_deserializer=ftp__server_dot_ftp__server__pb2.SetRootDirRequest.FromString, + response_serializer=ftp__server_dot_ftp__server__pb2.SetRootDirResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.ftp_server.FtpServerService', rpc_method_handlers) + "mavsdk.rpc.ftp_server.FtpServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.ftp_server.FtpServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.ftp_server.FtpServerService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class FtpServerService(object): - """Provide files or directories to transfer. - """ + """Provide files or directories to transfer.""" @staticmethod - def SetRootDir(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRootDir( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir', + "/mavsdk.rpc.ftp_server.FtpServerService/SetRootDir", ftp__server_dot_ftp__server__pb2.SetRootDirRequest.SerializeToString, ftp__server_dot_ftp__server__pb2.SetRootDirResponse.FromString, options, @@ -104,4 +111,5 @@ def SetRootDir(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/geofence.py b/mavsdk/geofence.py index 274a8388..5aaf4132 100644 --- a/mavsdk/geofence.py +++ b/mavsdk/geofence.py @@ -8,19 +8,18 @@ class FenceType(Enum): """ - Geofence types. + Geofence types. - Values - ------ - INCLUSION - Type representing an inclusion fence + Values + ------ + INCLUSION + Type representing an inclusion fence - EXCLUSION - Type representing an exclusion fence + EXCLUSION + Type representing an exclusion fence - """ + """ - INCLUSION = 0 EXCLUSION = 1 @@ -32,7 +31,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == geofence_pb2.FENCE_TYPE_INCLUSION: return FenceType.INCLUSION if rpc_enum_value == geofence_pb2.FENCE_TYPE_EXCLUSION: @@ -44,386 +43,311 @@ def __str__(self): class Point: """ - Point type. - - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Point type. - longitude_deg : double - Longitude in degrees (range: -180 to +180) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - """ + longitude_deg : double + Longitude in degrees (range: -180 to +180) - + """ - def __init__( - self, - latitude_deg, - longitude_deg): - """ Initializes the Point object """ + def __init__(self, latitude_deg, longitude_deg): + """Initializes the Point object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg def __eq__(self, to_compare): - """ Checks if two Point are the same """ + """Checks if two Point are the same""" try: # Try to compare - this likely fails when it is compared to a non # Point object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) + return (self.latitude_deg == to_compare.latitude_deg) and ( + self.longitude_deg == to_compare.longitude_deg + ) except AttributeError: return False def __str__(self): - """ Point in string representation """ - struct_repr = ", ".join([ + """Point in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), - "longitude_deg: " + str(self.longitude_deg) - ]) + "longitude_deg: " + str(self.longitude_deg), + ] + ) return f"Point: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPoint): - """ Translates a gRPC struct to the SDK equivalent """ - return Point( - - rpcPoint.latitude_deg, - - - rpcPoint.longitude_deg - ) + """Translates a gRPC struct to the SDK equivalent""" + return Point(rpcPoint.latitude_deg, rpcPoint.longitude_deg) def translate_to_rpc(self, rpcPoint): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPoint.latitude_deg = self.latitude_deg - - - - - + rpcPoint.longitude_deg = self.longitude_deg - - - class Polygon: """ - Polygon type. - - Parameters - ---------- - points : [Point] - Points defining the polygon + Polygon type. - fence_type : FenceType - Fence type + Parameters + ---------- + points : [Point] + Points defining the polygon - """ + fence_type : FenceType + Fence type - + """ - def __init__( - self, - points, - fence_type): - """ Initializes the Polygon object """ + def __init__(self, points, fence_type): + """Initializes the Polygon object""" self.points = points self.fence_type = fence_type def __eq__(self, to_compare): - """ Checks if two Polygon are the same """ + """Checks if two Polygon are the same""" try: # Try to compare - this likely fails when it is compared to a non # Polygon object - return \ - (self.points == to_compare.points) and \ - (self.fence_type == to_compare.fence_type) + return (self.points == to_compare.points) and ( + self.fence_type == to_compare.fence_type + ) except AttributeError: return False def __str__(self): - """ Polygon in string representation """ - struct_repr = ", ".join([ - "points: " + str(self.points), - "fence_type: " + str(self.fence_type) - ]) + """Polygon in string representation""" + struct_repr = ", ".join( + ["points: " + str(self.points), "fence_type: " + str(self.fence_type)] + ) return f"Polygon: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPolygon): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Polygon( - - list(map(lambda elem: Point.translate_from_rpc(elem), rpcPolygon.points)), - - - FenceType.translate_from_rpc(rpcPolygon.fence_type) - ) + list(map(lambda elem: Point.translate_from_rpc(elem), rpcPolygon.points)), + FenceType.translate_from_rpc(rpcPolygon.fence_type), + ) def translate_to_rpc(self, rpcPolygon): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.points: - rpc_elem = geofence_pb2.Point() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcPolygon.points.extend(rpc_elems_list) - - - - - + rpcPolygon.fence_type = self.fence_type.translate_to_rpc() - - - class Circle: """ - Circular type. - - Parameters - ---------- - point : Point - Point defining the center + Circular type. - radius : float - Radius of the circular fence + Parameters + ---------- + point : Point + Point defining the center - fence_type : FenceType - Fence type + radius : float + Radius of the circular fence - """ + fence_type : FenceType + Fence type - + """ - def __init__( - self, - point, - radius, - fence_type): - """ Initializes the Circle object """ + def __init__(self, point, radius, fence_type): + """Initializes the Circle object""" self.point = point self.radius = radius self.fence_type = fence_type def __eq__(self, to_compare): - """ Checks if two Circle are the same """ + """Checks if two Circle are the same""" try: # Try to compare - this likely fails when it is compared to a non # Circle object - return \ - (self.point == to_compare.point) and \ - (self.radius == to_compare.radius) and \ - (self.fence_type == to_compare.fence_type) + return ( + (self.point == to_compare.point) + and (self.radius == to_compare.radius) + and (self.fence_type == to_compare.fence_type) + ) except AttributeError: return False def __str__(self): - """ Circle in string representation """ - struct_repr = ", ".join([ + """Circle in string representation""" + struct_repr = ", ".join( + [ "point: " + str(self.point), "radius: " + str(self.radius), - "fence_type: " + str(self.fence_type) - ]) + "fence_type: " + str(self.fence_type), + ] + ) return f"Circle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCircle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Circle( - - Point.translate_from_rpc(rpcCircle.point), - - - rpcCircle.radius, - - - FenceType.translate_from_rpc(rpcCircle.fence_type) - ) + Point.translate_from_rpc(rpcCircle.point), + rpcCircle.radius, + FenceType.translate_from_rpc(rpcCircle.fence_type), + ) def translate_to_rpc(self, rpcCircle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - self.point.translate_to_rpc(rpcCircle.point) - - - - - + rpcCircle.radius = self.radius - - - - - + rpcCircle.fence_type = self.fence_type.translate_to_rpc() - - - class GeofenceData: """ - Geofence data type. - - Parameters - ---------- - polygons : [Polygon] - Polygon(s) representing the geofence(s) + Geofence data type. - circles : [Circle] - Circle(s) representing the geofence(s) + Parameters + ---------- + polygons : [Polygon] + Polygon(s) representing the geofence(s) - """ + circles : [Circle] + Circle(s) representing the geofence(s) - + """ - def __init__( - self, - polygons, - circles): - """ Initializes the GeofenceData object """ + def __init__(self, polygons, circles): + """Initializes the GeofenceData object""" self.polygons = polygons self.circles = circles def __eq__(self, to_compare): - """ Checks if two GeofenceData are the same """ + """Checks if two GeofenceData are the same""" try: # Try to compare - this likely fails when it is compared to a non # GeofenceData object - return \ - (self.polygons == to_compare.polygons) and \ - (self.circles == to_compare.circles) + return (self.polygons == to_compare.polygons) and ( + self.circles == to_compare.circles + ) except AttributeError: return False def __str__(self): - """ GeofenceData in string representation """ - struct_repr = ", ".join([ - "polygons: " + str(self.polygons), - "circles: " + str(self.circles) - ]) + """GeofenceData in string representation""" + struct_repr = ", ".join( + ["polygons: " + str(self.polygons), "circles: " + str(self.circles)] + ) return f"GeofenceData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGeofenceData): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GeofenceData( - - list(map(lambda elem: Polygon.translate_from_rpc(elem), rpcGeofenceData.polygons)), - - - list(map(lambda elem: Circle.translate_from_rpc(elem), rpcGeofenceData.circles)) + list( + map( + lambda elem: Polygon.translate_from_rpc(elem), + rpcGeofenceData.polygons, + ) + ), + list( + map( + lambda elem: Circle.translate_from_rpc(elem), + rpcGeofenceData.circles, ) + ), + ) def translate_to_rpc(self, rpcGeofenceData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.polygons: - rpc_elem = geofence_pb2.Polygon() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcGeofenceData.polygons.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.circles: - rpc_elem = geofence_pb2.Circle() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcGeofenceData.circles.extend(rpc_elems_list) - - - class GeofenceResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for geofence requests. + Possible results returned for geofence requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - ERROR - Error + ERROR + Error - TOO_MANY_GEOFENCE_ITEMS - Too many objects in the geofence + TOO_MANY_GEOFENCE_ITEMS + Too many objects in the geofence - BUSY - Vehicle is busy + BUSY + Vehicle is busy - TIMEOUT - Request timed out + TIMEOUT + Request timed out - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 ERROR = 2 @@ -453,14 +377,17 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == geofence_pb2.GeofenceResult.RESULT_UNKNOWN: return GeofenceResult.Result.UNKNOWN if rpc_enum_value == geofence_pb2.GeofenceResult.RESULT_SUCCESS: return GeofenceResult.Result.SUCCESS if rpc_enum_value == geofence_pb2.GeofenceResult.RESULT_ERROR: return GeofenceResult.Result.ERROR - if rpc_enum_value == geofence_pb2.GeofenceResult.RESULT_TOO_MANY_GEOFENCE_ITEMS: + if ( + rpc_enum_value + == geofence_pb2.GeofenceResult.RESULT_TOO_MANY_GEOFENCE_ITEMS + ): return GeofenceResult.Result.TOO_MANY_GEOFENCE_ITEMS if rpc_enum_value == geofence_pb2.GeofenceResult.RESULT_BUSY: return GeofenceResult.Result.BUSY @@ -473,69 +400,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the GeofenceResult object """ + def __init__(self, result, result_str): + """Initializes the GeofenceResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two GeofenceResult are the same """ + """Checks if two GeofenceResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # GeofenceResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ GeofenceResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """GeofenceResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"GeofenceResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGeofenceResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GeofenceResult( - - GeofenceResult.Result.translate_from_rpc(rpcGeofenceResult.result), - - - rpcGeofenceResult.result_str - ) + GeofenceResult.Result.translate_from_rpc(rpcGeofenceResult.result), + rpcGeofenceResult.result_str, + ) def translate_to_rpc(self, rpcGeofenceResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGeofenceResult.result = self.result.translate_to_rpc() - - - - - - rpcGeofenceResult.result_str = self.result_str - - - + rpcGeofenceResult.result_str = self.result_str class GeofenceError(Exception): - """ Raised when a GeofenceResult is a fail code """ + """Raised when a GeofenceResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -548,72 +456,65 @@ def __str__(self): class Geofence(AsyncBase): """ - Enable setting a geofence. + Enable setting a geofence. - Generated by dcsdkgen - MAVSDK Geofence API + Generated by dcsdkgen - MAVSDK Geofence API """ # Plugin name name = "Geofence" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = geofence_pb2_grpc.GeofenceServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return GeofenceResult.translate_from_rpc(response.geofence_result) - async def upload_geofence(self, geofence_data): """ - Upload geofences. + Upload geofences. - Polygon and Circular geofences are uploaded to a drone. Once uploaded, the geofence will remain - on the drone even if a connection is lost. + Polygon and Circular geofences are uploaded to a drone. Once uploaded, the geofence will remain + on the drone even if a connection is lost. - Parameters - ---------- - geofence_data : GeofenceData - Circle(s) and/or Polygon(s) representing the geofence(s) + Parameters + ---------- + geofence_data : GeofenceData + Circle(s) and/or Polygon(s) representing the geofence(s) - Raises - ------ - GeofenceError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GeofenceError + If the request fails. The error contains the reason for the failure. """ request = geofence_pb2.UploadGeofenceRequest() - + geofence_data.translate_to_rpc(request.geofence_data) - - + response = await self._stub.UploadGeofence(request) - result = self._extract_result(response) if result.result != GeofenceResult.Result.SUCCESS: raise GeofenceError(result, "upload_geofence()", geofence_data) - async def clear_geofence(self): """ - Clear all geofences saved on the vehicle. + Clear all geofences saved on the vehicle. - Raises - ------ - GeofenceError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GeofenceError + If the request fails. The error contains the reason for the failure. """ request = geofence_pb2.ClearGeofenceRequest() response = await self._stub.ClearGeofence(request) - result = self._extract_result(response) if result.result != GeofenceResult.Result.SUCCESS: raise GeofenceError(result, "clear_geofence()") - \ No newline at end of file diff --git a/mavsdk/geofence_pb2.py b/mavsdk/geofence_pb2.py index 9c34b469..7f3730c7 100644 --- a/mavsdk/geofence_pb2.py +++ b/mavsdk/geofence_pb2.py @@ -4,18 +4,15 @@ # source: geofence/geofence.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'geofence/geofence.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "geofence/geofence.proto" ) # @@protoc_insertion_point(imports) @@ -25,38 +22,44 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'geofence.geofence_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "geofence.geofence_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\022io.mavsdk.geofenceB\rGeofenceProto' - _globals['_CIRCLE'].fields_by_name['radius']._loaded_options = None - _globals['_CIRCLE'].fields_by_name['radius']._serialized_options = b'\202\265\030\003NaN' - _globals['_FENCETYPE']._serialized_start=1046 - _globals['_FENCETYPE']._serialized_end=1109 - _globals['_POINT']._serialized_start=70 - _globals['_POINT']._serialized_end=122 - _globals['_POLYGON']._serialized_start=124 - _globals['_POLYGON']._serialized_end=229 - _globals['_CIRCLE']._serialized_start=232 - _globals['_CIRCLE']._serialized_end=360 - _globals['_GEOFENCEDATA']._serialized_start=362 - _globals['_GEOFENCEDATA']._serialized_end=470 - _globals['_UPLOADGEOFENCEREQUEST']._serialized_start=472 - _globals['_UPLOADGEOFENCEREQUEST']._serialized_end=553 - _globals['_UPLOADGEOFENCERESPONSE']._serialized_start=555 - _globals['_UPLOADGEOFENCERESPONSE']._serialized_end=641 - _globals['_CLEARGEOFENCEREQUEST']._serialized_start=643 - _globals['_CLEARGEOFENCEREQUEST']._serialized_end=665 - _globals['_CLEARGEOFENCERESPONSE']._serialized_start=667 - _globals['_CLEARGEOFENCERESPONSE']._serialized_end=752 - _globals['_GEOFENCERESULT']._serialized_start=755 - _globals['_GEOFENCERESULT']._serialized_end=1044 - _globals['_GEOFENCERESULT_RESULT']._serialized_start=854 - _globals['_GEOFENCERESULT_RESULT']._serialized_end=1044 - _globals['_GEOFENCESERVICE']._serialized_start=1112 - _globals['_GEOFENCESERVICE']._serialized_end=1344 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\022io.mavsdk.geofenceB\rGeofenceProto" + _globals["_CIRCLE"].fields_by_name["radius"]._loaded_options = None + _globals["_CIRCLE"].fields_by_name[ + "radius" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FENCETYPE"]._serialized_start = 1046 + _globals["_FENCETYPE"]._serialized_end = 1109 + _globals["_POINT"]._serialized_start = 70 + _globals["_POINT"]._serialized_end = 122 + _globals["_POLYGON"]._serialized_start = 124 + _globals["_POLYGON"]._serialized_end = 229 + _globals["_CIRCLE"]._serialized_start = 232 + _globals["_CIRCLE"]._serialized_end = 360 + _globals["_GEOFENCEDATA"]._serialized_start = 362 + _globals["_GEOFENCEDATA"]._serialized_end = 470 + _globals["_UPLOADGEOFENCEREQUEST"]._serialized_start = 472 + _globals["_UPLOADGEOFENCEREQUEST"]._serialized_end = 553 + _globals["_UPLOADGEOFENCERESPONSE"]._serialized_start = 555 + _globals["_UPLOADGEOFENCERESPONSE"]._serialized_end = 641 + _globals["_CLEARGEOFENCEREQUEST"]._serialized_start = 643 + _globals["_CLEARGEOFENCEREQUEST"]._serialized_end = 665 + _globals["_CLEARGEOFENCERESPONSE"]._serialized_start = 667 + _globals["_CLEARGEOFENCERESPONSE"]._serialized_end = 752 + _globals["_GEOFENCERESULT"]._serialized_start = 755 + _globals["_GEOFENCERESULT"]._serialized_end = 1044 + _globals["_GEOFENCERESULT_RESULT"]._serialized_start = 854 + _globals["_GEOFENCERESULT_RESULT"]._serialized_end = 1044 + _globals["_GEOFENCESERVICE"]._serialized_start = 1112 + _globals["_GEOFENCESERVICE"]._serialized_end = 1344 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/geofence_pb2_grpc.py b/mavsdk/geofence_pb2_grpc.py index 033e97ea..b7ecffad 100644 --- a/mavsdk/geofence_pb2_grpc.py +++ b/mavsdk/geofence_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import geofence_pb2 as geofence_dot_geofence__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in geofence/geofence_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in geofence/geofence_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class GeofenceServiceStub(object): - """Enable setting a geofence. - """ + """Enable setting a geofence.""" def __init__(self, channel): """Constructor. @@ -36,20 +39,21 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.UploadGeofence = channel.unary_unary( - '/mavsdk.rpc.geofence.GeofenceService/UploadGeofence', - request_serializer=geofence_dot_geofence__pb2.UploadGeofenceRequest.SerializeToString, - response_deserializer=geofence_dot_geofence__pb2.UploadGeofenceResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.geofence.GeofenceService/UploadGeofence", + request_serializer=geofence_dot_geofence__pb2.UploadGeofenceRequest.SerializeToString, + response_deserializer=geofence_dot_geofence__pb2.UploadGeofenceResponse.FromString, + _registered_method=True, + ) self.ClearGeofence = channel.unary_unary( - '/mavsdk.rpc.geofence.GeofenceService/ClearGeofence', - request_serializer=geofence_dot_geofence__pb2.ClearGeofenceRequest.SerializeToString, - response_deserializer=geofence_dot_geofence__pb2.ClearGeofenceResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.geofence.GeofenceService/ClearGeofence", + request_serializer=geofence_dot_geofence__pb2.ClearGeofenceRequest.SerializeToString, + response_deserializer=geofence_dot_geofence__pb2.ClearGeofenceResponse.FromString, + _registered_method=True, + ) class GeofenceServiceServicer(object): - """Enable setting a geofence. - """ + """Enable setting a geofence.""" def UploadGeofence(self, request, context): """ @@ -59,57 +63,61 @@ def UploadGeofence(self, request, context): on the drone even if a connection is lost. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ClearGeofence(self, request, context): """ Clear all geofences saved on the vehicle. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_GeofenceServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'UploadGeofence': grpc.unary_unary_rpc_method_handler( - servicer.UploadGeofence, - request_deserializer=geofence_dot_geofence__pb2.UploadGeofenceRequest.FromString, - response_serializer=geofence_dot_geofence__pb2.UploadGeofenceResponse.SerializeToString, - ), - 'ClearGeofence': grpc.unary_unary_rpc_method_handler( - servicer.ClearGeofence, - request_deserializer=geofence_dot_geofence__pb2.ClearGeofenceRequest.FromString, - response_serializer=geofence_dot_geofence__pb2.ClearGeofenceResponse.SerializeToString, - ), + "UploadGeofence": grpc.unary_unary_rpc_method_handler( + servicer.UploadGeofence, + request_deserializer=geofence_dot_geofence__pb2.UploadGeofenceRequest.FromString, + response_serializer=geofence_dot_geofence__pb2.UploadGeofenceResponse.SerializeToString, + ), + "ClearGeofence": grpc.unary_unary_rpc_method_handler( + servicer.ClearGeofence, + request_deserializer=geofence_dot_geofence__pb2.ClearGeofenceRequest.FromString, + response_serializer=geofence_dot_geofence__pb2.ClearGeofenceResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.geofence.GeofenceService', rpc_method_handlers) + "mavsdk.rpc.geofence.GeofenceService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.geofence.GeofenceService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.geofence.GeofenceService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class GeofenceService(object): - """Enable setting a geofence. - """ + """Enable setting a geofence.""" @staticmethod - def UploadGeofence(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def UploadGeofence( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.geofence.GeofenceService/UploadGeofence', + "/mavsdk.rpc.geofence.GeofenceService/UploadGeofence", geofence_dot_geofence__pb2.UploadGeofenceRequest.SerializeToString, geofence_dot_geofence__pb2.UploadGeofenceResponse.FromString, options, @@ -120,23 +128,26 @@ def UploadGeofence(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ClearGeofence(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ClearGeofence( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.geofence.GeofenceService/ClearGeofence', + "/mavsdk.rpc.geofence.GeofenceService/ClearGeofence", geofence_dot_geofence__pb2.ClearGeofenceRequest.SerializeToString, geofence_dot_geofence__pb2.ClearGeofenceResponse.FromString, options, @@ -147,4 +158,5 @@ def ClearGeofence(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/gimbal.py b/mavsdk/gimbal.py index eb70e271..72139bea 100644 --- a/mavsdk/gimbal.py +++ b/mavsdk/gimbal.py @@ -8,19 +8,18 @@ class GimbalMode(Enum): """ - Gimbal mode type. + Gimbal mode type. - Values - ------ - YAW_FOLLOW - Yaw follow will point the gimbal to the vehicle heading + Values + ------ + YAW_FOLLOW + Yaw follow will point the gimbal to the vehicle heading - YAW_LOCK - Yaw lock will fix the gimbal pointing to an absolute direction + YAW_LOCK + Yaw lock will fix the gimbal pointing to an absolute direction - """ + """ - YAW_FOLLOW = 0 YAW_LOCK = 1 @@ -32,7 +31,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == gimbal_pb2.GIMBAL_MODE_YAW_FOLLOW: return GimbalMode.YAW_FOLLOW if rpc_enum_value == gimbal_pb2.GIMBAL_MODE_YAW_LOCK: @@ -44,22 +43,21 @@ def __str__(self): class ControlMode(Enum): """ - Control mode + Control mode - Values - ------ - NONE - Indicates that the component does not have control over the gimbal + Values + ------ + NONE + Indicates that the component does not have control over the gimbal - PRIMARY - To take primary control over the gimbal + PRIMARY + To take primary control over the gimbal - SECONDARY - To take secondary control over the gimbal + SECONDARY + To take secondary control over the gimbal - """ + """ - NONE = 0 PRIMARY = 1 SECONDARY = 2 @@ -74,7 +72,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == gimbal_pb2.CONTROL_MODE_NONE: return ControlMode.NONE if rpc_enum_value == gimbal_pb2.CONTROL_MODE_PRIMARY: @@ -88,19 +86,18 @@ def __str__(self): class SendMode(Enum): """ - The send mode type + The send mode type - Values - ------ - ONCE - Send command exactly once with quality of service (use for sporadic commands slower than 1 Hz) + Values + ------ + ONCE + Send command exactly once with quality of service (use for sporadic commands slower than 1 Hz) - STREAM - Stream setpoint without quality of service (use for setpoints faster than 1 Hz). + STREAM + Stream setpoint without quality of service (use for setpoints faster than 1 Hz). - """ + """ - ONCE = 0 STREAM = 1 @@ -112,7 +109,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == gimbal_pb2.SEND_MODE_ONCE: return SendMode.ONCE if rpc_enum_value == gimbal_pb2.SEND_MODE_STREAM: @@ -124,344 +121,265 @@ def __str__(self): class Quaternion: """ - Quaternion type. + Quaternion type. - All rotations and axis systems follow the right-hand rule. - The Hamilton quaternion product definition is used. - A zero-rotation quaternion is represented by (1,0,0,0). - The quaternion could also be written as w + xi + yj + zk. + All rotations and axis systems follow the right-hand rule. + The Hamilton quaternion product definition is used. + A zero-rotation quaternion is represented by (1,0,0,0). + The quaternion could also be written as w + xi + yj + zk. - For more info see: https://en.wikipedia.org/wiki/Quaternion + For more info see: https://en.wikipedia.org/wiki/Quaternion - Parameters - ---------- - w : float - Quaternion entry 0, also denoted as a + Parameters + ---------- + w : float + Quaternion entry 0, also denoted as a - x : float - Quaternion entry 1, also denoted as b + x : float + Quaternion entry 1, also denoted as b - y : float - Quaternion entry 2, also denoted as c + y : float + Quaternion entry 2, also denoted as c - z : float - Quaternion entry 3, also denoted as d + z : float + Quaternion entry 3, also denoted as d - """ - - + """ - def __init__( - self, - w, - x, - y, - z): - """ Initializes the Quaternion object """ + def __init__(self, w, x, y, z): + """Initializes the Quaternion object""" self.w = w self.x = x self.y = y self.z = z def __eq__(self, to_compare): - """ Checks if two Quaternion are the same """ + """Checks if two Quaternion are the same""" try: # Try to compare - this likely fails when it is compared to a non # Quaternion object - return \ - (self.w == to_compare.w) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) + return ( + (self.w == to_compare.w) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + ) except AttributeError: return False def __str__(self): - """ Quaternion in string representation """ - struct_repr = ", ".join([ + """Quaternion in string representation""" + struct_repr = ", ".join( + [ "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), - "z: " + str(self.z) - ]) + "z: " + str(self.z), + ] + ) return f"Quaternion: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcQuaternion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Quaternion( - - rpcQuaternion.w, - - - rpcQuaternion.x, - - - rpcQuaternion.y, - - - rpcQuaternion.z - ) + rpcQuaternion.w, rpcQuaternion.x, rpcQuaternion.y, rpcQuaternion.z + ) def translate_to_rpc(self, rpcQuaternion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcQuaternion.w = self.w - - - - - + rpcQuaternion.x = self.x - - - - - + rpcQuaternion.y = self.y - - - - - + rpcQuaternion.z = self.z - - - class EulerAngle: """ - Euler angle type. + Euler angle type. - All rotations and axis systems follow the right-hand rule. - The Euler angles are converted using the 3-1-2 sequence instead of standard 3-2-1 in order - to avoid the gimbal lock at 90 degrees down. + All rotations and axis systems follow the right-hand rule. + The Euler angles are converted using the 3-1-2 sequence instead of standard 3-2-1 in order + to avoid the gimbal lock at 90 degrees down. - For more info see https://en.wikipedia.org/wiki/Euler_angles + For more info see https://en.wikipedia.org/wiki/Euler_angles - Parameters - ---------- - roll_deg : float - Roll angle in degrees, positive is banking to the right + Parameters + ---------- + roll_deg : float + Roll angle in degrees, positive is banking to the right - pitch_deg : float - Pitch angle in degrees, positive is pitching nose up + pitch_deg : float + Pitch angle in degrees, positive is pitching nose up - yaw_deg : float - Yaw angle in degrees, positive is clock-wise seen from above + yaw_deg : float + Yaw angle in degrees, positive is clock-wise seen from above - """ - - + """ - def __init__( - self, - roll_deg, - pitch_deg, - yaw_deg): - """ Initializes the EulerAngle object """ + def __init__(self, roll_deg, pitch_deg, yaw_deg): + """Initializes the EulerAngle object""" self.roll_deg = roll_deg self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg def __eq__(self, to_compare): - """ Checks if two EulerAngle are the same """ + """Checks if two EulerAngle are the same""" try: # Try to compare - this likely fails when it is compared to a non # EulerAngle object - return \ - (self.roll_deg == to_compare.roll_deg) and \ - (self.pitch_deg == to_compare.pitch_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) + return ( + (self.roll_deg == to_compare.roll_deg) + and (self.pitch_deg == to_compare.pitch_deg) + and (self.yaw_deg == to_compare.yaw_deg) + ) except AttributeError: return False def __str__(self): - """ EulerAngle in string representation """ - struct_repr = ", ".join([ + """EulerAngle in string representation""" + struct_repr = ", ".join( + [ "roll_deg: " + str(self.roll_deg), "pitch_deg: " + str(self.pitch_deg), - "yaw_deg: " + str(self.yaw_deg) - ]) + "yaw_deg: " + str(self.yaw_deg), + ] + ) return f"EulerAngle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEulerAngle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return EulerAngle( - - rpcEulerAngle.roll_deg, - - - rpcEulerAngle.pitch_deg, - - - rpcEulerAngle.yaw_deg - ) + rpcEulerAngle.roll_deg, rpcEulerAngle.pitch_deg, rpcEulerAngle.yaw_deg + ) def translate_to_rpc(self, rpcEulerAngle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEulerAngle.roll_deg = self.roll_deg - - - - - + rpcEulerAngle.pitch_deg = self.pitch_deg - - - - - + rpcEulerAngle.yaw_deg = self.yaw_deg - - - class AngularVelocityBody: """ - Gimbal angular rate type - - Parameters - ---------- - roll_rad_s : float - Roll angular velocity + Gimbal angular rate type - pitch_rad_s : float - Pitch angular velocity + Parameters + ---------- + roll_rad_s : float + Roll angular velocity - yaw_rad_s : float - Yaw angular velocity + pitch_rad_s : float + Pitch angular velocity - """ + yaw_rad_s : float + Yaw angular velocity - + """ - def __init__( - self, - roll_rad_s, - pitch_rad_s, - yaw_rad_s): - """ Initializes the AngularVelocityBody object """ + def __init__(self, roll_rad_s, pitch_rad_s, yaw_rad_s): + """Initializes the AngularVelocityBody object""" self.roll_rad_s = roll_rad_s self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s def __eq__(self, to_compare): - """ Checks if two AngularVelocityBody are the same """ + """Checks if two AngularVelocityBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngularVelocityBody object - return \ - (self.roll_rad_s == to_compare.roll_rad_s) and \ - (self.pitch_rad_s == to_compare.pitch_rad_s) and \ - (self.yaw_rad_s == to_compare.yaw_rad_s) + return ( + (self.roll_rad_s == to_compare.roll_rad_s) + and (self.pitch_rad_s == to_compare.pitch_rad_s) + and (self.yaw_rad_s == to_compare.yaw_rad_s) + ) except AttributeError: return False def __str__(self): - """ AngularVelocityBody in string representation """ - struct_repr = ", ".join([ + """AngularVelocityBody in string representation""" + struct_repr = ", ".join( + [ "roll_rad_s: " + str(self.roll_rad_s), "pitch_rad_s: " + str(self.pitch_rad_s), - "yaw_rad_s: " + str(self.yaw_rad_s) - ]) + "yaw_rad_s: " + str(self.yaw_rad_s), + ] + ) return f"AngularVelocityBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngularVelocityBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngularVelocityBody( - - rpcAngularVelocityBody.roll_rad_s, - - - rpcAngularVelocityBody.pitch_rad_s, - - - rpcAngularVelocityBody.yaw_rad_s - ) + rpcAngularVelocityBody.roll_rad_s, + rpcAngularVelocityBody.pitch_rad_s, + rpcAngularVelocityBody.yaw_rad_s, + ) def translate_to_rpc(self, rpcAngularVelocityBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngularVelocityBody.roll_rad_s = self.roll_rad_s - - - - - + rpcAngularVelocityBody.pitch_rad_s = self.pitch_rad_s - - - - - + rpcAngularVelocityBody.yaw_rad_s = self.yaw_rad_s - - - class Attitude: """ - Gimbal attitude type - - Parameters - ---------- - gimbal_id : int32_t - Gimbal ID + Gimbal attitude type - euler_angle_forward : EulerAngle - Euler angle relative to forward + Parameters + ---------- + gimbal_id : int32_t + Gimbal ID - quaternion_forward : Quaternion - Quaternion relative to forward + euler_angle_forward : EulerAngle + Euler angle relative to forward - euler_angle_north : EulerAngle - Euler angle relative to North + quaternion_forward : Quaternion + Quaternion relative to forward - quaternion_north : Quaternion - Quaternion relative to North + euler_angle_north : EulerAngle + Euler angle relative to North - angular_velocity : AngularVelocityBody - The angular rate + quaternion_north : Quaternion + Quaternion relative to North - timestamp_us : uint64_t - Timestamp in microseconds + angular_velocity : AngularVelocityBody + The angular rate - """ + timestamp_us : uint64_t + Timestamp in microseconds - + """ def __init__( - self, - gimbal_id, - euler_angle_forward, - quaternion_forward, - euler_angle_north, - quaternion_north, - angular_velocity, - timestamp_us): - """ Initializes the Attitude object """ + self, + gimbal_id, + euler_angle_forward, + quaternion_forward, + euler_angle_north, + quaternion_north, + angular_velocity, + timestamp_us, + ): + """Initializes the Attitude object""" self.gimbal_id = gimbal_id self.euler_angle_forward = euler_angle_forward self.quaternion_forward = quaternion_forward @@ -471,147 +389,106 @@ def __init__( self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two Attitude are the same """ + """Checks if two Attitude are the same""" try: # Try to compare - this likely fails when it is compared to a non # Attitude object - return \ - (self.gimbal_id == to_compare.gimbal_id) and \ - (self.euler_angle_forward == to_compare.euler_angle_forward) and \ - (self.quaternion_forward == to_compare.quaternion_forward) and \ - (self.euler_angle_north == to_compare.euler_angle_north) and \ - (self.quaternion_north == to_compare.quaternion_north) and \ - (self.angular_velocity == to_compare.angular_velocity) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.gimbal_id == to_compare.gimbal_id) + and (self.euler_angle_forward == to_compare.euler_angle_forward) + and (self.quaternion_forward == to_compare.quaternion_forward) + and (self.euler_angle_north == to_compare.euler_angle_north) + and (self.quaternion_north == to_compare.quaternion_north) + and (self.angular_velocity == to_compare.angular_velocity) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ Attitude in string representation """ - struct_repr = ", ".join([ + """Attitude in string representation""" + struct_repr = ", ".join( + [ "gimbal_id: " + str(self.gimbal_id), "euler_angle_forward: " + str(self.euler_angle_forward), "quaternion_forward: " + str(self.quaternion_forward), "euler_angle_north: " + str(self.euler_angle_north), "quaternion_north: " + str(self.quaternion_north), "angular_velocity: " + str(self.angular_velocity), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"Attitude: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAttitude): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Attitude( - - rpcAttitude.gimbal_id, - - - EulerAngle.translate_from_rpc(rpcAttitude.euler_angle_forward), - - - Quaternion.translate_from_rpc(rpcAttitude.quaternion_forward), - - - EulerAngle.translate_from_rpc(rpcAttitude.euler_angle_north), - - - Quaternion.translate_from_rpc(rpcAttitude.quaternion_north), - - - AngularVelocityBody.translate_from_rpc(rpcAttitude.angular_velocity), - - - rpcAttitude.timestamp_us - ) + rpcAttitude.gimbal_id, + EulerAngle.translate_from_rpc(rpcAttitude.euler_angle_forward), + Quaternion.translate_from_rpc(rpcAttitude.quaternion_forward), + EulerAngle.translate_from_rpc(rpcAttitude.euler_angle_north), + Quaternion.translate_from_rpc(rpcAttitude.quaternion_north), + AngularVelocityBody.translate_from_rpc(rpcAttitude.angular_velocity), + rpcAttitude.timestamp_us, + ) def translate_to_rpc(self, rpcAttitude): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAttitude.gimbal_id = self.gimbal_id - - - - - + self.euler_angle_forward.translate_to_rpc(rpcAttitude.euler_angle_forward) - - - - - + self.quaternion_forward.translate_to_rpc(rpcAttitude.quaternion_forward) - - - - - + self.euler_angle_north.translate_to_rpc(rpcAttitude.euler_angle_north) - - - - - + self.quaternion_north.translate_to_rpc(rpcAttitude.quaternion_north) - - - - - + self.angular_velocity.translate_to_rpc(rpcAttitude.angular_velocity) - - - - - + rpcAttitude.timestamp_us = self.timestamp_us - - - class GimbalItem: """ - Gimbal list item - - Parameters - ---------- - gimbal_id : int32_t - ID to address it, starting at 1 (0 means all gimbals) + Gimbal list item - vendor_name : std::string - Vendor name + Parameters + ---------- + gimbal_id : int32_t + ID to address it, starting at 1 (0 means all gimbals) - model_name : std::string - Model name + vendor_name : std::string + Vendor name - custom_name : std::string - Custom name name + model_name : std::string + Model name - gimbal_manager_component_id : int32_t - MAVLink component of gimbal manager, for debugging purposes + custom_name : std::string + Custom name name - gimbal_device_id : int32_t - MAVLink component of gimbal device + gimbal_manager_component_id : int32_t + MAVLink component of gimbal manager, for debugging purposes - """ + gimbal_device_id : int32_t + MAVLink component of gimbal device - + """ def __init__( - self, - gimbal_id, - vendor_name, - model_name, - custom_name, - gimbal_manager_component_id, - gimbal_device_id): - """ Initializes the GimbalItem object """ + self, + gimbal_id, + vendor_name, + model_name, + custom_name, + gimbal_manager_component_id, + gimbal_device_id, + ): + """Initializes the GimbalItem object""" self.gimbal_id = gimbal_id self.vendor_name = vendor_name self.model_name = model_name @@ -620,201 +497,159 @@ def __init__( self.gimbal_device_id = gimbal_device_id def __eq__(self, to_compare): - """ Checks if two GimbalItem are the same """ + """Checks if two GimbalItem are the same""" try: # Try to compare - this likely fails when it is compared to a non # GimbalItem object - return \ - (self.gimbal_id == to_compare.gimbal_id) and \ - (self.vendor_name == to_compare.vendor_name) and \ - (self.model_name == to_compare.model_name) and \ - (self.custom_name == to_compare.custom_name) and \ - (self.gimbal_manager_component_id == to_compare.gimbal_manager_component_id) and \ - (self.gimbal_device_id == to_compare.gimbal_device_id) + return ( + (self.gimbal_id == to_compare.gimbal_id) + and (self.vendor_name == to_compare.vendor_name) + and (self.model_name == to_compare.model_name) + and (self.custom_name == to_compare.custom_name) + and ( + self.gimbal_manager_component_id + == to_compare.gimbal_manager_component_id + ) + and (self.gimbal_device_id == to_compare.gimbal_device_id) + ) except AttributeError: return False def __str__(self): - """ GimbalItem in string representation """ - struct_repr = ", ".join([ + """GimbalItem in string representation""" + struct_repr = ", ".join( + [ "gimbal_id: " + str(self.gimbal_id), "vendor_name: " + str(self.vendor_name), "model_name: " + str(self.model_name), "custom_name: " + str(self.custom_name), "gimbal_manager_component_id: " + str(self.gimbal_manager_component_id), - "gimbal_device_id: " + str(self.gimbal_device_id) - ]) + "gimbal_device_id: " + str(self.gimbal_device_id), + ] + ) return f"GimbalItem: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGimbalItem): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GimbalItem( - - rpcGimbalItem.gimbal_id, - - - rpcGimbalItem.vendor_name, - - - rpcGimbalItem.model_name, - - - rpcGimbalItem.custom_name, - - - rpcGimbalItem.gimbal_manager_component_id, - - - rpcGimbalItem.gimbal_device_id - ) + rpcGimbalItem.gimbal_id, + rpcGimbalItem.vendor_name, + rpcGimbalItem.model_name, + rpcGimbalItem.custom_name, + rpcGimbalItem.gimbal_manager_component_id, + rpcGimbalItem.gimbal_device_id, + ) def translate_to_rpc(self, rpcGimbalItem): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGimbalItem.gimbal_id = self.gimbal_id - - - - - + rpcGimbalItem.vendor_name = self.vendor_name - - - - - + rpcGimbalItem.model_name = self.model_name - - - - - + rpcGimbalItem.custom_name = self.custom_name - - - - - + rpcGimbalItem.gimbal_manager_component_id = self.gimbal_manager_component_id - - - - - + rpcGimbalItem.gimbal_device_id = self.gimbal_device_id - - - class GimbalList: """ - Gimbal list + Gimbal list - Parameters - ---------- - gimbals : [GimbalItem] - Gimbal items. + Parameters + ---------- + gimbals : [GimbalItem] + Gimbal items. - """ - - + """ - def __init__( - self, - gimbals): - """ Initializes the GimbalList object """ + def __init__(self, gimbals): + """Initializes the GimbalList object""" self.gimbals = gimbals def __eq__(self, to_compare): - """ Checks if two GimbalList are the same """ + """Checks if two GimbalList are the same""" try: # Try to compare - this likely fails when it is compared to a non # GimbalList object - return \ - (self.gimbals == to_compare.gimbals) + return self.gimbals == to_compare.gimbals except AttributeError: return False def __str__(self): - """ GimbalList in string representation """ - struct_repr = ", ".join([ - "gimbals: " + str(self.gimbals) - ]) + """GimbalList in string representation""" + struct_repr = ", ".join(["gimbals: " + str(self.gimbals)]) return f"GimbalList: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGimbalList): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GimbalList( - - list(map(lambda elem: GimbalItem.translate_from_rpc(elem), rpcGimbalList.gimbals)) + list( + map( + lambda elem: GimbalItem.translate_from_rpc(elem), + rpcGimbalList.gimbals, ) + ) + ) def translate_to_rpc(self, rpcGimbalList): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.gimbals: - rpc_elem = gimbal_pb2.GimbalItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcGimbalList.gimbals.extend(rpc_elems_list) - - - class ControlStatus: """ - Control status - - Parameters - ---------- - gimbal_id : int32_t - Gimbal ID + Control status - control_mode : ControlMode - Control mode (none, primary or secondary) + Parameters + ---------- + gimbal_id : int32_t + Gimbal ID - sysid_primary_control : int32_t - Sysid of the component that has primary control over the gimbal (0 if no one is in control) + control_mode : ControlMode + Control mode (none, primary or secondary) - compid_primary_control : int32_t - Compid of the component that has primary control over the gimbal (0 if no one is in control) + sysid_primary_control : int32_t + Sysid of the component that has primary control over the gimbal (0 if no one is in control) - sysid_secondary_control : int32_t - Sysid of the component that has secondary control over the gimbal (0 if no one is in control) + compid_primary_control : int32_t + Compid of the component that has primary control over the gimbal (0 if no one is in control) - compid_secondary_control : int32_t - Compid of the component that has secondary control over the gimbal (0 if no one is in control) + sysid_secondary_control : int32_t + Sysid of the component that has secondary control over the gimbal (0 if no one is in control) - """ + compid_secondary_control : int32_t + Compid of the component that has secondary control over the gimbal (0 if no one is in control) - + """ def __init__( - self, - gimbal_id, - control_mode, - sysid_primary_control, - compid_primary_control, - sysid_secondary_control, - compid_secondary_control): - """ Initializes the ControlStatus object """ + self, + gimbal_id, + control_mode, + sysid_primary_control, + compid_primary_control, + sysid_secondary_control, + compid_secondary_control, + ): + """Initializes the ControlStatus object""" self.gimbal_id = gimbal_id self.control_mode = control_mode self.sysid_primary_control = sysid_primary_control @@ -823,145 +658,110 @@ def __init__( self.compid_secondary_control = compid_secondary_control def __eq__(self, to_compare): - """ Checks if two ControlStatus are the same """ + """Checks if two ControlStatus are the same""" try: # Try to compare - this likely fails when it is compared to a non # ControlStatus object - return \ - (self.gimbal_id == to_compare.gimbal_id) and \ - (self.control_mode == to_compare.control_mode) and \ - (self.sysid_primary_control == to_compare.sysid_primary_control) and \ - (self.compid_primary_control == to_compare.compid_primary_control) and \ - (self.sysid_secondary_control == to_compare.sysid_secondary_control) and \ - (self.compid_secondary_control == to_compare.compid_secondary_control) + return ( + (self.gimbal_id == to_compare.gimbal_id) + and (self.control_mode == to_compare.control_mode) + and (self.sysid_primary_control == to_compare.sysid_primary_control) + and (self.compid_primary_control == to_compare.compid_primary_control) + and (self.sysid_secondary_control == to_compare.sysid_secondary_control) + and ( + self.compid_secondary_control == to_compare.compid_secondary_control + ) + ) except AttributeError: return False def __str__(self): - """ ControlStatus in string representation """ - struct_repr = ", ".join([ + """ControlStatus in string representation""" + struct_repr = ", ".join( + [ "gimbal_id: " + str(self.gimbal_id), "control_mode: " + str(self.control_mode), "sysid_primary_control: " + str(self.sysid_primary_control), "compid_primary_control: " + str(self.compid_primary_control), "sysid_secondary_control: " + str(self.sysid_secondary_control), - "compid_secondary_control: " + str(self.compid_secondary_control) - ]) + "compid_secondary_control: " + str(self.compid_secondary_control), + ] + ) return f"ControlStatus: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcControlStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ControlStatus( - - rpcControlStatus.gimbal_id, - - - ControlMode.translate_from_rpc(rpcControlStatus.control_mode), - - - rpcControlStatus.sysid_primary_control, - - - rpcControlStatus.compid_primary_control, - - - rpcControlStatus.sysid_secondary_control, - - - rpcControlStatus.compid_secondary_control - ) + rpcControlStatus.gimbal_id, + ControlMode.translate_from_rpc(rpcControlStatus.control_mode), + rpcControlStatus.sysid_primary_control, + rpcControlStatus.compid_primary_control, + rpcControlStatus.sysid_secondary_control, + rpcControlStatus.compid_secondary_control, + ) def translate_to_rpc(self, rpcControlStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcControlStatus.gimbal_id = self.gimbal_id - - - - - + rpcControlStatus.control_mode = self.control_mode.translate_to_rpc() - - - - - + rpcControlStatus.sysid_primary_control = self.sysid_primary_control - - - - - + rpcControlStatus.compid_primary_control = self.compid_primary_control - - - - - + rpcControlStatus.sysid_secondary_control = self.sysid_secondary_control - - - - - + rpcControlStatus.compid_secondary_control = self.compid_secondary_control - - - class GimbalResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for gimbal commands. + Possible results returned for gimbal commands. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Command was accepted + SUCCESS + Command was accepted - ERROR - Error occurred sending the command + ERROR + Error occurred sending the command - TIMEOUT - Command timed out + TIMEOUT + Command timed out - UNSUPPORTED - Functionality not supported + UNSUPPORTED + Functionality not supported - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - """ + """ - UNKNOWN = 0 SUCCESS = 1 ERROR = 2 @@ -988,7 +788,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == gimbal_pb2.GimbalResult.RESULT_UNKNOWN: return GimbalResult.Result.UNKNOWN if rpc_enum_value == gimbal_pb2.GimbalResult.RESULT_SUCCESS: @@ -1006,69 +806,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the GimbalResult object """ + def __init__(self, result, result_str): + """Initializes the GimbalResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two GimbalResult are the same """ + """Checks if two GimbalResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # GimbalResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ GimbalResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """GimbalResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"GimbalResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGimbalResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GimbalResult( - - GimbalResult.Result.translate_from_rpc(rpcGimbalResult.result), - - - rpcGimbalResult.result_str - ) + GimbalResult.Result.translate_from_rpc(rpcGimbalResult.result), + rpcGimbalResult.result_str, + ) def translate_to_rpc(self, rpcGimbalResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGimbalResult.result = self.result.translate_to_rpc() - - - - - - rpcGimbalResult.result_str = self.result_str - - - + rpcGimbalResult.result_str = self.result_str class GimbalError(Exception): - """ Raised when a GimbalResult is a fail code """ + """Raised when a GimbalResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -1081,58 +862,58 @@ def __str__(self): class Gimbal(AsyncBase): """ - Provide control over a gimbal. + Provide control over a gimbal. - Generated by dcsdkgen - MAVSDK Gimbal API + Generated by dcsdkgen - MAVSDK Gimbal API """ # Plugin name name = "Gimbal" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = gimbal_pb2_grpc.GimbalServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return GimbalResult.translate_from_rpc(response.gimbal_result) - - async def set_angles(self, gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode): + async def set_angles( + self, gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode + ): """ - Set gimbal roll, pitch and yaw angles. + Set gimbal roll, pitch and yaw angles. - This sets the desired roll, pitch and yaw angles of a gimbal. - Will return when the command is accepted, however, it might - take the gimbal longer to actually be set to the new angles. + This sets the desired roll, pitch and yaw angles of a gimbal. + Will return when the command is accepted, however, it might + take the gimbal longer to actually be set to the new angles. - Note that the roll angle needs to be set to 0 when send_mode is Once. + Note that the roll angle needs to be set to 0 when send_mode is Once. - Parameters - ---------- - gimbal_id : int32_t - Gimbal id to address (0 for all gimbals) + Parameters + ---------- + gimbal_id : int32_t + Gimbal id to address (0 for all gimbals) - roll_deg : float - Roll angle in degrees (negative down on the right) + roll_deg : float + Roll angle in degrees (negative down on the right) - pitch_deg : float - Pitch angle in degrees (negative points down) + pitch_deg : float + Pitch angle in degrees (negative points down) - yaw_deg : float - Yaw angle in degrees (positive is clock-wise, range: -180 to 180 or 0 to 360) + yaw_deg : float + Yaw angle in degrees (positive is clock-wise, range: -180 to 180 or 0 to 360) - gimbal_mode : GimbalMode - Gimbal mode to use + gimbal_mode : GimbalMode + Gimbal mode to use - send_mode : SendMode - Send mode of command/setpoint + send_mode : SendMode + Send mode of command/setpoint - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.SetAnglesRequest() @@ -1140,57 +921,69 @@ async def set_angles(self, gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, request.roll_deg = roll_deg request.pitch_deg = pitch_deg request.yaw_deg = yaw_deg - + request.gimbal_mode = gimbal_mode.translate_to_rpc() - - - + request.send_mode = send_mode.translate_to_rpc() - - + response = await self._stub.SetAngles(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: - raise GimbalError(result, "set_angles()", gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode) - - - async def set_angular_rates(self, gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, gimbal_mode, send_mode): + raise GimbalError( + result, + "set_angles()", + gimbal_id, + roll_deg, + pitch_deg, + yaw_deg, + gimbal_mode, + send_mode, + ) + + async def set_angular_rates( + self, + gimbal_id, + roll_rate_deg_s, + pitch_rate_deg_s, + yaw_rate_deg_s, + gimbal_mode, + send_mode, + ): """ - Set gimbal angular rates. + Set gimbal angular rates. - This sets the desired angular rates around roll, pitch and yaw axes of a gimbal. - Will return when the command is accepted, however, it might - take the gimbal longer to actually reach the angular rate. + This sets the desired angular rates around roll, pitch and yaw axes of a gimbal. + Will return when the command is accepted, however, it might + take the gimbal longer to actually reach the angular rate. - Note that the roll angle needs to be set to 0 when send_mode is Once. + Note that the roll angle needs to be set to 0 when send_mode is Once. - Parameters - ---------- - gimbal_id : int32_t - Gimbal id to address (0 for all gimbals) + Parameters + ---------- + gimbal_id : int32_t + Gimbal id to address (0 for all gimbals) - roll_rate_deg_s : float - Angular rate around roll axis in degrees/second (negative down on the right) + roll_rate_deg_s : float + Angular rate around roll axis in degrees/second (negative down on the right) - pitch_rate_deg_s : float - Angular rate around pitch axis in degrees/second (negative downward) + pitch_rate_deg_s : float + Angular rate around pitch axis in degrees/second (negative downward) - yaw_rate_deg_s : float - Angular rate around yaw axis in degrees/second (positive is clock-wise) + yaw_rate_deg_s : float + Angular rate around yaw axis in degrees/second (positive is clock-wise) - gimbal_mode : GimbalMode - Gimbal mode to use + gimbal_mode : GimbalMode + Gimbal mode to use - send_mode : SendMode - Send mode of command/setpoint + send_mode : SendMode + Send mode of command/setpoint - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.SetAngularRatesRequest() @@ -1198,51 +991,57 @@ async def set_angular_rates(self, gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, request.roll_rate_deg_s = roll_rate_deg_s request.pitch_rate_deg_s = pitch_rate_deg_s request.yaw_rate_deg_s = yaw_rate_deg_s - + request.gimbal_mode = gimbal_mode.translate_to_rpc() - - - + request.send_mode = send_mode.translate_to_rpc() - - + response = await self._stub.SetAngularRates(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: - raise GimbalError(result, "set_angular_rates()", gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, gimbal_mode, send_mode) - - - async def set_roi_location(self, gimbal_id, latitude_deg, longitude_deg, altitude_m): + raise GimbalError( + result, + "set_angular_rates()", + gimbal_id, + roll_rate_deg_s, + pitch_rate_deg_s, + yaw_rate_deg_s, + gimbal_mode, + send_mode, + ) + + async def set_roi_location( + self, gimbal_id, latitude_deg, longitude_deg, altitude_m + ): """ - Set gimbal region of interest (ROI). + Set gimbal region of interest (ROI). - This sets a region of interest that the gimbal will point to. - The gimbal will continue to point to the specified region until it - receives a new command. - The function will return when the command is accepted, however, it might - take the gimbal longer to actually rotate to the ROI. + This sets a region of interest that the gimbal will point to. + The gimbal will continue to point to the specified region until it + receives a new command. + The function will return when the command is accepted, however, it might + take the gimbal longer to actually rotate to the ROI. - Parameters - ---------- - gimbal_id : int32_t - Gimbal id to address (0 for all gimbals) + Parameters + ---------- + gimbal_id : int32_t + Gimbal id to address (0 for all gimbals) - latitude_deg : double - Latitude in degrees + latitude_deg : double + Latitude in degrees - longitude_deg : double - Longitude in degrees + longitude_deg : double + Longitude in degrees - altitude_m : float - Altitude in metres (AMSL) + altitude_m : float + Altitude in metres (AMSL) - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.SetRoiLocationRequest() @@ -1252,95 +1051,95 @@ async def set_roi_location(self, gimbal_id, latitude_deg, longitude_deg, altitud request.altitude_m = altitude_m response = await self._stub.SetRoiLocation(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: - raise GimbalError(result, "set_roi_location()", gimbal_id, latitude_deg, longitude_deg, altitude_m) - + raise GimbalError( + result, + "set_roi_location()", + gimbal_id, + latitude_deg, + longitude_deg, + altitude_m, + ) async def take_control(self, gimbal_id, control_mode): """ - Take control. + Take control. - There can be only two components in control of a gimbal at any given time. - One with "primary" control, and one with "secondary" control. The way the - secondary control is implemented is not specified and hence depends on the - vehicle. + There can be only two components in control of a gimbal at any given time. + One with "primary" control, and one with "secondary" control. The way the + secondary control is implemented is not specified and hence depends on the + vehicle. - Components are expected to be cooperative, which means that they can - override each other and should therefore do it carefully. + Components are expected to be cooperative, which means that they can + override each other and should therefore do it carefully. - Parameters - ---------- - gimbal_id : int32_t - Gimbal id to address (0 for all gimbals) + Parameters + ---------- + gimbal_id : int32_t + Gimbal id to address (0 for all gimbals) - control_mode : ControlMode - Control mode (primary or secondary) + control_mode : ControlMode + Control mode (primary or secondary) - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.TakeControlRequest() request.gimbal_id = gimbal_id - + request.control_mode = control_mode.translate_to_rpc() - - + response = await self._stub.TakeControl(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "take_control()", gimbal_id, control_mode) - async def release_control(self, gimbal_id): """ - Release control. + Release control. - Release control, such that other components can control the gimbal. + Release control, such that other components can control the gimbal. - Parameters - ---------- - gimbal_id : int32_t - Gimbal id to address (0 for all gimbals) + Parameters + ---------- + gimbal_id : int32_t + Gimbal id to address (0 for all gimbals) - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.ReleaseControlRequest() request.gimbal_id = gimbal_id response = await self._stub.ReleaseControl(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "release_control()", gimbal_id) - async def gimbal_list(self): """ - Subscribe to list of gimbals. + Subscribe to list of gimbals. + + This allows to find out what gimbals are connected to the system. + Based on the gimbal ID, we can then address a specific gimbal. - This allows to find out what gimbals are connected to the system. - Based on the gimbal ID, we can then address a specific gimbal. + Yields + ------- + gimbal_list : GimbalList + Gimbal list - Yields - ------- - gimbal_list : GimbalList - Gimbal list - """ request = gimbal_pb2.SubscribeGimbalListRequest() @@ -1348,27 +1147,24 @@ async def gimbal_list(self): try: async for response in gimbal_list_stream: - - - yield GimbalList.translate_from_rpc(response.gimbal_list) finally: gimbal_list_stream.cancel() async def control_status(self): """ - Subscribe to control status updates. + Subscribe to control status updates. + + This allows a component to know if it has primary, secondary or + no control over the gimbal. Also, it gives the system and component ids + of the other components in control (if any). - This allows a component to know if it has primary, secondary or - no control over the gimbal. Also, it gives the system and component ids - of the other components in control (if any). + Yields + ------- + control_status : ControlStatus + Control status - Yields - ------- - control_status : ControlStatus - Control status - """ request = gimbal_pb2.SubscribeControlStatusRequest() @@ -1376,62 +1172,55 @@ async def control_status(self): try: async for response in control_status_stream: - - - yield ControlStatus.translate_from_rpc(response.control_status) finally: control_status_stream.cancel() async def get_control_status(self, gimbal_id): """ - Get control status for specific gimbal. - - Parameters - ---------- - gimbal_id : int32_t - Gimbal ID - - Returns - ------- - control_status : ControlStatus - Control status - - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Get control status for specific gimbal. + + Parameters + ---------- + gimbal_id : int32_t + Gimbal ID + + Returns + ------- + control_status : ControlStatus + Control status + + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.GetControlStatusRequest() - - + request.gimbal_id = gimbal_id - + response = await self._stub.GetControlStatus(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "get_control_status()", gimbal_id) - return ControlStatus.translate_from_rpc(response.control_status) - async def attitude(self): """ - Subscribe to attitude updates. + Subscribe to attitude updates. - This gets you the gimbal's attitude and angular rate. + This gets you the gimbal's attitude and angular rate. + + Yields + ------- + attitude : Attitude + The attitude - Yields - ------- - attitude : Attitude - The attitude - """ request = gimbal_pb2.SubscribeAttitudeRequest() @@ -1439,46 +1228,39 @@ async def attitude(self): try: async for response in attitude_stream: - - - yield Attitude.translate_from_rpc(response.attitude) finally: attitude_stream.cancel() async def get_attitude(self, gimbal_id): """ - Get attitude for specific gimbal. - - Parameters - ---------- - gimbal_id : int32_t - Gimbal ID - - Returns - ------- - attitude : Attitude - The attitude - - Raises - ------ - GimbalError - If the request fails. The error contains the reason for the failure. + Get attitude for specific gimbal. + + Parameters + ---------- + gimbal_id : int32_t + Gimbal ID + + Returns + ------- + attitude : Attitude + The attitude + + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. """ request = gimbal_pb2.GetAttitudeRequest() - - + request.gimbal_id = gimbal_id - + response = await self._stub.GetAttitude(request) - result = self._extract_result(response) if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "get_attitude()", gimbal_id) - return Attitude.translate_from_rpc(response.attitude) - \ No newline at end of file diff --git a/mavsdk/gimbal_pb2.py b/mavsdk/gimbal_pb2.py index 772a1e54..426efbdd 100644 --- a/mavsdk/gimbal_pb2.py +++ b/mavsdk/gimbal_pb2.py @@ -4,18 +4,15 @@ # source: gimbal/gimbal.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'gimbal/gimbal.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "gimbal/gimbal.proto" ) # @@protoc_insertion_point(imports) @@ -25,106 +22,146 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13gimbal/gimbal.proto\x12\x11mavsdk.rpc.gimbal\x1a\x14mavsdk_options.proto\"\xbf\x01\n\x10SetAnglesRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x10\n\x08roll_deg\x18\x02 \x01(\x02\x12\x11\n\tpitch_deg\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\x12\x32\n\x0bgimbal_mode\x18\x05 \x01(\x0e\x32\x1d.mavsdk.rpc.gimbal.GimbalMode\x12.\n\tsend_mode\x18\x06 \x01(\x0e\x32\x1b.mavsdk.rpc.gimbal.SendMode\"K\n\x11SetAnglesResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"\xda\x01\n\x16SetAngularRatesRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x17\n\x0froll_rate_deg_s\x18\x02 \x01(\x02\x12\x18\n\x10pitch_rate_deg_s\x18\x03 \x01(\x02\x12\x16\n\x0eyaw_rate_deg_s\x18\x04 \x01(\x02\x12\x32\n\x0bgimbal_mode\x18\x05 \x01(\x0e\x32\x1d.mavsdk.rpc.gimbal.GimbalMode\x12.\n\tsend_mode\x18\x06 \x01(\x0e\x32\x1b.mavsdk.rpc.gimbal.SendMode\"Q\n\x17SetAngularRatesResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"k\n\x15SetRoiLocationRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12\x12\n\naltitude_m\x18\x04 \x01(\x02\"P\n\x16SetRoiLocationResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"]\n\x12TakeControlRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x34\n\x0c\x63ontrol_mode\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.gimbal.ControlMode\"M\n\x13TakeControlResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"*\n\x15ReleaseControlRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\"P\n\x16ReleaseControlResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"\x1f\n\x1dSubscribeControlStatusRequest\"Q\n\x15\x43ontrolStatusResponse\x12\x38\n\x0e\x63ontrol_status\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.gimbal.ControlStatus\",\n\x17GetControlStatusRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\"\x8c\x01\n\x18GetControlStatusResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\x12\x38\n\x0e\x63ontrol_status\x18\x02 \x01(\x0b\x32 .mavsdk.rpc.gimbal.ControlStatus\"\\\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"]\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xdf\x02\n\x08\x41ttitude\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12:\n\x13\x65uler_angle_forward\x18\x02 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.EulerAngle\x12\x39\n\x12quaternion_forward\x18\x03 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.Quaternion\x12\x38\n\x11\x65uler_angle_north\x18\x04 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.EulerAngle\x12\x37\n\x10quaternion_north\x18\x05 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.Quaternion\x12@\n\x10\x61ngular_velocity\x18\x06 \x01(\x0b\x32&.mavsdk.rpc.gimbal.AngularVelocityBody\x12\x14\n\x0ctimestamp_us\x18\x07 \x01(\x04\"\x1a\n\x18SubscribeAttitudeRequest\"A\n\x10\x41ttitudeResponse\x12-\n\x08\x61ttitude\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.gimbal.Attitude\"\'\n\x12GetAttitudeRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\"|\n\x13GetAttitudeResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\x12-\n\x08\x61ttitude\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.gimbal.Attitude\"\x1c\n\x1aSubscribeGimbalListRequest\"H\n\x12GimbalListResponse\x12\x32\n\x0bgimbal_list\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.GimbalList\"\x9c\x01\n\nGimbalItem\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nmodel_name\x18\x03 \x01(\t\x12\x13\n\x0b\x63ustom_name\x18\x04 \x01(\t\x12#\n\x1bgimbal_manager_component_id\x18\x05 \x01(\x05\x12\x18\n\x10gimbal_device_id\x18\x06 \x01(\x05\"<\n\nGimbalList\x12.\n\x07gimbals\x18\x01 \x03(\x0b\x32\x1d.mavsdk.rpc.gimbal.GimbalItem\"\xda\x01\n\rControlStatus\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x34\n\x0c\x63ontrol_mode\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.gimbal.ControlMode\x12\x1d\n\x15sysid_primary_control\x18\x03 \x01(\x05\x12\x1e\n\x16\x63ompid_primary_control\x18\x04 \x01(\x05\x12\x1f\n\x17sysid_secondary_control\x18\x05 \x01(\x05\x12 \n\x18\x63ompid_secondary_control\x18\x06 \x01(\x05\"\xfe\x01\n\x0cGimbalResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.gimbal.GimbalResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xa1\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\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x04\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x05\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x06*B\n\nGimbalMode\x12\x1a\n\x16GIMBAL_MODE_YAW_FOLLOW\x10\x00\x12\x18\n\x14GIMBAL_MODE_YAW_LOCK\x10\x01*Z\n\x0b\x43ontrolMode\x12\x15\n\x11\x43ONTROL_MODE_NONE\x10\x00\x12\x18\n\x14\x43ONTROL_MODE_PRIMARY\x10\x01\x12\x1a\n\x16\x43ONTROL_MODE_SECONDARY\x10\x02*4\n\x08SendMode\x12\x12\n\x0eSEND_MODE_ONCE\x10\x00\x12\x14\n\x10SEND_MODE_STREAM\x10\x01\x32\xbc\x08\n\rGimbalService\x12X\n\tSetAngles\x12#.mavsdk.rpc.gimbal.SetAnglesRequest\x1a$.mavsdk.rpc.gimbal.SetAnglesResponse\"\x00\x12j\n\x0fSetAngularRates\x12).mavsdk.rpc.gimbal.SetAngularRatesRequest\x1a*.mavsdk.rpc.gimbal.SetAngularRatesResponse\"\x00\x12g\n\x0eSetRoiLocation\x12(.mavsdk.rpc.gimbal.SetRoiLocationRequest\x1a).mavsdk.rpc.gimbal.SetRoiLocationResponse\"\x00\x12^\n\x0bTakeControl\x12%.mavsdk.rpc.gimbal.TakeControlRequest\x1a&.mavsdk.rpc.gimbal.TakeControlResponse\"\x00\x12g\n\x0eReleaseControl\x12(.mavsdk.rpc.gimbal.ReleaseControlRequest\x1a).mavsdk.rpc.gimbal.ReleaseControlResponse\"\x00\x12o\n\x13SubscribeGimbalList\x12-.mavsdk.rpc.gimbal.SubscribeGimbalListRequest\x1a%.mavsdk.rpc.gimbal.GimbalListResponse\"\x00\x30\x01\x12|\n\x16SubscribeControlStatus\x12\x30.mavsdk.rpc.gimbal.SubscribeControlStatusRequest\x1a(.mavsdk.rpc.gimbal.ControlStatusResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12q\n\x10GetControlStatus\x12*.mavsdk.rpc.gimbal.GetControlStatusRequest\x1a+.mavsdk.rpc.gimbal.GetControlStatusResponse\"\x04\x80\xb5\x18\x01\x12m\n\x11SubscribeAttitude\x12+.mavsdk.rpc.gimbal.SubscribeAttitudeRequest\x1a#.mavsdk.rpc.gimbal.AttitudeResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x62\n\x0bGetAttitude\x12%.mavsdk.rpc.gimbal.GetAttitudeRequest\x1a&.mavsdk.rpc.gimbal.GetAttitudeResponse\"\x04\x80\xb5\x18\x01\x42\x1f\n\x10io.mavsdk.gimbalB\x0bGimbalProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x13gimbal/gimbal.proto\x12\x11mavsdk.rpc.gimbal\x1a\x14mavsdk_options.proto"\xbf\x01\n\x10SetAnglesRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x10\n\x08roll_deg\x18\x02 \x01(\x02\x12\x11\n\tpitch_deg\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\x12\x32\n\x0bgimbal_mode\x18\x05 \x01(\x0e\x32\x1d.mavsdk.rpc.gimbal.GimbalMode\x12.\n\tsend_mode\x18\x06 \x01(\x0e\x32\x1b.mavsdk.rpc.gimbal.SendMode"K\n\x11SetAnglesResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult"\xda\x01\n\x16SetAngularRatesRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x17\n\x0froll_rate_deg_s\x18\x02 \x01(\x02\x12\x18\n\x10pitch_rate_deg_s\x18\x03 \x01(\x02\x12\x16\n\x0eyaw_rate_deg_s\x18\x04 \x01(\x02\x12\x32\n\x0bgimbal_mode\x18\x05 \x01(\x0e\x32\x1d.mavsdk.rpc.gimbal.GimbalMode\x12.\n\tsend_mode\x18\x06 \x01(\x0e\x32\x1b.mavsdk.rpc.gimbal.SendMode"Q\n\x17SetAngularRatesResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult"k\n\x15SetRoiLocationRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12\x12\n\naltitude_m\x18\x04 \x01(\x02"P\n\x16SetRoiLocationResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult"]\n\x12TakeControlRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x34\n\x0c\x63ontrol_mode\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.gimbal.ControlMode"M\n\x13TakeControlResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult"*\n\x15ReleaseControlRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05"P\n\x16ReleaseControlResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult"\x1f\n\x1dSubscribeControlStatusRequest"Q\n\x15\x43ontrolStatusResponse\x12\x38\n\x0e\x63ontrol_status\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.gimbal.ControlStatus",\n\x17GetControlStatusRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05"\x8c\x01\n\x18GetControlStatusResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\x12\x38\n\x0e\x63ontrol_status\x18\x02 \x01(\x0b\x32 .mavsdk.rpc.gimbal.ControlStatus"\\\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"]\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xdf\x02\n\x08\x41ttitude\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12:\n\x13\x65uler_angle_forward\x18\x02 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.EulerAngle\x12\x39\n\x12quaternion_forward\x18\x03 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.Quaternion\x12\x38\n\x11\x65uler_angle_north\x18\x04 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.EulerAngle\x12\x37\n\x10quaternion_north\x18\x05 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.Quaternion\x12@\n\x10\x61ngular_velocity\x18\x06 \x01(\x0b\x32&.mavsdk.rpc.gimbal.AngularVelocityBody\x12\x14\n\x0ctimestamp_us\x18\x07 \x01(\x04"\x1a\n\x18SubscribeAttitudeRequest"A\n\x10\x41ttitudeResponse\x12-\n\x08\x61ttitude\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.gimbal.Attitude"\'\n\x12GetAttitudeRequest\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05"|\n\x13GetAttitudeResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\x12-\n\x08\x61ttitude\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.gimbal.Attitude"\x1c\n\x1aSubscribeGimbalListRequest"H\n\x12GimbalListResponse\x12\x32\n\x0bgimbal_list\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.gimbal.GimbalList"\x9c\x01\n\nGimbalItem\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nmodel_name\x18\x03 \x01(\t\x12\x13\n\x0b\x63ustom_name\x18\x04 \x01(\t\x12#\n\x1bgimbal_manager_component_id\x18\x05 \x01(\x05\x12\x18\n\x10gimbal_device_id\x18\x06 \x01(\x05"<\n\nGimbalList\x12.\n\x07gimbals\x18\x01 \x03(\x0b\x32\x1d.mavsdk.rpc.gimbal.GimbalItem"\xda\x01\n\rControlStatus\x12\x11\n\tgimbal_id\x18\x01 \x01(\x05\x12\x34\n\x0c\x63ontrol_mode\x18\x02 \x01(\x0e\x32\x1e.mavsdk.rpc.gimbal.ControlMode\x12\x1d\n\x15sysid_primary_control\x18\x03 \x01(\x05\x12\x1e\n\x16\x63ompid_primary_control\x18\x04 \x01(\x05\x12\x1f\n\x17sysid_secondary_control\x18\x05 \x01(\x05\x12 \n\x18\x63ompid_secondary_control\x18\x06 \x01(\x05"\xfe\x01\n\x0cGimbalResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.gimbal.GimbalResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xa1\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\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x04\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x05\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x06*B\n\nGimbalMode\x12\x1a\n\x16GIMBAL_MODE_YAW_FOLLOW\x10\x00\x12\x18\n\x14GIMBAL_MODE_YAW_LOCK\x10\x01*Z\n\x0b\x43ontrolMode\x12\x15\n\x11\x43ONTROL_MODE_NONE\x10\x00\x12\x18\n\x14\x43ONTROL_MODE_PRIMARY\x10\x01\x12\x1a\n\x16\x43ONTROL_MODE_SECONDARY\x10\x02*4\n\x08SendMode\x12\x12\n\x0eSEND_MODE_ONCE\x10\x00\x12\x14\n\x10SEND_MODE_STREAM\x10\x01\x32\xbc\x08\n\rGimbalService\x12X\n\tSetAngles\x12#.mavsdk.rpc.gimbal.SetAnglesRequest\x1a$.mavsdk.rpc.gimbal.SetAnglesResponse"\x00\x12j\n\x0fSetAngularRates\x12).mavsdk.rpc.gimbal.SetAngularRatesRequest\x1a*.mavsdk.rpc.gimbal.SetAngularRatesResponse"\x00\x12g\n\x0eSetRoiLocation\x12(.mavsdk.rpc.gimbal.SetRoiLocationRequest\x1a).mavsdk.rpc.gimbal.SetRoiLocationResponse"\x00\x12^\n\x0bTakeControl\x12%.mavsdk.rpc.gimbal.TakeControlRequest\x1a&.mavsdk.rpc.gimbal.TakeControlResponse"\x00\x12g\n\x0eReleaseControl\x12(.mavsdk.rpc.gimbal.ReleaseControlRequest\x1a).mavsdk.rpc.gimbal.ReleaseControlResponse"\x00\x12o\n\x13SubscribeGimbalList\x12-.mavsdk.rpc.gimbal.SubscribeGimbalListRequest\x1a%.mavsdk.rpc.gimbal.GimbalListResponse"\x00\x30\x01\x12|\n\x16SubscribeControlStatus\x12\x30.mavsdk.rpc.gimbal.SubscribeControlStatusRequest\x1a(.mavsdk.rpc.gimbal.ControlStatusResponse"\x04\x80\xb5\x18\x00\x30\x01\x12q\n\x10GetControlStatus\x12*.mavsdk.rpc.gimbal.GetControlStatusRequest\x1a+.mavsdk.rpc.gimbal.GetControlStatusResponse"\x04\x80\xb5\x18\x01\x12m\n\x11SubscribeAttitude\x12+.mavsdk.rpc.gimbal.SubscribeAttitudeRequest\x1a#.mavsdk.rpc.gimbal.AttitudeResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x62\n\x0bGetAttitude\x12%.mavsdk.rpc.gimbal.GetAttitudeRequest\x1a&.mavsdk.rpc.gimbal.GetAttitudeResponse"\x04\x80\xb5\x18\x01\x42\x1f\n\x10io.mavsdk.gimbalB\x0bGimbalProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'gimbal.gimbal_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "gimbal.gimbal_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\020io.mavsdk.gimbalB\013GimbalProto' - _globals['_QUATERNION'].fields_by_name['w']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['w']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['x']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['x']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['y']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['y']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['z']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['z']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['roll_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['roll_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['pitch_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['pitch_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['yaw_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['yaw_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['roll_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['roll_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['pitch_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['pitch_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['yaw_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['yaw_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_GIMBALSERVICE'].methods_by_name['SubscribeControlStatus']._loaded_options = None - _globals['_GIMBALSERVICE'].methods_by_name['SubscribeControlStatus']._serialized_options = b'\200\265\030\000' - _globals['_GIMBALSERVICE'].methods_by_name['GetControlStatus']._loaded_options = None - _globals['_GIMBALSERVICE'].methods_by_name['GetControlStatus']._serialized_options = b'\200\265\030\001' - _globals['_GIMBALSERVICE'].methods_by_name['SubscribeAttitude']._loaded_options = None - _globals['_GIMBALSERVICE'].methods_by_name['SubscribeAttitude']._serialized_options = b'\200\265\030\000' - _globals['_GIMBALSERVICE'].methods_by_name['GetAttitude']._loaded_options = None - _globals['_GIMBALSERVICE'].methods_by_name['GetAttitude']._serialized_options = b'\200\265\030\001' - _globals['_GIMBALMODE']._serialized_start=3153 - _globals['_GIMBALMODE']._serialized_end=3219 - _globals['_CONTROLMODE']._serialized_start=3221 - _globals['_CONTROLMODE']._serialized_end=3311 - _globals['_SENDMODE']._serialized_start=3313 - _globals['_SENDMODE']._serialized_end=3365 - _globals['_SETANGLESREQUEST']._serialized_start=65 - _globals['_SETANGLESREQUEST']._serialized_end=256 - _globals['_SETANGLESRESPONSE']._serialized_start=258 - _globals['_SETANGLESRESPONSE']._serialized_end=333 - _globals['_SETANGULARRATESREQUEST']._serialized_start=336 - _globals['_SETANGULARRATESREQUEST']._serialized_end=554 - _globals['_SETANGULARRATESRESPONSE']._serialized_start=556 - _globals['_SETANGULARRATESRESPONSE']._serialized_end=637 - _globals['_SETROILOCATIONREQUEST']._serialized_start=639 - _globals['_SETROILOCATIONREQUEST']._serialized_end=746 - _globals['_SETROILOCATIONRESPONSE']._serialized_start=748 - _globals['_SETROILOCATIONRESPONSE']._serialized_end=828 - _globals['_TAKECONTROLREQUEST']._serialized_start=830 - _globals['_TAKECONTROLREQUEST']._serialized_end=923 - _globals['_TAKECONTROLRESPONSE']._serialized_start=925 - _globals['_TAKECONTROLRESPONSE']._serialized_end=1002 - _globals['_RELEASECONTROLREQUEST']._serialized_start=1004 - _globals['_RELEASECONTROLREQUEST']._serialized_end=1046 - _globals['_RELEASECONTROLRESPONSE']._serialized_start=1048 - _globals['_RELEASECONTROLRESPONSE']._serialized_end=1128 - _globals['_SUBSCRIBECONTROLSTATUSREQUEST']._serialized_start=1130 - _globals['_SUBSCRIBECONTROLSTATUSREQUEST']._serialized_end=1161 - _globals['_CONTROLSTATUSRESPONSE']._serialized_start=1163 - _globals['_CONTROLSTATUSRESPONSE']._serialized_end=1244 - _globals['_GETCONTROLSTATUSREQUEST']._serialized_start=1246 - _globals['_GETCONTROLSTATUSREQUEST']._serialized_end=1290 - _globals['_GETCONTROLSTATUSRESPONSE']._serialized_start=1293 - _globals['_GETCONTROLSTATUSRESPONSE']._serialized_end=1433 - _globals['_QUATERNION']._serialized_start=1435 - _globals['_QUATERNION']._serialized_end=1527 - _globals['_EULERANGLE']._serialized_start=1529 - _globals['_EULERANGLE']._serialized_end=1622 - _globals['_ANGULARVELOCITYBODY']._serialized_start=1624 - _globals['_ANGULARVELOCITYBODY']._serialized_end=1732 - _globals['_ATTITUDE']._serialized_start=1735 - _globals['_ATTITUDE']._serialized_end=2086 - _globals['_SUBSCRIBEATTITUDEREQUEST']._serialized_start=2088 - _globals['_SUBSCRIBEATTITUDEREQUEST']._serialized_end=2114 - _globals['_ATTITUDERESPONSE']._serialized_start=2116 - _globals['_ATTITUDERESPONSE']._serialized_end=2181 - _globals['_GETATTITUDEREQUEST']._serialized_start=2183 - _globals['_GETATTITUDEREQUEST']._serialized_end=2222 - _globals['_GETATTITUDERESPONSE']._serialized_start=2224 - _globals['_GETATTITUDERESPONSE']._serialized_end=2348 - _globals['_SUBSCRIBEGIMBALLISTREQUEST']._serialized_start=2350 - _globals['_SUBSCRIBEGIMBALLISTREQUEST']._serialized_end=2378 - _globals['_GIMBALLISTRESPONSE']._serialized_start=2380 - _globals['_GIMBALLISTRESPONSE']._serialized_end=2452 - _globals['_GIMBALITEM']._serialized_start=2455 - _globals['_GIMBALITEM']._serialized_end=2611 - _globals['_GIMBALLIST']._serialized_start=2613 - _globals['_GIMBALLIST']._serialized_end=2673 - _globals['_CONTROLSTATUS']._serialized_start=2676 - _globals['_CONTROLSTATUS']._serialized_end=2894 - _globals['_GIMBALRESULT']._serialized_start=2897 - _globals['_GIMBALRESULT']._serialized_end=3151 - _globals['_GIMBALRESULT_RESULT']._serialized_start=2990 - _globals['_GIMBALRESULT_RESULT']._serialized_end=3151 - _globals['_GIMBALSERVICE']._serialized_start=3368 - _globals['_GIMBALSERVICE']._serialized_end=4452 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\020io.mavsdk.gimbalB\013GimbalProto" + _globals["_QUATERNION"].fields_by_name["w"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "w" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["x"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "x" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["y"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "y" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["z"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "z" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["roll_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "roll_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["pitch_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "pitch_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["yaw_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "yaw_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name["roll_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "roll_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "pitch_rad_s" + ]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "pitch_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name["yaw_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "yaw_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GIMBALSERVICE"].methods_by_name[ + "SubscribeControlStatus" + ]._loaded_options = None + _globals["_GIMBALSERVICE"].methods_by_name[ + "SubscribeControlStatus" + ]._serialized_options = b"\200\265\030\000" + _globals["_GIMBALSERVICE"].methods_by_name[ + "GetControlStatus" + ]._loaded_options = None + _globals["_GIMBALSERVICE"].methods_by_name[ + "GetControlStatus" + ]._serialized_options = b"\200\265\030\001" + _globals["_GIMBALSERVICE"].methods_by_name[ + "SubscribeAttitude" + ]._loaded_options = None + _globals["_GIMBALSERVICE"].methods_by_name[ + "SubscribeAttitude" + ]._serialized_options = b"\200\265\030\000" + _globals["_GIMBALSERVICE"].methods_by_name["GetAttitude"]._loaded_options = None + _globals["_GIMBALSERVICE"].methods_by_name[ + "GetAttitude" + ]._serialized_options = b"\200\265\030\001" + _globals["_GIMBALMODE"]._serialized_start = 3153 + _globals["_GIMBALMODE"]._serialized_end = 3219 + _globals["_CONTROLMODE"]._serialized_start = 3221 + _globals["_CONTROLMODE"]._serialized_end = 3311 + _globals["_SENDMODE"]._serialized_start = 3313 + _globals["_SENDMODE"]._serialized_end = 3365 + _globals["_SETANGLESREQUEST"]._serialized_start = 65 + _globals["_SETANGLESREQUEST"]._serialized_end = 256 + _globals["_SETANGLESRESPONSE"]._serialized_start = 258 + _globals["_SETANGLESRESPONSE"]._serialized_end = 333 + _globals["_SETANGULARRATESREQUEST"]._serialized_start = 336 + _globals["_SETANGULARRATESREQUEST"]._serialized_end = 554 + _globals["_SETANGULARRATESRESPONSE"]._serialized_start = 556 + _globals["_SETANGULARRATESRESPONSE"]._serialized_end = 637 + _globals["_SETROILOCATIONREQUEST"]._serialized_start = 639 + _globals["_SETROILOCATIONREQUEST"]._serialized_end = 746 + _globals["_SETROILOCATIONRESPONSE"]._serialized_start = 748 + _globals["_SETROILOCATIONRESPONSE"]._serialized_end = 828 + _globals["_TAKECONTROLREQUEST"]._serialized_start = 830 + _globals["_TAKECONTROLREQUEST"]._serialized_end = 923 + _globals["_TAKECONTROLRESPONSE"]._serialized_start = 925 + _globals["_TAKECONTROLRESPONSE"]._serialized_end = 1002 + _globals["_RELEASECONTROLREQUEST"]._serialized_start = 1004 + _globals["_RELEASECONTROLREQUEST"]._serialized_end = 1046 + _globals["_RELEASECONTROLRESPONSE"]._serialized_start = 1048 + _globals["_RELEASECONTROLRESPONSE"]._serialized_end = 1128 + _globals["_SUBSCRIBECONTROLSTATUSREQUEST"]._serialized_start = 1130 + _globals["_SUBSCRIBECONTROLSTATUSREQUEST"]._serialized_end = 1161 + _globals["_CONTROLSTATUSRESPONSE"]._serialized_start = 1163 + _globals["_CONTROLSTATUSRESPONSE"]._serialized_end = 1244 + _globals["_GETCONTROLSTATUSREQUEST"]._serialized_start = 1246 + _globals["_GETCONTROLSTATUSREQUEST"]._serialized_end = 1290 + _globals["_GETCONTROLSTATUSRESPONSE"]._serialized_start = 1293 + _globals["_GETCONTROLSTATUSRESPONSE"]._serialized_end = 1433 + _globals["_QUATERNION"]._serialized_start = 1435 + _globals["_QUATERNION"]._serialized_end = 1527 + _globals["_EULERANGLE"]._serialized_start = 1529 + _globals["_EULERANGLE"]._serialized_end = 1622 + _globals["_ANGULARVELOCITYBODY"]._serialized_start = 1624 + _globals["_ANGULARVELOCITYBODY"]._serialized_end = 1732 + _globals["_ATTITUDE"]._serialized_start = 1735 + _globals["_ATTITUDE"]._serialized_end = 2086 + _globals["_SUBSCRIBEATTITUDEREQUEST"]._serialized_start = 2088 + _globals["_SUBSCRIBEATTITUDEREQUEST"]._serialized_end = 2114 + _globals["_ATTITUDERESPONSE"]._serialized_start = 2116 + _globals["_ATTITUDERESPONSE"]._serialized_end = 2181 + _globals["_GETATTITUDEREQUEST"]._serialized_start = 2183 + _globals["_GETATTITUDEREQUEST"]._serialized_end = 2222 + _globals["_GETATTITUDERESPONSE"]._serialized_start = 2224 + _globals["_GETATTITUDERESPONSE"]._serialized_end = 2348 + _globals["_SUBSCRIBEGIMBALLISTREQUEST"]._serialized_start = 2350 + _globals["_SUBSCRIBEGIMBALLISTREQUEST"]._serialized_end = 2378 + _globals["_GIMBALLISTRESPONSE"]._serialized_start = 2380 + _globals["_GIMBALLISTRESPONSE"]._serialized_end = 2452 + _globals["_GIMBALITEM"]._serialized_start = 2455 + _globals["_GIMBALITEM"]._serialized_end = 2611 + _globals["_GIMBALLIST"]._serialized_start = 2613 + _globals["_GIMBALLIST"]._serialized_end = 2673 + _globals["_CONTROLSTATUS"]._serialized_start = 2676 + _globals["_CONTROLSTATUS"]._serialized_end = 2894 + _globals["_GIMBALRESULT"]._serialized_start = 2897 + _globals["_GIMBALRESULT"]._serialized_end = 3151 + _globals["_GIMBALRESULT_RESULT"]._serialized_start = 2990 + _globals["_GIMBALRESULT_RESULT"]._serialized_end = 3151 + _globals["_GIMBALSERVICE"]._serialized_start = 3368 + _globals["_GIMBALSERVICE"]._serialized_end = 4452 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/gimbal_pb2_grpc.py b/mavsdk/gimbal_pb2_grpc.py index 96bf485d..2d9e05d6 100644 --- a/mavsdk/gimbal_pb2_grpc.py +++ b/mavsdk/gimbal_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import gimbal_pb2 as gimbal_dot_gimbal__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in gimbal/gimbal_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in gimbal/gimbal_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class GimbalServiceStub(object): - """Provide control over a gimbal. - """ + """Provide control over a gimbal.""" def __init__(self, channel): """Constructor. @@ -36,60 +39,69 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetAngles = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/SetAngles', - request_serializer=gimbal_dot_gimbal__pb2.SetAnglesRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.SetAnglesResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/SetAngles", + request_serializer=gimbal_dot_gimbal__pb2.SetAnglesRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.SetAnglesResponse.FromString, + _registered_method=True, + ) self.SetAngularRates = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/SetAngularRates', - request_serializer=gimbal_dot_gimbal__pb2.SetAngularRatesRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.SetAngularRatesResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/SetAngularRates", + request_serializer=gimbal_dot_gimbal__pb2.SetAngularRatesRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.SetAngularRatesResponse.FromString, + _registered_method=True, + ) self.SetRoiLocation = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/SetRoiLocation', - request_serializer=gimbal_dot_gimbal__pb2.SetRoiLocationRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.SetRoiLocationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/SetRoiLocation", + request_serializer=gimbal_dot_gimbal__pb2.SetRoiLocationRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.SetRoiLocationResponse.FromString, + _registered_method=True, + ) self.TakeControl = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/TakeControl', - request_serializer=gimbal_dot_gimbal__pb2.TakeControlRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.TakeControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/TakeControl", + request_serializer=gimbal_dot_gimbal__pb2.TakeControlRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.TakeControlResponse.FromString, + _registered_method=True, + ) self.ReleaseControl = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/ReleaseControl', - request_serializer=gimbal_dot_gimbal__pb2.ReleaseControlRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.ReleaseControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/ReleaseControl", + request_serializer=gimbal_dot_gimbal__pb2.ReleaseControlRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.ReleaseControlResponse.FromString, + _registered_method=True, + ) self.SubscribeGimbalList = channel.unary_stream( - '/mavsdk.rpc.gimbal.GimbalService/SubscribeGimbalList', - request_serializer=gimbal_dot_gimbal__pb2.SubscribeGimbalListRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.GimbalListResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/SubscribeGimbalList", + request_serializer=gimbal_dot_gimbal__pb2.SubscribeGimbalListRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.GimbalListResponse.FromString, + _registered_method=True, + ) self.SubscribeControlStatus = channel.unary_stream( - '/mavsdk.rpc.gimbal.GimbalService/SubscribeControlStatus', - request_serializer=gimbal_dot_gimbal__pb2.SubscribeControlStatusRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.ControlStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/SubscribeControlStatus", + request_serializer=gimbal_dot_gimbal__pb2.SubscribeControlStatusRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.ControlStatusResponse.FromString, + _registered_method=True, + ) self.GetControlStatus = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/GetControlStatus', - request_serializer=gimbal_dot_gimbal__pb2.GetControlStatusRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.GetControlStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/GetControlStatus", + request_serializer=gimbal_dot_gimbal__pb2.GetControlStatusRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.GetControlStatusResponse.FromString, + _registered_method=True, + ) self.SubscribeAttitude = channel.unary_stream( - '/mavsdk.rpc.gimbal.GimbalService/SubscribeAttitude', - request_serializer=gimbal_dot_gimbal__pb2.SubscribeAttitudeRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.AttitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/SubscribeAttitude", + request_serializer=gimbal_dot_gimbal__pb2.SubscribeAttitudeRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.AttitudeResponse.FromString, + _registered_method=True, + ) self.GetAttitude = channel.unary_unary( - '/mavsdk.rpc.gimbal.GimbalService/GetAttitude', - request_serializer=gimbal_dot_gimbal__pb2.GetAttitudeRequest.SerializeToString, - response_deserializer=gimbal_dot_gimbal__pb2.GetAttitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gimbal.GimbalService/GetAttitude", + request_serializer=gimbal_dot_gimbal__pb2.GetAttitudeRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.GetAttitudeResponse.FromString, + _registered_method=True, + ) class GimbalServiceServicer(object): - """Provide control over a gimbal. - """ + """Provide control over a gimbal.""" def SetAngles(self, request, context): """ @@ -102,8 +114,8 @@ def SetAngles(self, request, context): Note that the roll angle needs to be set to 0 when send_mode is Once. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAngularRates(self, request, context): """ @@ -116,8 +128,8 @@ def SetAngularRates(self, request, context): Note that the roll angle needs to be set to 0 when send_mode is Once. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRoiLocation(self, request, context): """ @@ -130,8 +142,8 @@ def SetRoiLocation(self, request, context): take the gimbal longer to actually rotate to the ROI. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def TakeControl(self, request, context): """ @@ -146,8 +158,8 @@ def TakeControl(self, request, context): override each other and should therefore do it carefully. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ReleaseControl(self, request, context): """ @@ -156,8 +168,8 @@ def ReleaseControl(self, request, context): Release control, such that other components can control the gimbal. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeGimbalList(self, request, context): """ @@ -167,8 +179,8 @@ def SubscribeGimbalList(self, request, context): Based on the gimbal ID, we can then address a specific gimbal. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeControlStatus(self, request, context): """ @@ -179,16 +191,16 @@ def SubscribeControlStatus(self, request, context): of the other components in control (if any). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetControlStatus(self, request, context): """ Get control status for specific gimbal. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeAttitude(self, request, context): """ @@ -197,97 +209,101 @@ def SubscribeAttitude(self, request, context): This gets you the gimbal's attitude and angular rate. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetAttitude(self, request, context): """ Get attitude for specific gimbal. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_GimbalServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetAngles': grpc.unary_unary_rpc_method_handler( - servicer.SetAngles, - request_deserializer=gimbal_dot_gimbal__pb2.SetAnglesRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.SetAnglesResponse.SerializeToString, - ), - 'SetAngularRates': grpc.unary_unary_rpc_method_handler( - servicer.SetAngularRates, - request_deserializer=gimbal_dot_gimbal__pb2.SetAngularRatesRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.SetAngularRatesResponse.SerializeToString, - ), - 'SetRoiLocation': grpc.unary_unary_rpc_method_handler( - servicer.SetRoiLocation, - request_deserializer=gimbal_dot_gimbal__pb2.SetRoiLocationRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.SetRoiLocationResponse.SerializeToString, - ), - 'TakeControl': grpc.unary_unary_rpc_method_handler( - servicer.TakeControl, - request_deserializer=gimbal_dot_gimbal__pb2.TakeControlRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.TakeControlResponse.SerializeToString, - ), - 'ReleaseControl': grpc.unary_unary_rpc_method_handler( - servicer.ReleaseControl, - request_deserializer=gimbal_dot_gimbal__pb2.ReleaseControlRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.ReleaseControlResponse.SerializeToString, - ), - 'SubscribeGimbalList': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeGimbalList, - request_deserializer=gimbal_dot_gimbal__pb2.SubscribeGimbalListRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.GimbalListResponse.SerializeToString, - ), - 'SubscribeControlStatus': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeControlStatus, - request_deserializer=gimbal_dot_gimbal__pb2.SubscribeControlStatusRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.ControlStatusResponse.SerializeToString, - ), - 'GetControlStatus': grpc.unary_unary_rpc_method_handler( - servicer.GetControlStatus, - request_deserializer=gimbal_dot_gimbal__pb2.GetControlStatusRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.GetControlStatusResponse.SerializeToString, - ), - 'SubscribeAttitude': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeAttitude, - request_deserializer=gimbal_dot_gimbal__pb2.SubscribeAttitudeRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.AttitudeResponse.SerializeToString, - ), - 'GetAttitude': grpc.unary_unary_rpc_method_handler( - servicer.GetAttitude, - request_deserializer=gimbal_dot_gimbal__pb2.GetAttitudeRequest.FromString, - response_serializer=gimbal_dot_gimbal__pb2.GetAttitudeResponse.SerializeToString, - ), + "SetAngles": grpc.unary_unary_rpc_method_handler( + servicer.SetAngles, + request_deserializer=gimbal_dot_gimbal__pb2.SetAnglesRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.SetAnglesResponse.SerializeToString, + ), + "SetAngularRates": grpc.unary_unary_rpc_method_handler( + servicer.SetAngularRates, + request_deserializer=gimbal_dot_gimbal__pb2.SetAngularRatesRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.SetAngularRatesResponse.SerializeToString, + ), + "SetRoiLocation": grpc.unary_unary_rpc_method_handler( + servicer.SetRoiLocation, + request_deserializer=gimbal_dot_gimbal__pb2.SetRoiLocationRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.SetRoiLocationResponse.SerializeToString, + ), + "TakeControl": grpc.unary_unary_rpc_method_handler( + servicer.TakeControl, + request_deserializer=gimbal_dot_gimbal__pb2.TakeControlRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.TakeControlResponse.SerializeToString, + ), + "ReleaseControl": grpc.unary_unary_rpc_method_handler( + servicer.ReleaseControl, + request_deserializer=gimbal_dot_gimbal__pb2.ReleaseControlRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.ReleaseControlResponse.SerializeToString, + ), + "SubscribeGimbalList": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeGimbalList, + request_deserializer=gimbal_dot_gimbal__pb2.SubscribeGimbalListRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.GimbalListResponse.SerializeToString, + ), + "SubscribeControlStatus": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeControlStatus, + request_deserializer=gimbal_dot_gimbal__pb2.SubscribeControlStatusRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.ControlStatusResponse.SerializeToString, + ), + "GetControlStatus": grpc.unary_unary_rpc_method_handler( + servicer.GetControlStatus, + request_deserializer=gimbal_dot_gimbal__pb2.GetControlStatusRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.GetControlStatusResponse.SerializeToString, + ), + "SubscribeAttitude": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeAttitude, + request_deserializer=gimbal_dot_gimbal__pb2.SubscribeAttitudeRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.AttitudeResponse.SerializeToString, + ), + "GetAttitude": grpc.unary_unary_rpc_method_handler( + servicer.GetAttitude, + request_deserializer=gimbal_dot_gimbal__pb2.GetAttitudeRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.GetAttitudeResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.gimbal.GimbalService', rpc_method_handlers) + "mavsdk.rpc.gimbal.GimbalService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.gimbal.GimbalService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.gimbal.GimbalService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class GimbalService(object): - """Provide control over a gimbal. - """ + """Provide control over a gimbal.""" @staticmethod - def SetAngles(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAngles( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/SetAngles', + "/mavsdk.rpc.gimbal.GimbalService/SetAngles", gimbal_dot_gimbal__pb2.SetAnglesRequest.SerializeToString, gimbal_dot_gimbal__pb2.SetAnglesResponse.FromString, options, @@ -298,23 +314,26 @@ def SetAngles(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAngularRates(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAngularRates( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/SetAngularRates', + "/mavsdk.rpc.gimbal.GimbalService/SetAngularRates", gimbal_dot_gimbal__pb2.SetAngularRatesRequest.SerializeToString, gimbal_dot_gimbal__pb2.SetAngularRatesResponse.FromString, options, @@ -325,23 +344,26 @@ def SetAngularRates(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRoiLocation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRoiLocation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/SetRoiLocation', + "/mavsdk.rpc.gimbal.GimbalService/SetRoiLocation", gimbal_dot_gimbal__pb2.SetRoiLocationRequest.SerializeToString, gimbal_dot_gimbal__pb2.SetRoiLocationResponse.FromString, options, @@ -352,23 +374,26 @@ def SetRoiLocation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def TakeControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def TakeControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/TakeControl', + "/mavsdk.rpc.gimbal.GimbalService/TakeControl", gimbal_dot_gimbal__pb2.TakeControlRequest.SerializeToString, gimbal_dot_gimbal__pb2.TakeControlResponse.FromString, options, @@ -379,23 +404,26 @@ def TakeControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ReleaseControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ReleaseControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/ReleaseControl', + "/mavsdk.rpc.gimbal.GimbalService/ReleaseControl", gimbal_dot_gimbal__pb2.ReleaseControlRequest.SerializeToString, gimbal_dot_gimbal__pb2.ReleaseControlResponse.FromString, options, @@ -406,23 +434,26 @@ def ReleaseControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeGimbalList(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeGimbalList( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.gimbal.GimbalService/SubscribeGimbalList', + "/mavsdk.rpc.gimbal.GimbalService/SubscribeGimbalList", gimbal_dot_gimbal__pb2.SubscribeGimbalListRequest.SerializeToString, gimbal_dot_gimbal__pb2.GimbalListResponse.FromString, options, @@ -433,23 +464,26 @@ def SubscribeGimbalList(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeControlStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeControlStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.gimbal.GimbalService/SubscribeControlStatus', + "/mavsdk.rpc.gimbal.GimbalService/SubscribeControlStatus", gimbal_dot_gimbal__pb2.SubscribeControlStatusRequest.SerializeToString, gimbal_dot_gimbal__pb2.ControlStatusResponse.FromString, options, @@ -460,23 +494,26 @@ def SubscribeControlStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetControlStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetControlStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/GetControlStatus', + "/mavsdk.rpc.gimbal.GimbalService/GetControlStatus", gimbal_dot_gimbal__pb2.GetControlStatusRequest.SerializeToString, gimbal_dot_gimbal__pb2.GetControlStatusResponse.FromString, options, @@ -487,23 +524,26 @@ def GetControlStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeAttitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeAttitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.gimbal.GimbalService/SubscribeAttitude', + "/mavsdk.rpc.gimbal.GimbalService/SubscribeAttitude", gimbal_dot_gimbal__pb2.SubscribeAttitudeRequest.SerializeToString, gimbal_dot_gimbal__pb2.AttitudeResponse.FromString, options, @@ -514,23 +554,26 @@ def SubscribeAttitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetAttitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetAttitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gimbal.GimbalService/GetAttitude', + "/mavsdk.rpc.gimbal.GimbalService/GetAttitude", gimbal_dot_gimbal__pb2.GetAttitudeRequest.SerializeToString, gimbal_dot_gimbal__pb2.GetAttitudeResponse.FromString, options, @@ -541,4 +584,5 @@ def GetAttitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/gripper.py b/mavsdk/gripper.py index 2c172cff..8c534c59 100644 --- a/mavsdk/gripper.py +++ b/mavsdk/gripper.py @@ -8,22 +8,21 @@ class GripperAction(Enum): """ - Gripper Actions. + Gripper Actions. - Available gripper actions are defined in mavlink under - https://mavlink.io/en/messages/common.html#GRIPPER_ACTIONS + Available gripper actions are defined in mavlink under + https://mavlink.io/en/messages/common.html#GRIPPER_ACTIONS - Values - ------ - RELEASE - Open the gripper to release the cargo + Values + ------ + RELEASE + Open the gripper to release the cargo - GRAB - Close the gripper and grab onto cargo + GRAB + Close the gripper and grab onto cargo - """ + """ - RELEASE = 0 GRAB = 1 @@ -35,7 +34,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == gripper_pb2.GRIPPER_ACTION_RELEASE: return GripperAction.RELEASE if rpc_enum_value == gripper_pb2.GRIPPER_ACTION_GRAB: @@ -47,50 +46,47 @@ def __str__(self): class GripperResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for gripper action requests. + Possible results returned for gripper action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request was successful + SUCCESS + Request was successful - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - BUSY - Temporarily rejected + BUSY + Temporarily rejected - TIMEOUT - Request timed out + TIMEOUT + Request timed out - UNSUPPORTED - Action not supported + UNSUPPORTED + Action not supported - FAILED - Action failed + FAILED + Action failed - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -117,7 +113,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == gripper_pb2.GripperResult.RESULT_UNKNOWN: return GripperResult.Result.UNKNOWN if rpc_enum_value == gripper_pb2.GripperResult.RESULT_SUCCESS: @@ -135,69 +131,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the GripperResult object """ + def __init__(self, result, result_str): + """Initializes the GripperResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two GripperResult are the same """ + """Checks if two GripperResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # GripperResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ GripperResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """GripperResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"GripperResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGripperResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GripperResult( - - GripperResult.Result.translate_from_rpc(rpcGripperResult.result), - - - rpcGripperResult.result_str - ) + GripperResult.Result.translate_from_rpc(rpcGripperResult.result), + rpcGripperResult.result_str, + ) def translate_to_rpc(self, rpcGripperResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGripperResult.result = self.result.translate_to_rpc() - - - - - - rpcGripperResult.result_str = self.result_str - - - + rpcGripperResult.result_str = self.result_str class GripperError(Exception): - """ Raised when a GripperResult is a fail code """ + """Raised when a GripperResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -210,70 +187,64 @@ def __str__(self): class Gripper(AsyncBase): """ - Allows users to send gripper actions. + Allows users to send gripper actions. - Generated by dcsdkgen - MAVSDK Gripper API + Generated by dcsdkgen - MAVSDK Gripper API """ # Plugin name name = "Gripper" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = gripper_pb2_grpc.GripperServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return GripperResult.translate_from_rpc(response.gripper_result) - async def grab(self, instance): """ - Gripper grab cargo. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - GripperError - If the request fails. The error contains the reason for the failure. + Gripper grab cargo. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + GripperError + If the request fails. The error contains the reason for the failure. """ request = gripper_pb2.GrabRequest() request.instance = instance response = await self._stub.Grab(request) - result = self._extract_result(response) if result.result != GripperResult.Result.SUCCESS: raise GripperError(result, "grab()", instance) - async def release(self, instance): """ - Gripper release cargo. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - GripperError - If the request fails. The error contains the reason for the failure. + Gripper release cargo. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + GripperError + If the request fails. The error contains the reason for the failure. """ request = gripper_pb2.ReleaseRequest() request.instance = instance response = await self._stub.Release(request) - result = self._extract_result(response) if result.result != GripperResult.Result.SUCCESS: raise GripperError(result, "release()", instance) - \ No newline at end of file diff --git a/mavsdk/gripper_pb2.py b/mavsdk/gripper_pb2.py index aeb9735b..e0945eb9 100644 --- a/mavsdk/gripper_pb2.py +++ b/mavsdk/gripper_pb2.py @@ -4,48 +4,47 @@ # source: gripper/gripper.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'gripper/gripper.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "gripper/gripper.proto" ) # @@protoc_insertion_point(imports) _sym_db = _symbol_database.Default() - - -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'gripper.gripper_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "gripper.gripper_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\021io.mavsdk.gripperB\014GripperProto' - _globals['_GRIPPERACTION']._serialized_start=516 - _globals['_GRIPPERACTION']._serialized_end=584 - _globals['_GRABREQUEST']._serialized_start=45 - _globals['_GRABREQUEST']._serialized_end=76 - _globals['_GRABRESPONSE']._serialized_start=78 - _globals['_GRABRESPONSE']._serialized_end=151 - _globals['_RELEASEREQUEST']._serialized_start=153 - _globals['_RELEASEREQUEST']._serialized_end=187 - _globals['_RELEASERESPONSE']._serialized_start=189 - _globals['_RELEASERESPONSE']._serialized_end=265 - _globals['_GRIPPERRESULT']._serialized_start=268 - _globals['_GRIPPERRESULT']._serialized_end=514 - _globals['_GRIPPERRESULT_RESULT']._serialized_start=364 - _globals['_GRIPPERRESULT_RESULT']._serialized_end=514 - _globals['_GRIPPERSERVICE']._serialized_start=587 - _globals['_GRIPPERSERVICE']._serialized_end=766 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\021io.mavsdk.gripperB\014GripperProto" + _globals["_GRIPPERACTION"]._serialized_start = 516 + _globals["_GRIPPERACTION"]._serialized_end = 584 + _globals["_GRABREQUEST"]._serialized_start = 45 + _globals["_GRABREQUEST"]._serialized_end = 76 + _globals["_GRABRESPONSE"]._serialized_start = 78 + _globals["_GRABRESPONSE"]._serialized_end = 151 + _globals["_RELEASEREQUEST"]._serialized_start = 153 + _globals["_RELEASEREQUEST"]._serialized_end = 187 + _globals["_RELEASERESPONSE"]._serialized_start = 189 + _globals["_RELEASERESPONSE"]._serialized_end = 265 + _globals["_GRIPPERRESULT"]._serialized_start = 268 + _globals["_GRIPPERRESULT"]._serialized_end = 514 + _globals["_GRIPPERRESULT_RESULT"]._serialized_start = 364 + _globals["_GRIPPERRESULT_RESULT"]._serialized_end = 514 + _globals["_GRIPPERSERVICE"]._serialized_start = 587 + _globals["_GRIPPERSERVICE"]._serialized_end = 766 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/gripper_pb2_grpc.py b/mavsdk/gripper_pb2_grpc.py index 14b58c33..f054478f 100644 --- a/mavsdk/gripper_pb2_grpc.py +++ b/mavsdk/gripper_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import gripper_pb2 as gripper_dot_gripper__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in gripper/gripper_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in gripper/gripper_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -37,15 +41,17 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.Grab = channel.unary_unary( - '/mavsdk.rpc.gripper.GripperService/Grab', - request_serializer=gripper_dot_gripper__pb2.GrabRequest.SerializeToString, - response_deserializer=gripper_dot_gripper__pb2.GrabResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gripper.GripperService/Grab", + request_serializer=gripper_dot_gripper__pb2.GrabRequest.SerializeToString, + response_deserializer=gripper_dot_gripper__pb2.GrabResponse.FromString, + _registered_method=True, + ) self.Release = channel.unary_unary( - '/mavsdk.rpc.gripper.GripperService/Release', - request_serializer=gripper_dot_gripper__pb2.ReleaseRequest.SerializeToString, - response_deserializer=gripper_dot_gripper__pb2.ReleaseResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.gripper.GripperService/Release", + request_serializer=gripper_dot_gripper__pb2.ReleaseRequest.SerializeToString, + response_deserializer=gripper_dot_gripper__pb2.ReleaseResponse.FromString, + _registered_method=True, + ) class GripperServiceServicer(object): @@ -58,58 +64,63 @@ def Grab(self, request, context): Gripper grab cargo. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Release(self, request, context): """ Gripper release cargo. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_GripperServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'Grab': grpc.unary_unary_rpc_method_handler( - servicer.Grab, - request_deserializer=gripper_dot_gripper__pb2.GrabRequest.FromString, - response_serializer=gripper_dot_gripper__pb2.GrabResponse.SerializeToString, - ), - 'Release': grpc.unary_unary_rpc_method_handler( - servicer.Release, - request_deserializer=gripper_dot_gripper__pb2.ReleaseRequest.FromString, - response_serializer=gripper_dot_gripper__pb2.ReleaseResponse.SerializeToString, - ), + "Grab": grpc.unary_unary_rpc_method_handler( + servicer.Grab, + request_deserializer=gripper_dot_gripper__pb2.GrabRequest.FromString, + response_serializer=gripper_dot_gripper__pb2.GrabResponse.SerializeToString, + ), + "Release": grpc.unary_unary_rpc_method_handler( + servicer.Release, + request_deserializer=gripper_dot_gripper__pb2.ReleaseRequest.FromString, + response_serializer=gripper_dot_gripper__pb2.ReleaseResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.gripper.GripperService', rpc_method_handlers) + "mavsdk.rpc.gripper.GripperService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.gripper.GripperService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.gripper.GripperService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class GripperService(object): """ Allows users to send gripper actions. """ @staticmethod - def Grab(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Grab( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gripper.GripperService/Grab', + "/mavsdk.rpc.gripper.GripperService/Grab", gripper_dot_gripper__pb2.GrabRequest.SerializeToString, gripper_dot_gripper__pb2.GrabResponse.FromString, options, @@ -120,23 +131,26 @@ def Grab(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Release(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Release( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.gripper.GripperService/Release', + "/mavsdk.rpc.gripper.GripperService/Release", gripper_dot_gripper__pb2.ReleaseRequest.SerializeToString, gripper_dot_gripper__pb2.ReleaseResponse.FromString, options, @@ -147,4 +161,5 @@ def Release(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/info.py b/mavsdk/info.py index 18259bc0..c2b97580 100644 --- a/mavsdk/info.py +++ b/mavsdk/info.py @@ -8,363 +8,296 @@ class FlightInfo: """ - System flight information. + System flight information. - Parameters - ---------- - time_boot_ms : uint32_t - Time since system boot + Parameters + ---------- + time_boot_ms : uint32_t + Time since system boot - flight_uid : uint64_t - Flight counter. Starts from zero, is incremented at every disarm and is never reset (even after reboot) + flight_uid : uint64_t + Flight counter. Starts from zero, is incremented at every disarm and is never reset (even after reboot) - duration_since_arming_ms : uint32_t - Duration since arming in milliseconds + duration_since_arming_ms : uint32_t + Duration since arming in milliseconds - duration_since_takeoff_ms : uint32_t - Duration since takeoff in milliseconds + duration_since_takeoff_ms : uint32_t + Duration since takeoff in milliseconds - """ - - + """ def __init__( - self, - time_boot_ms, - flight_uid, - duration_since_arming_ms, - duration_since_takeoff_ms): - """ Initializes the FlightInfo object """ + self, + time_boot_ms, + flight_uid, + duration_since_arming_ms, + duration_since_takeoff_ms, + ): + """Initializes the FlightInfo object""" self.time_boot_ms = time_boot_ms self.flight_uid = flight_uid self.duration_since_arming_ms = duration_since_arming_ms self.duration_since_takeoff_ms = duration_since_takeoff_ms def __eq__(self, to_compare): - """ Checks if two FlightInfo are the same """ + """Checks if two FlightInfo are the same""" try: # Try to compare - this likely fails when it is compared to a non # FlightInfo object - return \ - (self.time_boot_ms == to_compare.time_boot_ms) and \ - (self.flight_uid == to_compare.flight_uid) and \ - (self.duration_since_arming_ms == to_compare.duration_since_arming_ms) and \ - (self.duration_since_takeoff_ms == to_compare.duration_since_takeoff_ms) + return ( + (self.time_boot_ms == to_compare.time_boot_ms) + and (self.flight_uid == to_compare.flight_uid) + and ( + self.duration_since_arming_ms == to_compare.duration_since_arming_ms + ) + and ( + self.duration_since_takeoff_ms + == to_compare.duration_since_takeoff_ms + ) + ) except AttributeError: return False def __str__(self): - """ FlightInfo in string representation """ - struct_repr = ", ".join([ + """FlightInfo in string representation""" + struct_repr = ", ".join( + [ "time_boot_ms: " + str(self.time_boot_ms), "flight_uid: " + str(self.flight_uid), "duration_since_arming_ms: " + str(self.duration_since_arming_ms), - "duration_since_takeoff_ms: " + str(self.duration_since_takeoff_ms) - ]) + "duration_since_takeoff_ms: " + str(self.duration_since_takeoff_ms), + ] + ) return f"FlightInfo: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFlightInfo): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FlightInfo( - - rpcFlightInfo.time_boot_ms, - - - rpcFlightInfo.flight_uid, - - - rpcFlightInfo.duration_since_arming_ms, - - - rpcFlightInfo.duration_since_takeoff_ms - ) + rpcFlightInfo.time_boot_ms, + rpcFlightInfo.flight_uid, + rpcFlightInfo.duration_since_arming_ms, + rpcFlightInfo.duration_since_takeoff_ms, + ) def translate_to_rpc(self, rpcFlightInfo): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFlightInfo.time_boot_ms = self.time_boot_ms - - - - - + rpcFlightInfo.flight_uid = self.flight_uid - - - - - + rpcFlightInfo.duration_since_arming_ms = self.duration_since_arming_ms - - - - - + rpcFlightInfo.duration_since_takeoff_ms = self.duration_since_takeoff_ms - - - class Identification: """ - System identification. - - Parameters - ---------- - hardware_uid : std::string - UID of the hardware. This refers to uid2 of MAVLink. If the system does not support uid2 yet, this is all zeros. + System identification. - legacy_uid : uint64_t - Legacy UID of the hardware, referred to as uid in MAVLink (formerly exposed during system discovery as UUID). + Parameters + ---------- + hardware_uid : std::string + UID of the hardware. This refers to uid2 of MAVLink. If the system does not support uid2 yet, this is all zeros. - """ + legacy_uid : uint64_t + Legacy UID of the hardware, referred to as uid in MAVLink (formerly exposed during system discovery as UUID). - + """ - def __init__( - self, - hardware_uid, - legacy_uid): - """ Initializes the Identification object """ + def __init__(self, hardware_uid, legacy_uid): + """Initializes the Identification object""" self.hardware_uid = hardware_uid self.legacy_uid = legacy_uid def __eq__(self, to_compare): - """ Checks if two Identification are the same """ + """Checks if two Identification are the same""" try: # Try to compare - this likely fails when it is compared to a non # Identification object - return \ - (self.hardware_uid == to_compare.hardware_uid) and \ - (self.legacy_uid == to_compare.legacy_uid) + return (self.hardware_uid == to_compare.hardware_uid) and ( + self.legacy_uid == to_compare.legacy_uid + ) except AttributeError: return False def __str__(self): - """ Identification in string representation """ - struct_repr = ", ".join([ + """Identification in string representation""" + struct_repr = ", ".join( + [ "hardware_uid: " + str(self.hardware_uid), - "legacy_uid: " + str(self.legacy_uid) - ]) + "legacy_uid: " + str(self.legacy_uid), + ] + ) return f"Identification: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcIdentification): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Identification( - - rpcIdentification.hardware_uid, - - - rpcIdentification.legacy_uid - ) + rpcIdentification.hardware_uid, rpcIdentification.legacy_uid + ) def translate_to_rpc(self, rpcIdentification): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcIdentification.hardware_uid = self.hardware_uid - - - - - + rpcIdentification.legacy_uid = self.legacy_uid - - - class Product: """ - System product information. - - Parameters - ---------- - vendor_id : int32_t - ID of the board vendor + System product information. - vendor_name : std::string - Name of the vendor + Parameters + ---------- + vendor_id : int32_t + ID of the board vendor - product_id : int32_t - ID of the product + vendor_name : std::string + Name of the vendor - product_name : std::string - Name of the product + product_id : int32_t + ID of the product - """ + product_name : std::string + Name of the product - + """ - def __init__( - self, - vendor_id, - vendor_name, - product_id, - product_name): - """ Initializes the Product object """ + def __init__(self, vendor_id, vendor_name, product_id, product_name): + """Initializes the Product object""" self.vendor_id = vendor_id self.vendor_name = vendor_name self.product_id = product_id self.product_name = product_name def __eq__(self, to_compare): - """ Checks if two Product are the same """ + """Checks if two Product are the same""" try: # Try to compare - this likely fails when it is compared to a non # Product object - return \ - (self.vendor_id == to_compare.vendor_id) and \ - (self.vendor_name == to_compare.vendor_name) and \ - (self.product_id == to_compare.product_id) and \ - (self.product_name == to_compare.product_name) + return ( + (self.vendor_id == to_compare.vendor_id) + and (self.vendor_name == to_compare.vendor_name) + and (self.product_id == to_compare.product_id) + and (self.product_name == to_compare.product_name) + ) except AttributeError: return False def __str__(self): - """ Product in string representation """ - struct_repr = ", ".join([ + """Product in string representation""" + struct_repr = ", ".join( + [ "vendor_id: " + str(self.vendor_id), "vendor_name: " + str(self.vendor_name), "product_id: " + str(self.product_id), - "product_name: " + str(self.product_name) - ]) + "product_name: " + str(self.product_name), + ] + ) return f"Product: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcProduct): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Product( - - rpcProduct.vendor_id, - - - rpcProduct.vendor_name, - - - rpcProduct.product_id, - - - rpcProduct.product_name - ) + rpcProduct.vendor_id, + rpcProduct.vendor_name, + rpcProduct.product_id, + rpcProduct.product_name, + ) def translate_to_rpc(self, rpcProduct): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcProduct.vendor_id = self.vendor_id - - - - - + rpcProduct.vendor_name = self.vendor_name - - - - - + rpcProduct.product_id = self.product_id - - - - - + rpcProduct.product_name = self.product_name - - - class Version: """ - System version information. + System version information. - Parameters - ---------- - flight_sw_major : int32_t - Flight software major version + Parameters + ---------- + flight_sw_major : int32_t + Flight software major version - flight_sw_minor : int32_t - Flight software minor version + flight_sw_minor : int32_t + Flight software minor version - flight_sw_patch : int32_t - Flight software patch version + flight_sw_patch : int32_t + Flight software patch version - flight_sw_vendor_major : int32_t - Flight software vendor major version + flight_sw_vendor_major : int32_t + Flight software vendor major version - flight_sw_vendor_minor : int32_t - Flight software vendor minor version + flight_sw_vendor_minor : int32_t + Flight software vendor minor version - flight_sw_vendor_patch : int32_t - Flight software vendor patch version + flight_sw_vendor_patch : int32_t + Flight software vendor patch version - os_sw_major : int32_t - Operating system software major version + os_sw_major : int32_t + Operating system software major version - os_sw_minor : int32_t - Operating system software minor version + os_sw_minor : int32_t + Operating system software minor version - os_sw_patch : int32_t - Operating system software patch version + os_sw_patch : int32_t + Operating system software patch version - flight_sw_git_hash : std::string - Flight software git hash + flight_sw_git_hash : std::string + Flight software git hash - os_sw_git_hash : std::string - Operating system software git hash + os_sw_git_hash : std::string + Operating system software git hash - flight_sw_version_type : FlightSoftwareVersionType - Flight software version type + flight_sw_version_type : FlightSoftwareVersionType + Flight software version type - """ + """ - - class FlightSoftwareVersionType(Enum): """ - These values define the type of firmware/flight software release + These values define the type of firmware/flight software release - Values - ------ - UNKNOWN - Unknown type + Values + ------ + UNKNOWN + Unknown type - DEV - Development release + DEV + Development release - ALPHA - Alpha release + ALPHA + Alpha release - BETA - Beta release + BETA + Beta release - RC - Release candidate + RC + Release candidate - RELEASE - Official stable release + RELEASE + Official stable release - """ + """ - UNKNOWN = 0 DEV = 1 ALPHA = 2 @@ -388,7 +321,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == info_pb2.Version.FLIGHT_SOFTWARE_VERSION_TYPE_UNKNOWN: return Version.FlightSoftwareVersionType.UNKNOWN if rpc_enum_value == info_pb2.Version.FLIGHT_SOFTWARE_VERSION_TYPE_DEV: @@ -404,23 +337,23 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - def __init__( - self, - flight_sw_major, - flight_sw_minor, - flight_sw_patch, - flight_sw_vendor_major, - flight_sw_vendor_minor, - flight_sw_vendor_patch, - os_sw_major, - os_sw_minor, - os_sw_patch, - flight_sw_git_hash, - os_sw_git_hash, - flight_sw_version_type): - """ Initializes the Version object """ + self, + flight_sw_major, + flight_sw_minor, + flight_sw_patch, + flight_sw_vendor_major, + flight_sw_vendor_minor, + flight_sw_vendor_patch, + os_sw_major, + os_sw_minor, + os_sw_patch, + flight_sw_git_hash, + os_sw_git_hash, + flight_sw_version_type, + ): + """Initializes the Version object""" self.flight_sw_major = flight_sw_major self.flight_sw_minor = flight_sw_minor self.flight_sw_patch = flight_sw_patch @@ -435,30 +368,32 @@ def __init__( self.flight_sw_version_type = flight_sw_version_type def __eq__(self, to_compare): - """ Checks if two Version are the same """ + """Checks if two Version are the same""" try: # Try to compare - this likely fails when it is compared to a non # Version object - return \ - (self.flight_sw_major == to_compare.flight_sw_major) and \ - (self.flight_sw_minor == to_compare.flight_sw_minor) and \ - (self.flight_sw_patch == to_compare.flight_sw_patch) and \ - (self.flight_sw_vendor_major == to_compare.flight_sw_vendor_major) and \ - (self.flight_sw_vendor_minor == to_compare.flight_sw_vendor_minor) and \ - (self.flight_sw_vendor_patch == to_compare.flight_sw_vendor_patch) and \ - (self.os_sw_major == to_compare.os_sw_major) and \ - (self.os_sw_minor == to_compare.os_sw_minor) and \ - (self.os_sw_patch == to_compare.os_sw_patch) and \ - (self.flight_sw_git_hash == to_compare.flight_sw_git_hash) and \ - (self.os_sw_git_hash == to_compare.os_sw_git_hash) and \ - (self.flight_sw_version_type == to_compare.flight_sw_version_type) + return ( + (self.flight_sw_major == to_compare.flight_sw_major) + and (self.flight_sw_minor == to_compare.flight_sw_minor) + and (self.flight_sw_patch == to_compare.flight_sw_patch) + and (self.flight_sw_vendor_major == to_compare.flight_sw_vendor_major) + and (self.flight_sw_vendor_minor == to_compare.flight_sw_vendor_minor) + and (self.flight_sw_vendor_patch == to_compare.flight_sw_vendor_patch) + and (self.os_sw_major == to_compare.os_sw_major) + and (self.os_sw_minor == to_compare.os_sw_minor) + and (self.os_sw_patch == to_compare.os_sw_patch) + and (self.flight_sw_git_hash == to_compare.flight_sw_git_hash) + and (self.os_sw_git_hash == to_compare.os_sw_git_hash) + and (self.flight_sw_version_type == to_compare.flight_sw_version_type) + ) except AttributeError: return False def __str__(self): - """ Version in string representation """ - struct_repr = ", ".join([ + """Version in string representation""" + struct_repr = ", ".join( + [ "flight_sw_major: " + str(self.flight_sw_major), "flight_sw_minor: " + str(self.flight_sw_minor), "flight_sw_patch: " + str(self.flight_sw_patch), @@ -470,167 +405,96 @@ def __str__(self): "os_sw_patch: " + str(self.os_sw_patch), "flight_sw_git_hash: " + str(self.flight_sw_git_hash), "os_sw_git_hash: " + str(self.os_sw_git_hash), - "flight_sw_version_type: " + str(self.flight_sw_version_type) - ]) + "flight_sw_version_type: " + str(self.flight_sw_version_type), + ] + ) return f"Version: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVersion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Version( - - rpcVersion.flight_sw_major, - - - rpcVersion.flight_sw_minor, - - - rpcVersion.flight_sw_patch, - - - rpcVersion.flight_sw_vendor_major, - - - rpcVersion.flight_sw_vendor_minor, - - - rpcVersion.flight_sw_vendor_patch, - - - rpcVersion.os_sw_major, - - - rpcVersion.os_sw_minor, - - - rpcVersion.os_sw_patch, - - - rpcVersion.flight_sw_git_hash, - - - rpcVersion.os_sw_git_hash, - - - Version.FlightSoftwareVersionType.translate_from_rpc(rpcVersion.flight_sw_version_type) - ) + rpcVersion.flight_sw_major, + rpcVersion.flight_sw_minor, + rpcVersion.flight_sw_patch, + rpcVersion.flight_sw_vendor_major, + rpcVersion.flight_sw_vendor_minor, + rpcVersion.flight_sw_vendor_patch, + rpcVersion.os_sw_major, + rpcVersion.os_sw_minor, + rpcVersion.os_sw_patch, + rpcVersion.flight_sw_git_hash, + rpcVersion.os_sw_git_hash, + Version.FlightSoftwareVersionType.translate_from_rpc( + rpcVersion.flight_sw_version_type + ), + ) def translate_to_rpc(self, rpcVersion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVersion.flight_sw_major = self.flight_sw_major - - - - - + rpcVersion.flight_sw_minor = self.flight_sw_minor - - - - - + rpcVersion.flight_sw_patch = self.flight_sw_patch - - - - - + rpcVersion.flight_sw_vendor_major = self.flight_sw_vendor_major - - - - - + rpcVersion.flight_sw_vendor_minor = self.flight_sw_vendor_minor - - - - - + rpcVersion.flight_sw_vendor_patch = self.flight_sw_vendor_patch - - - - - + rpcVersion.os_sw_major = self.os_sw_major - - - - - + rpcVersion.os_sw_minor = self.os_sw_minor - - - - - + rpcVersion.os_sw_patch = self.os_sw_patch - - - - - + rpcVersion.flight_sw_git_hash = self.flight_sw_git_hash - - - - - + rpcVersion.os_sw_git_hash = self.os_sw_git_hash - - - - - - rpcVersion.flight_sw_version_type = self.flight_sw_version_type.translate_to_rpc() - - - + + rpcVersion.flight_sw_version_type = ( + self.flight_sw_version_type.translate_to_rpc() + ) class InfoResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for info requests. + Possible results returned for info requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - INFORMATION_NOT_RECEIVED_YET - Information has not been received yet + INFORMATION_NOT_RECEIVED_YET + Information has not been received yet - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 INFORMATION_NOT_RECEIVED_YET = 2 @@ -648,81 +512,65 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == info_pb2.InfoResult.RESULT_UNKNOWN: return InfoResult.Result.UNKNOWN if rpc_enum_value == info_pb2.InfoResult.RESULT_SUCCESS: return InfoResult.Result.SUCCESS - if rpc_enum_value == info_pb2.InfoResult.RESULT_INFORMATION_NOT_RECEIVED_YET: + if ( + rpc_enum_value + == info_pb2.InfoResult.RESULT_INFORMATION_NOT_RECEIVED_YET + ): return InfoResult.Result.INFORMATION_NOT_RECEIVED_YET if rpc_enum_value == info_pb2.InfoResult.RESULT_NO_SYSTEM: return InfoResult.Result.NO_SYSTEM def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the InfoResult object """ + def __init__(self, result, result_str): + """Initializes the InfoResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two InfoResult are the same """ + """Checks if two InfoResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # InfoResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ InfoResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """InfoResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"InfoResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcInfoResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return InfoResult( - - InfoResult.Result.translate_from_rpc(rpcInfoResult.result), - - - rpcInfoResult.result_str - ) + InfoResult.Result.translate_from_rpc(rpcInfoResult.result), + rpcInfoResult.result_str, + ) def translate_to_rpc(self, rpcInfoResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcInfoResult.result = self.result.translate_to_rpc() - - - - - - rpcInfoResult.result_str = self.result_str - - - + rpcInfoResult.result_str = self.result_str class InfoError(Exception): - """ Raised when a InfoResult is a fail code """ + """Raised when a InfoResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -735,174 +583,157 @@ def __str__(self): class Info(AsyncBase): """ - Provide information about the hardware and/or software of a system. + Provide information about the hardware and/or software of a system. - Generated by dcsdkgen - MAVSDK Info API + Generated by dcsdkgen - MAVSDK Info API """ # Plugin name name = "Info" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = info_pb2_grpc.InfoServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return InfoResult.translate_from_rpc(response.info_result) - async def get_flight_information(self): """ - Get flight information of the system. + Get flight information of the system. - Returns - ------- - flight_info : FlightInfo - Flight information of the system + Returns + ------- + flight_info : FlightInfo + Flight information of the system - Raises - ------ - InfoError - If the request fails. The error contains the reason for the failure. + Raises + ------ + InfoError + If the request fails. The error contains the reason for the failure. """ request = info_pb2.GetFlightInformationRequest() response = await self._stub.GetFlightInformation(request) - result = self._extract_result(response) if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_flight_information()") - return FlightInfo.translate_from_rpc(response.flight_info) - async def get_identification(self): """ - Get the identification of the system. + Get the identification of the system. - Returns - ------- - identification : Identification - Identification of the system + Returns + ------- + identification : Identification + Identification of the system - Raises - ------ - InfoError - If the request fails. The error contains the reason for the failure. + Raises + ------ + InfoError + If the request fails. The error contains the reason for the failure. """ request = info_pb2.GetIdentificationRequest() response = await self._stub.GetIdentification(request) - result = self._extract_result(response) if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_identification()") - return Identification.translate_from_rpc(response.identification) - async def get_product(self): """ - Get product information of the system. + Get product information of the system. - Returns - ------- - product : Product - Product information of the system + Returns + ------- + product : Product + Product information of the system - Raises - ------ - InfoError - If the request fails. The error contains the reason for the failure. + Raises + ------ + InfoError + If the request fails. The error contains the reason for the failure. """ request = info_pb2.GetProductRequest() response = await self._stub.GetProduct(request) - result = self._extract_result(response) if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_product()") - return Product.translate_from_rpc(response.product) - async def get_version(self): """ - Get the version information of the system. + Get the version information of the system. - Returns - ------- - version : Version - Version information about the system + Returns + ------- + version : Version + Version information about the system - Raises - ------ - InfoError - If the request fails. The error contains the reason for the failure. + Raises + ------ + InfoError + If the request fails. The error contains the reason for the failure. """ request = info_pb2.GetVersionRequest() response = await self._stub.GetVersion(request) - result = self._extract_result(response) if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_version()") - return Version.translate_from_rpc(response.version) - async def get_speed_factor(self): """ - Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). + Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). - Returns - ------- - speed_factor : double - Speed factor of simulation + Returns + ------- + speed_factor : double + Speed factor of simulation - Raises - ------ - InfoError - If the request fails. The error contains the reason for the failure. + Raises + ------ + InfoError + If the request fails. The error contains the reason for the failure. """ request = info_pb2.GetSpeedFactorRequest() response = await self._stub.GetSpeedFactor(request) - result = self._extract_result(response) if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_speed_factor()") - return response.speed_factor - async def flight_information(self): """ - Subscribe to 'flight information' updates. + Subscribe to 'flight information' updates. + + Yields + ------- + flight_info : FlightInfo + The next flight information - Yields - ------- - flight_info : FlightInfo - The next flight information - """ request = info_pb2.SubscribeFlightInformationRequest() @@ -910,9 +741,6 @@ async def flight_information(self): try: async for response in flight_information_stream: - - - yield FlightInfo.translate_from_rpc(response.flight_info) finally: - flight_information_stream.cancel() \ No newline at end of file + flight_information_stream.cancel() diff --git a/mavsdk/info_pb2.py b/mavsdk/info_pb2.py index 52d7523d..9958c3c5 100644 --- a/mavsdk/info_pb2.py +++ b/mavsdk/info_pb2.py @@ -4,18 +4,15 @@ # source: info/info.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'info/info.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "info/info.proto" ) # @@protoc_insertion_point(imports) @@ -25,64 +22,82 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x0finfo/info.proto\x12\x0fmavsdk.rpc.info\x1a\x14mavsdk_options.proto\"\x1d\n\x1bGetFlightInformationRequest\"\x82\x01\n\x1cGetFlightInformationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x30\n\x0b\x66light_info\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.info.FlightInfo\"\x1a\n\x18GetIdentificationRequest\"\x86\x01\n\x19GetIdentificationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x37\n\x0eidentification\x18\x02 \x01(\x0b\x32\x1f.mavsdk.rpc.info.Identification\"\x13\n\x11GetProductRequest\"q\n\x12GetProductResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07product\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Product\"\x13\n\x11GetVersionRequest\"q\n\x12GetVersionResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07version\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Version\"\x17\n\x15GetSpeedFactorRequest\"`\n\x16GetSpeedFactorResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x14\n\x0cspeed_factor\x18\x02 \x01(\x01\"#\n!SubscribeFlightInformationRequest\"M\n\x19\x46lightInformationResponse\x12\x30\n\x0b\x66light_info\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.FlightInfo\"{\n\nFlightInfo\x12\x14\n\x0ctime_boot_ms\x18\x01 \x01(\r\x12\x12\n\nflight_uid\x18\x02 \x01(\x04\x12 \n\x18\x64uration_since_arming_ms\x18\x03 \x01(\r\x12!\n\x19\x64uration_since_takeoff_ms\x18\x04 \x01(\r\":\n\x0eIdentification\x12\x14\n\x0chardware_uid\x18\x01 \x01(\t\x12\x12\n\nlegacy_uid\x18\x02 \x01(\x04\"[\n\x07Product\x12\x11\n\tvendor_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nproduct_id\x18\x03 \x01(\x05\x12\x14\n\x0cproduct_name\x18\x04 \x01(\t\"\x87\x05\n\x07Version\x12\x17\n\x0f\x66light_sw_major\x18\x01 \x01(\x05\x12\x17\n\x0f\x66light_sw_minor\x18\x02 \x01(\x05\x12\x17\n\x0f\x66light_sw_patch\x18\x03 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_major\x18\x04 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_minor\x18\x05 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_patch\x18\x06 \x01(\x05\x12\x13\n\x0bos_sw_major\x18\x07 \x01(\x05\x12\x13\n\x0bos_sw_minor\x18\x08 \x01(\x05\x12\x13\n\x0bos_sw_patch\x18\t \x01(\x05\x12\x1a\n\x12\x66light_sw_git_hash\x18\n \x01(\t\x12\x16\n\x0eos_sw_git_hash\x18\x0b \x01(\t\x12R\n\x16\x66light_sw_version_type\x18\x0c \x01(\x0e\x32\x32.mavsdk.rpc.info.Version.FlightSoftwareVersionType\"\x89\x02\n\x19\x46lightSoftwareVersionType\x12(\n$FLIGHT_SOFTWARE_VERSION_TYPE_UNKNOWN\x10\x00\x12$\n FLIGHT_SOFTWARE_VERSION_TYPE_DEV\x10\x01\x12&\n\"FLIGHT_SOFTWARE_VERSION_TYPE_ALPHA\x10\x02\x12%\n!FLIGHT_SOFTWARE_VERSION_TYPE_BETA\x10\x03\x12#\n\x1f\x46LIGHT_SOFTWARE_VERSION_TYPE_RC\x10\x04\x12(\n$FLIGHT_SOFTWARE_VERSION_TYPE_RELEASE\x10\x05\"\xc5\x01\n\nInfoResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32\".mavsdk.rpc.info.InfoResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"o\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\'\n#RESULT_INFORMATION_NOT_RECEIVED_YET\x10\x02\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x03\x32\xa4\x05\n\x0bInfoService\x12y\n\x14GetFlightInformation\x12,.mavsdk.rpc.info.GetFlightInformationRequest\x1a-.mavsdk.rpc.info.GetFlightInformationResponse\"\x04\x80\xb5\x18\x01\x12p\n\x11GetIdentification\x12).mavsdk.rpc.info.GetIdentificationRequest\x1a*.mavsdk.rpc.info.GetIdentificationResponse\"\x04\x80\xb5\x18\x01\x12[\n\nGetProduct\x12\".mavsdk.rpc.info.GetProductRequest\x1a#.mavsdk.rpc.info.GetProductResponse\"\x04\x80\xb5\x18\x01\x12[\n\nGetVersion\x12\".mavsdk.rpc.info.GetVersionRequest\x1a#.mavsdk.rpc.info.GetVersionResponse\"\x04\x80\xb5\x18\x01\x12g\n\x0eGetSpeedFactor\x12&.mavsdk.rpc.info.GetSpeedFactorRequest\x1a\'.mavsdk.rpc.info.GetSpeedFactorResponse\"\x04\x80\xb5\x18\x01\x12\x84\x01\n\x1aSubscribeFlightInformation\x12\x32.mavsdk.rpc.info.SubscribeFlightInformationRequest\x1a*.mavsdk.rpc.info.FlightInformationResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42\x1b\n\x0eio.mavsdk.infoB\tInfoProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x0finfo/info.proto\x12\x0fmavsdk.rpc.info\x1a\x14mavsdk_options.proto"\x1d\n\x1bGetFlightInformationRequest"\x82\x01\n\x1cGetFlightInformationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x30\n\x0b\x66light_info\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.info.FlightInfo"\x1a\n\x18GetIdentificationRequest"\x86\x01\n\x19GetIdentificationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x37\n\x0eidentification\x18\x02 \x01(\x0b\x32\x1f.mavsdk.rpc.info.Identification"\x13\n\x11GetProductRequest"q\n\x12GetProductResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07product\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Product"\x13\n\x11GetVersionRequest"q\n\x12GetVersionResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07version\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Version"\x17\n\x15GetSpeedFactorRequest"`\n\x16GetSpeedFactorResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x14\n\x0cspeed_factor\x18\x02 \x01(\x01"#\n!SubscribeFlightInformationRequest"M\n\x19\x46lightInformationResponse\x12\x30\n\x0b\x66light_info\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.FlightInfo"{\n\nFlightInfo\x12\x14\n\x0ctime_boot_ms\x18\x01 \x01(\r\x12\x12\n\nflight_uid\x18\x02 \x01(\x04\x12 \n\x18\x64uration_since_arming_ms\x18\x03 \x01(\r\x12!\n\x19\x64uration_since_takeoff_ms\x18\x04 \x01(\r":\n\x0eIdentification\x12\x14\n\x0chardware_uid\x18\x01 \x01(\t\x12\x12\n\nlegacy_uid\x18\x02 \x01(\x04"[\n\x07Product\x12\x11\n\tvendor_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nproduct_id\x18\x03 \x01(\x05\x12\x14\n\x0cproduct_name\x18\x04 \x01(\t"\x87\x05\n\x07Version\x12\x17\n\x0f\x66light_sw_major\x18\x01 \x01(\x05\x12\x17\n\x0f\x66light_sw_minor\x18\x02 \x01(\x05\x12\x17\n\x0f\x66light_sw_patch\x18\x03 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_major\x18\x04 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_minor\x18\x05 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_patch\x18\x06 \x01(\x05\x12\x13\n\x0bos_sw_major\x18\x07 \x01(\x05\x12\x13\n\x0bos_sw_minor\x18\x08 \x01(\x05\x12\x13\n\x0bos_sw_patch\x18\t \x01(\x05\x12\x1a\n\x12\x66light_sw_git_hash\x18\n \x01(\t\x12\x16\n\x0eos_sw_git_hash\x18\x0b \x01(\t\x12R\n\x16\x66light_sw_version_type\x18\x0c \x01(\x0e\x32\x32.mavsdk.rpc.info.Version.FlightSoftwareVersionType"\x89\x02\n\x19\x46lightSoftwareVersionType\x12(\n$FLIGHT_SOFTWARE_VERSION_TYPE_UNKNOWN\x10\x00\x12$\n FLIGHT_SOFTWARE_VERSION_TYPE_DEV\x10\x01\x12&\n"FLIGHT_SOFTWARE_VERSION_TYPE_ALPHA\x10\x02\x12%\n!FLIGHT_SOFTWARE_VERSION_TYPE_BETA\x10\x03\x12#\n\x1f\x46LIGHT_SOFTWARE_VERSION_TYPE_RC\x10\x04\x12(\n$FLIGHT_SOFTWARE_VERSION_TYPE_RELEASE\x10\x05"\xc5\x01\n\nInfoResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32".mavsdk.rpc.info.InfoResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"o\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\'\n#RESULT_INFORMATION_NOT_RECEIVED_YET\x10\x02\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x03\x32\xa4\x05\n\x0bInfoService\x12y\n\x14GetFlightInformation\x12,.mavsdk.rpc.info.GetFlightInformationRequest\x1a-.mavsdk.rpc.info.GetFlightInformationResponse"\x04\x80\xb5\x18\x01\x12p\n\x11GetIdentification\x12).mavsdk.rpc.info.GetIdentificationRequest\x1a*.mavsdk.rpc.info.GetIdentificationResponse"\x04\x80\xb5\x18\x01\x12[\n\nGetProduct\x12".mavsdk.rpc.info.GetProductRequest\x1a#.mavsdk.rpc.info.GetProductResponse"\x04\x80\xb5\x18\x01\x12[\n\nGetVersion\x12".mavsdk.rpc.info.GetVersionRequest\x1a#.mavsdk.rpc.info.GetVersionResponse"\x04\x80\xb5\x18\x01\x12g\n\x0eGetSpeedFactor\x12&.mavsdk.rpc.info.GetSpeedFactorRequest\x1a\'.mavsdk.rpc.info.GetSpeedFactorResponse"\x04\x80\xb5\x18\x01\x12\x84\x01\n\x1aSubscribeFlightInformation\x12\x32.mavsdk.rpc.info.SubscribeFlightInformationRequest\x1a*.mavsdk.rpc.info.FlightInformationResponse"\x04\x80\xb5\x18\x00\x30\x01\x42\x1b\n\x0eio.mavsdk.infoB\tInfoProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'info.info_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "info.info_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\016io.mavsdk.infoB\tInfoProto' - _globals['_INFOSERVICE'].methods_by_name['GetFlightInformation']._loaded_options = None - _globals['_INFOSERVICE'].methods_by_name['GetFlightInformation']._serialized_options = b'\200\265\030\001' - _globals['_INFOSERVICE'].methods_by_name['GetIdentification']._loaded_options = None - _globals['_INFOSERVICE'].methods_by_name['GetIdentification']._serialized_options = b'\200\265\030\001' - _globals['_INFOSERVICE'].methods_by_name['GetProduct']._loaded_options = None - _globals['_INFOSERVICE'].methods_by_name['GetProduct']._serialized_options = b'\200\265\030\001' - _globals['_INFOSERVICE'].methods_by_name['GetVersion']._loaded_options = None - _globals['_INFOSERVICE'].methods_by_name['GetVersion']._serialized_options = b'\200\265\030\001' - _globals['_INFOSERVICE'].methods_by_name['GetSpeedFactor']._loaded_options = None - _globals['_INFOSERVICE'].methods_by_name['GetSpeedFactor']._serialized_options = b'\200\265\030\001' - _globals['_INFOSERVICE'].methods_by_name['SubscribeFlightInformation']._loaded_options = None - _globals['_INFOSERVICE'].methods_by_name['SubscribeFlightInformation']._serialized_options = b'\200\265\030\000' - _globals['_GETFLIGHTINFORMATIONREQUEST']._serialized_start=58 - _globals['_GETFLIGHTINFORMATIONREQUEST']._serialized_end=87 - _globals['_GETFLIGHTINFORMATIONRESPONSE']._serialized_start=90 - _globals['_GETFLIGHTINFORMATIONRESPONSE']._serialized_end=220 - _globals['_GETIDENTIFICATIONREQUEST']._serialized_start=222 - _globals['_GETIDENTIFICATIONREQUEST']._serialized_end=248 - _globals['_GETIDENTIFICATIONRESPONSE']._serialized_start=251 - _globals['_GETIDENTIFICATIONRESPONSE']._serialized_end=385 - _globals['_GETPRODUCTREQUEST']._serialized_start=387 - _globals['_GETPRODUCTREQUEST']._serialized_end=406 - _globals['_GETPRODUCTRESPONSE']._serialized_start=408 - _globals['_GETPRODUCTRESPONSE']._serialized_end=521 - _globals['_GETVERSIONREQUEST']._serialized_start=523 - _globals['_GETVERSIONREQUEST']._serialized_end=542 - _globals['_GETVERSIONRESPONSE']._serialized_start=544 - _globals['_GETVERSIONRESPONSE']._serialized_end=657 - _globals['_GETSPEEDFACTORREQUEST']._serialized_start=659 - _globals['_GETSPEEDFACTORREQUEST']._serialized_end=682 - _globals['_GETSPEEDFACTORRESPONSE']._serialized_start=684 - _globals['_GETSPEEDFACTORRESPONSE']._serialized_end=780 - _globals['_SUBSCRIBEFLIGHTINFORMATIONREQUEST']._serialized_start=782 - _globals['_SUBSCRIBEFLIGHTINFORMATIONREQUEST']._serialized_end=817 - _globals['_FLIGHTINFORMATIONRESPONSE']._serialized_start=819 - _globals['_FLIGHTINFORMATIONRESPONSE']._serialized_end=896 - _globals['_FLIGHTINFO']._serialized_start=898 - _globals['_FLIGHTINFO']._serialized_end=1021 - _globals['_IDENTIFICATION']._serialized_start=1023 - _globals['_IDENTIFICATION']._serialized_end=1081 - _globals['_PRODUCT']._serialized_start=1083 - _globals['_PRODUCT']._serialized_end=1174 - _globals['_VERSION']._serialized_start=1177 - _globals['_VERSION']._serialized_end=1824 - _globals['_VERSION_FLIGHTSOFTWAREVERSIONTYPE']._serialized_start=1559 - _globals['_VERSION_FLIGHTSOFTWAREVERSIONTYPE']._serialized_end=1824 - _globals['_INFORESULT']._serialized_start=1827 - _globals['_INFORESULT']._serialized_end=2024 - _globals['_INFORESULT_RESULT']._serialized_start=1913 - _globals['_INFORESULT_RESULT']._serialized_end=2024 - _globals['_INFOSERVICE']._serialized_start=2027 - _globals['_INFOSERVICE']._serialized_end=2703 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\016io.mavsdk.infoB\tInfoProto" + _globals["_INFOSERVICE"].methods_by_name[ + "GetFlightInformation" + ]._loaded_options = None + _globals["_INFOSERVICE"].methods_by_name[ + "GetFlightInformation" + ]._serialized_options = b"\200\265\030\001" + _globals["_INFOSERVICE"].methods_by_name["GetIdentification"]._loaded_options = None + _globals["_INFOSERVICE"].methods_by_name[ + "GetIdentification" + ]._serialized_options = b"\200\265\030\001" + _globals["_INFOSERVICE"].methods_by_name["GetProduct"]._loaded_options = None + _globals["_INFOSERVICE"].methods_by_name[ + "GetProduct" + ]._serialized_options = b"\200\265\030\001" + _globals["_INFOSERVICE"].methods_by_name["GetVersion"]._loaded_options = None + _globals["_INFOSERVICE"].methods_by_name[ + "GetVersion" + ]._serialized_options = b"\200\265\030\001" + _globals["_INFOSERVICE"].methods_by_name["GetSpeedFactor"]._loaded_options = None + _globals["_INFOSERVICE"].methods_by_name[ + "GetSpeedFactor" + ]._serialized_options = b"\200\265\030\001" + _globals["_INFOSERVICE"].methods_by_name[ + "SubscribeFlightInformation" + ]._loaded_options = None + _globals["_INFOSERVICE"].methods_by_name[ + "SubscribeFlightInformation" + ]._serialized_options = b"\200\265\030\000" + _globals["_GETFLIGHTINFORMATIONREQUEST"]._serialized_start = 58 + _globals["_GETFLIGHTINFORMATIONREQUEST"]._serialized_end = 87 + _globals["_GETFLIGHTINFORMATIONRESPONSE"]._serialized_start = 90 + _globals["_GETFLIGHTINFORMATIONRESPONSE"]._serialized_end = 220 + _globals["_GETIDENTIFICATIONREQUEST"]._serialized_start = 222 + _globals["_GETIDENTIFICATIONREQUEST"]._serialized_end = 248 + _globals["_GETIDENTIFICATIONRESPONSE"]._serialized_start = 251 + _globals["_GETIDENTIFICATIONRESPONSE"]._serialized_end = 385 + _globals["_GETPRODUCTREQUEST"]._serialized_start = 387 + _globals["_GETPRODUCTREQUEST"]._serialized_end = 406 + _globals["_GETPRODUCTRESPONSE"]._serialized_start = 408 + _globals["_GETPRODUCTRESPONSE"]._serialized_end = 521 + _globals["_GETVERSIONREQUEST"]._serialized_start = 523 + _globals["_GETVERSIONREQUEST"]._serialized_end = 542 + _globals["_GETVERSIONRESPONSE"]._serialized_start = 544 + _globals["_GETVERSIONRESPONSE"]._serialized_end = 657 + _globals["_GETSPEEDFACTORREQUEST"]._serialized_start = 659 + _globals["_GETSPEEDFACTORREQUEST"]._serialized_end = 682 + _globals["_GETSPEEDFACTORRESPONSE"]._serialized_start = 684 + _globals["_GETSPEEDFACTORRESPONSE"]._serialized_end = 780 + _globals["_SUBSCRIBEFLIGHTINFORMATIONREQUEST"]._serialized_start = 782 + _globals["_SUBSCRIBEFLIGHTINFORMATIONREQUEST"]._serialized_end = 817 + _globals["_FLIGHTINFORMATIONRESPONSE"]._serialized_start = 819 + _globals["_FLIGHTINFORMATIONRESPONSE"]._serialized_end = 896 + _globals["_FLIGHTINFO"]._serialized_start = 898 + _globals["_FLIGHTINFO"]._serialized_end = 1021 + _globals["_IDENTIFICATION"]._serialized_start = 1023 + _globals["_IDENTIFICATION"]._serialized_end = 1081 + _globals["_PRODUCT"]._serialized_start = 1083 + _globals["_PRODUCT"]._serialized_end = 1174 + _globals["_VERSION"]._serialized_start = 1177 + _globals["_VERSION"]._serialized_end = 1824 + _globals["_VERSION_FLIGHTSOFTWAREVERSIONTYPE"]._serialized_start = 1559 + _globals["_VERSION_FLIGHTSOFTWAREVERSIONTYPE"]._serialized_end = 1824 + _globals["_INFORESULT"]._serialized_start = 1827 + _globals["_INFORESULT"]._serialized_end = 2024 + _globals["_INFORESULT_RESULT"]._serialized_start = 1913 + _globals["_INFORESULT_RESULT"]._serialized_end = 2024 + _globals["_INFOSERVICE"]._serialized_start = 2027 + _globals["_INFOSERVICE"]._serialized_end = 2703 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/info_pb2_grpc.py b/mavsdk/info_pb2_grpc.py index fa0c850b..cb97f572 100644 --- a/mavsdk/info_pb2_grpc.py +++ b/mavsdk/info_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import info_pb2 as info_dot_info__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in info/info_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in info/info_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class InfoServiceStub(object): - """Provide information about the hardware and/or software of a system. - """ + """Provide information about the hardware and/or software of a system.""" def __init__(self, channel): """Constructor. @@ -36,143 +39,146 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.GetFlightInformation = channel.unary_unary( - '/mavsdk.rpc.info.InfoService/GetFlightInformation', - request_serializer=info_dot_info__pb2.GetFlightInformationRequest.SerializeToString, - response_deserializer=info_dot_info__pb2.GetFlightInformationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.info.InfoService/GetFlightInformation", + request_serializer=info_dot_info__pb2.GetFlightInformationRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.GetFlightInformationResponse.FromString, + _registered_method=True, + ) self.GetIdentification = channel.unary_unary( - '/mavsdk.rpc.info.InfoService/GetIdentification', - request_serializer=info_dot_info__pb2.GetIdentificationRequest.SerializeToString, - response_deserializer=info_dot_info__pb2.GetIdentificationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.info.InfoService/GetIdentification", + request_serializer=info_dot_info__pb2.GetIdentificationRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.GetIdentificationResponse.FromString, + _registered_method=True, + ) self.GetProduct = channel.unary_unary( - '/mavsdk.rpc.info.InfoService/GetProduct', - request_serializer=info_dot_info__pb2.GetProductRequest.SerializeToString, - response_deserializer=info_dot_info__pb2.GetProductResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.info.InfoService/GetProduct", + request_serializer=info_dot_info__pb2.GetProductRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.GetProductResponse.FromString, + _registered_method=True, + ) self.GetVersion = channel.unary_unary( - '/mavsdk.rpc.info.InfoService/GetVersion', - request_serializer=info_dot_info__pb2.GetVersionRequest.SerializeToString, - response_deserializer=info_dot_info__pb2.GetVersionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.info.InfoService/GetVersion", + request_serializer=info_dot_info__pb2.GetVersionRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.GetVersionResponse.FromString, + _registered_method=True, + ) self.GetSpeedFactor = channel.unary_unary( - '/mavsdk.rpc.info.InfoService/GetSpeedFactor', - request_serializer=info_dot_info__pb2.GetSpeedFactorRequest.SerializeToString, - response_deserializer=info_dot_info__pb2.GetSpeedFactorResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.info.InfoService/GetSpeedFactor", + request_serializer=info_dot_info__pb2.GetSpeedFactorRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.GetSpeedFactorResponse.FromString, + _registered_method=True, + ) self.SubscribeFlightInformation = channel.unary_stream( - '/mavsdk.rpc.info.InfoService/SubscribeFlightInformation', - request_serializer=info_dot_info__pb2.SubscribeFlightInformationRequest.SerializeToString, - response_deserializer=info_dot_info__pb2.FlightInformationResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.info.InfoService/SubscribeFlightInformation", + request_serializer=info_dot_info__pb2.SubscribeFlightInformationRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.FlightInformationResponse.FromString, + _registered_method=True, + ) class InfoServiceServicer(object): - """Provide information about the hardware and/or software of a system. - """ + """Provide information about the hardware and/or software of a system.""" def GetFlightInformation(self, request, context): - """Get flight information of the system. - """ + """Get flight information of the system.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetIdentification(self, request, context): - """Get the identification of the system. - """ + """Get the identification of the system.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetProduct(self, request, context): - """Get product information of the system. - """ + """Get product information of the system.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetVersion(self, request, context): - """Get the version information of the system. - """ + """Get the version information of the system.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetSpeedFactor(self, request, context): - """Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). - """ + """Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime).""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFlightInformation(self, request, context): - """Subscribe to 'flight information' updates. - """ + """Subscribe to 'flight information' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_InfoServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'GetFlightInformation': grpc.unary_unary_rpc_method_handler( - servicer.GetFlightInformation, - request_deserializer=info_dot_info__pb2.GetFlightInformationRequest.FromString, - response_serializer=info_dot_info__pb2.GetFlightInformationResponse.SerializeToString, - ), - 'GetIdentification': grpc.unary_unary_rpc_method_handler( - servicer.GetIdentification, - request_deserializer=info_dot_info__pb2.GetIdentificationRequest.FromString, - response_serializer=info_dot_info__pb2.GetIdentificationResponse.SerializeToString, - ), - 'GetProduct': grpc.unary_unary_rpc_method_handler( - servicer.GetProduct, - request_deserializer=info_dot_info__pb2.GetProductRequest.FromString, - response_serializer=info_dot_info__pb2.GetProductResponse.SerializeToString, - ), - 'GetVersion': grpc.unary_unary_rpc_method_handler( - servicer.GetVersion, - request_deserializer=info_dot_info__pb2.GetVersionRequest.FromString, - response_serializer=info_dot_info__pb2.GetVersionResponse.SerializeToString, - ), - 'GetSpeedFactor': grpc.unary_unary_rpc_method_handler( - servicer.GetSpeedFactor, - request_deserializer=info_dot_info__pb2.GetSpeedFactorRequest.FromString, - response_serializer=info_dot_info__pb2.GetSpeedFactorResponse.SerializeToString, - ), - 'SubscribeFlightInformation': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFlightInformation, - request_deserializer=info_dot_info__pb2.SubscribeFlightInformationRequest.FromString, - response_serializer=info_dot_info__pb2.FlightInformationResponse.SerializeToString, - ), + "GetFlightInformation": grpc.unary_unary_rpc_method_handler( + servicer.GetFlightInformation, + request_deserializer=info_dot_info__pb2.GetFlightInformationRequest.FromString, + response_serializer=info_dot_info__pb2.GetFlightInformationResponse.SerializeToString, + ), + "GetIdentification": grpc.unary_unary_rpc_method_handler( + servicer.GetIdentification, + request_deserializer=info_dot_info__pb2.GetIdentificationRequest.FromString, + response_serializer=info_dot_info__pb2.GetIdentificationResponse.SerializeToString, + ), + "GetProduct": grpc.unary_unary_rpc_method_handler( + servicer.GetProduct, + request_deserializer=info_dot_info__pb2.GetProductRequest.FromString, + response_serializer=info_dot_info__pb2.GetProductResponse.SerializeToString, + ), + "GetVersion": grpc.unary_unary_rpc_method_handler( + servicer.GetVersion, + request_deserializer=info_dot_info__pb2.GetVersionRequest.FromString, + response_serializer=info_dot_info__pb2.GetVersionResponse.SerializeToString, + ), + "GetSpeedFactor": grpc.unary_unary_rpc_method_handler( + servicer.GetSpeedFactor, + request_deserializer=info_dot_info__pb2.GetSpeedFactorRequest.FromString, + response_serializer=info_dot_info__pb2.GetSpeedFactorResponse.SerializeToString, + ), + "SubscribeFlightInformation": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFlightInformation, + request_deserializer=info_dot_info__pb2.SubscribeFlightInformationRequest.FromString, + response_serializer=info_dot_info__pb2.FlightInformationResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.info.InfoService', rpc_method_handlers) + "mavsdk.rpc.info.InfoService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.info.InfoService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.info.InfoService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class InfoService(object): - """Provide information about the hardware and/or software of a system. - """ + """Provide information about the hardware and/or software of a system.""" @staticmethod - def GetFlightInformation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetFlightInformation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.info.InfoService/GetFlightInformation', + "/mavsdk.rpc.info.InfoService/GetFlightInformation", info_dot_info__pb2.GetFlightInformationRequest.SerializeToString, info_dot_info__pb2.GetFlightInformationResponse.FromString, options, @@ -183,23 +189,26 @@ def GetFlightInformation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetIdentification(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetIdentification( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.info.InfoService/GetIdentification', + "/mavsdk.rpc.info.InfoService/GetIdentification", info_dot_info__pb2.GetIdentificationRequest.SerializeToString, info_dot_info__pb2.GetIdentificationResponse.FromString, options, @@ -210,23 +219,26 @@ def GetIdentification(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetProduct(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetProduct( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.info.InfoService/GetProduct', + "/mavsdk.rpc.info.InfoService/GetProduct", info_dot_info__pb2.GetProductRequest.SerializeToString, info_dot_info__pb2.GetProductResponse.FromString, options, @@ -237,23 +249,26 @@ def GetProduct(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetVersion(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetVersion( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.info.InfoService/GetVersion', + "/mavsdk.rpc.info.InfoService/GetVersion", info_dot_info__pb2.GetVersionRequest.SerializeToString, info_dot_info__pb2.GetVersionResponse.FromString, options, @@ -264,23 +279,26 @@ def GetVersion(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetSpeedFactor(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetSpeedFactor( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.info.InfoService/GetSpeedFactor', + "/mavsdk.rpc.info.InfoService/GetSpeedFactor", info_dot_info__pb2.GetSpeedFactorRequest.SerializeToString, info_dot_info__pb2.GetSpeedFactorResponse.FromString, options, @@ -291,23 +309,26 @@ def GetSpeedFactor(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeFlightInformation(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeFlightInformation( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.info.InfoService/SubscribeFlightInformation', + "/mavsdk.rpc.info.InfoService/SubscribeFlightInformation", info_dot_info__pb2.SubscribeFlightInformationRequest.SerializeToString, info_dot_info__pb2.FlightInformationResponse.FromString, options, @@ -318,4 +339,5 @@ def SubscribeFlightInformation(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/log_files.py b/mavsdk/log_files.py index a608159d..84ad5ce4 100644 --- a/mavsdk/log_files.py +++ b/mavsdk/log_files.py @@ -8,201 +8,156 @@ class ProgressData: """ - Progress data coming when downloading a log file. + Progress data coming when downloading a log file. - Parameters - ---------- - progress : float - Progress from 0 to 1 + Parameters + ---------- + progress : float + Progress from 0 to 1 - """ - - + """ - def __init__( - self, - progress): - """ Initializes the ProgressData object """ + def __init__(self, progress): + """Initializes the ProgressData object""" self.progress = progress def __eq__(self, to_compare): - """ Checks if two ProgressData are the same """ + """Checks if two ProgressData are the same""" try: # Try to compare - this likely fails when it is compared to a non # ProgressData object - return \ - (self.progress == to_compare.progress) + return self.progress == to_compare.progress except AttributeError: return False def __str__(self): - """ ProgressData in string representation """ - struct_repr = ", ".join([ - "progress: " + str(self.progress) - ]) + """ProgressData in string representation""" + struct_repr = ", ".join(["progress: " + str(self.progress)]) return f"ProgressData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcProgressData): - """ Translates a gRPC struct to the SDK equivalent """ - return ProgressData( - - rpcProgressData.progress - ) + """Translates a gRPC struct to the SDK equivalent""" + return ProgressData(rpcProgressData.progress) def translate_to_rpc(self, rpcProgressData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcProgressData.progress = self.progress - - - class Entry: """ - Log file entry type. - - Parameters - ---------- - id : uint32_t - ID of the log file, to specify a file to be downloaded + Log file entry type. - date : std::string - Date of the log file in UTC in ISO 8601 format "yyyy-mm-ddThh:mm:ssZ" + Parameters + ---------- + id : uint32_t + ID of the log file, to specify a file to be downloaded - size_bytes : uint32_t - Size of file in bytes + date : std::string + Date of the log file in UTC in ISO 8601 format "yyyy-mm-ddThh:mm:ssZ" - """ + size_bytes : uint32_t + Size of file in bytes - + """ - def __init__( - self, - id, - date, - size_bytes): - """ Initializes the Entry object """ + def __init__(self, id, date, size_bytes): + """Initializes the Entry object""" self.id = id self.date = date self.size_bytes = size_bytes def __eq__(self, to_compare): - """ Checks if two Entry are the same """ + """Checks if two Entry are the same""" try: # Try to compare - this likely fails when it is compared to a non # Entry object - return \ - (self.id == to_compare.id) and \ - (self.date == to_compare.date) and \ - (self.size_bytes == to_compare.size_bytes) + return ( + (self.id == to_compare.id) + and (self.date == to_compare.date) + and (self.size_bytes == to_compare.size_bytes) + ) except AttributeError: return False def __str__(self): - """ Entry in string representation """ - struct_repr = ", ".join([ + """Entry in string representation""" + struct_repr = ", ".join( + [ "id: " + str(self.id), "date: " + str(self.date), - "size_bytes: " + str(self.size_bytes) - ]) + "size_bytes: " + str(self.size_bytes), + ] + ) return f"Entry: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEntry): - """ Translates a gRPC struct to the SDK equivalent """ - return Entry( - - rpcEntry.id, - - - rpcEntry.date, - - - rpcEntry.size_bytes - ) + """Translates a gRPC struct to the SDK equivalent""" + return Entry(rpcEntry.id, rpcEntry.date, rpcEntry.size_bytes) def translate_to_rpc(self, rpcEntry): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEntry.id = self.id - - - - - + rpcEntry.date = self.date - - - - - + rpcEntry.size_bytes = self.size_bytes - - - class LogFilesResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for calibration commands + Possible results returned for calibration commands - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NEXT - Progress update + NEXT + Progress update - NO_LOGFILES - No log files found + NO_LOGFILES + No log files found - TIMEOUT - A timeout happened + TIMEOUT + A timeout happened - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - FILE_OPEN_FAILED - File open failed + FILE_OPEN_FAILED + File open failed - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 NEXT = 2 @@ -232,7 +187,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == log_files_pb2.LogFilesResult.RESULT_UNKNOWN: return LogFilesResult.Result.UNKNOWN if rpc_enum_value == log_files_pb2.LogFilesResult.RESULT_SUCCESS: @@ -252,69 +207,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the LogFilesResult object """ + def __init__(self, result, result_str): + """Initializes the LogFilesResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two LogFilesResult are the same """ + """Checks if two LogFilesResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # LogFilesResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ LogFilesResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """LogFilesResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"LogFilesResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcLogFilesResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return LogFilesResult( - - LogFilesResult.Result.translate_from_rpc(rpcLogFilesResult.result), - - - rpcLogFilesResult.result_str - ) + LogFilesResult.Result.translate_from_rpc(rpcLogFilesResult.result), + rpcLogFilesResult.result_str, + ) def translate_to_rpc(self, rpcLogFilesResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcLogFilesResult.result = self.result.translate_to_rpc() - - - - - - rpcLogFilesResult.result_str = self.result_str - - - + rpcLogFilesResult.result_str = self.result_str class LogFilesError(Exception): - """ Raised when a LogFilesResult is a fail code """ + """Raised when a LogFilesResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -327,126 +263,117 @@ def __str__(self): class LogFiles(AsyncBase): """ - Allow to download log files from the vehicle after a flight is complete. - For log streaming during flight check the logging plugin. + Allow to download log files from the vehicle after a flight is complete. + For log streaming during flight check the logging plugin. - Generated by dcsdkgen - MAVSDK LogFiles API + Generated by dcsdkgen - MAVSDK LogFiles API """ # Plugin name name = "LogFiles" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = log_files_pb2_grpc.LogFilesServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return LogFilesResult.translate_from_rpc(response.log_files_result) - async def get_entries(self): """ - Get List of log files. + Get List of log files. - Returns - ------- - entries : [Entry] - List of entries + Returns + ------- + entries : [Entry] + List of entries - Raises - ------ - LogFilesError - If the request fails. The error contains the reason for the failure. + Raises + ------ + LogFilesError + If the request fails. The error contains the reason for the failure. """ request = log_files_pb2.GetEntriesRequest() response = await self._stub.GetEntries(request) - result = self._extract_result(response) if result.result != LogFilesResult.Result.SUCCESS: raise LogFilesError(result, "get_entries()") - entries = [] for entries_rpc in response.entries: entries.append(Entry.translate_from_rpc(entries_rpc)) return entries - async def download_log_file(self, entry, path): """ - Download log file. + Download log file. - Parameters - ---------- - entry : Entry - Entry of the log file to download. + Parameters + ---------- + entry : Entry + Entry of the log file to download. - path : std::string - Path of where to download log file to. + path : std::string + Path of where to download log file to. - Yields - ------- - progress : ProgressData - Progress if result is progress + Yields + ------- + progress : ProgressData + Progress if result is progress - Raises - ------ - LogFilesError - If the request fails. The error contains the reason for the failure. + Raises + ------ + LogFilesError + If the request fails. The error contains the reason for the failure. """ request = log_files_pb2.SubscribeDownloadLogFileRequest() - + entry.translate_to_rpc(request.entry) - - + request.path = path download_log_file_stream = self._stub.SubscribeDownloadLogFile(request) try: async for response in download_log_file_stream: - result = self._extract_result(response) success_codes = [LogFilesResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in LogFilesResult.Result]: + if "NEXT" in [ + return_code.name for return_code in LogFilesResult.Result + ]: success_codes.append(LogFilesResult.Result.NEXT) if result.result not in success_codes: raise LogFilesError(result, "download_log_file()", entry, path) if result.result == LogFilesResult.Result.SUCCESS: - download_log_file_stream.cancel(); + download_log_file_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress) finally: download_log_file_stream.cancel() async def erase_all_log_files(self): """ - Erase all log files. + Erase all log files. - Raises - ------ - LogFilesError - If the request fails. The error contains the reason for the failure. + Raises + ------ + LogFilesError + If the request fails. The error contains the reason for the failure. """ request = log_files_pb2.EraseAllLogFilesRequest() response = await self._stub.EraseAllLogFiles(request) - result = self._extract_result(response) if result.result != LogFilesResult.Result.SUCCESS: raise LogFilesError(result, "erase_all_log_files()") - \ No newline at end of file diff --git a/mavsdk/log_files_pb2.py b/mavsdk/log_files_pb2.py index d3f18c53..3da41aee 100644 --- a/mavsdk/log_files_pb2.py +++ b/mavsdk/log_files_pb2.py @@ -4,18 +4,15 @@ # source: log_files/log_files.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'log_files/log_files.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "log_files/log_files.proto" ) # @@protoc_insertion_point(imports) @@ -25,40 +22,54 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x19log_files/log_files.proto\x12\x14mavsdk.rpc.log_files\x1a\x14mavsdk_options.proto\"\x13\n\x11GetEntriesRequest\"\x82\x01\n\x12GetEntriesResponse\x12>\n\x10log_files_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.log_files.LogFilesResult\x12,\n\x07\x65ntries\x18\x02 \x03(\x0b\x32\x1b.mavsdk.rpc.log_files.Entry\"[\n\x1fSubscribeDownloadLogFileRequest\x12*\n\x05\x65ntry\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.log_files.Entry\x12\x0c\n\x04path\x18\x02 \x01(\t\"\x8f\x01\n\x17\x44ownloadLogFileResponse\x12>\n\x10log_files_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.log_files.LogFilesResult\x12\x34\n\x08progress\x18\x02 \x01(\x0b\x32\".mavsdk.rpc.log_files.ProgressData\"\x19\n\x17\x45raseAllLogFilesRequest\"Z\n\x18\x45raseAllLogFilesResponse\x12>\n\x10log_files_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.log_files.LogFilesResult\")\n\x0cProgressData\x12\x19\n\x08progress\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"5\n\x05\x45ntry\x12\n\n\x02id\x18\x01 \x01(\r\x12\x0c\n\x04\x64\x61te\x18\x02 \x01(\t\x12\x12\n\nsize_bytes\x18\x03 \x01(\r\"\xa1\x02\n\x0eLogFilesResult\x12;\n\x06result\x18\x01 \x01(\x0e\x32+.mavsdk.rpc.log_files.LogFilesResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xbd\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x16\n\x12RESULT_NO_LOGFILES\x10\x03\x12\x12\n\x0eRESULT_TIMEOUT\x10\x04\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x05\x12\x1b\n\x17RESULT_FILE_OPEN_FAILED\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07\x32\xfc\x02\n\x0fLogFilesService\x12\x61\n\nGetEntries\x12\'.mavsdk.rpc.log_files.GetEntriesRequest\x1a(.mavsdk.rpc.log_files.GetEntriesResponse\"\x00\x12\x8c\x01\n\x18SubscribeDownloadLogFile\x12\x35.mavsdk.rpc.log_files.SubscribeDownloadLogFileRequest\x1a-.mavsdk.rpc.log_files.DownloadLogFileResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12w\n\x10\x45raseAllLogFiles\x12-.mavsdk.rpc.log_files.EraseAllLogFilesRequest\x1a..mavsdk.rpc.log_files.EraseAllLogFilesResponse\"\x04\x80\xb5\x18\x01\x42$\n\x13io.mavsdk.log_filesB\rLogFilesProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x19log_files/log_files.proto\x12\x14mavsdk.rpc.log_files\x1a\x14mavsdk_options.proto"\x13\n\x11GetEntriesRequest"\x82\x01\n\x12GetEntriesResponse\x12>\n\x10log_files_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.log_files.LogFilesResult\x12,\n\x07\x65ntries\x18\x02 \x03(\x0b\x32\x1b.mavsdk.rpc.log_files.Entry"[\n\x1fSubscribeDownloadLogFileRequest\x12*\n\x05\x65ntry\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.log_files.Entry\x12\x0c\n\x04path\x18\x02 \x01(\t"\x8f\x01\n\x17\x44ownloadLogFileResponse\x12>\n\x10log_files_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.log_files.LogFilesResult\x12\x34\n\x08progress\x18\x02 \x01(\x0b\x32".mavsdk.rpc.log_files.ProgressData"\x19\n\x17\x45raseAllLogFilesRequest"Z\n\x18\x45raseAllLogFilesResponse\x12>\n\x10log_files_result\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.log_files.LogFilesResult")\n\x0cProgressData\x12\x19\n\x08progress\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"5\n\x05\x45ntry\x12\n\n\x02id\x18\x01 \x01(\r\x12\x0c\n\x04\x64\x61te\x18\x02 \x01(\t\x12\x12\n\nsize_bytes\x18\x03 \x01(\r"\xa1\x02\n\x0eLogFilesResult\x12;\n\x06result\x18\x01 \x01(\x0e\x32+.mavsdk.rpc.log_files.LogFilesResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xbd\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x16\n\x12RESULT_NO_LOGFILES\x10\x03\x12\x12\n\x0eRESULT_TIMEOUT\x10\x04\x12\x1b\n\x17RESULT_INVALID_ARGUMENT\x10\x05\x12\x1b\n\x17RESULT_FILE_OPEN_FAILED\x10\x06\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x07\x32\xfc\x02\n\x0fLogFilesService\x12\x61\n\nGetEntries\x12\'.mavsdk.rpc.log_files.GetEntriesRequest\x1a(.mavsdk.rpc.log_files.GetEntriesResponse"\x00\x12\x8c\x01\n\x18SubscribeDownloadLogFile\x12\x35.mavsdk.rpc.log_files.SubscribeDownloadLogFileRequest\x1a-.mavsdk.rpc.log_files.DownloadLogFileResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12w\n\x10\x45raseAllLogFiles\x12-.mavsdk.rpc.log_files.EraseAllLogFilesRequest\x1a..mavsdk.rpc.log_files.EraseAllLogFilesResponse"\x04\x80\xb5\x18\x01\x42$\n\x13io.mavsdk.log_filesB\rLogFilesProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'log_files.log_files_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "log_files.log_files_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\023io.mavsdk.log_filesB\rLogFilesProto' - _globals['_PROGRESSDATA'].fields_by_name['progress']._loaded_options = None - _globals['_PROGRESSDATA'].fields_by_name['progress']._serialized_options = b'\202\265\030\003NaN' - _globals['_LOGFILESSERVICE'].methods_by_name['SubscribeDownloadLogFile']._loaded_options = None - _globals['_LOGFILESSERVICE'].methods_by_name['SubscribeDownloadLogFile']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_LOGFILESSERVICE'].methods_by_name['EraseAllLogFiles']._loaded_options = None - _globals['_LOGFILESSERVICE'].methods_by_name['EraseAllLogFiles']._serialized_options = b'\200\265\030\001' - _globals['_GETENTRIESREQUEST']._serialized_start=73 - _globals['_GETENTRIESREQUEST']._serialized_end=92 - _globals['_GETENTRIESRESPONSE']._serialized_start=95 - _globals['_GETENTRIESRESPONSE']._serialized_end=225 - _globals['_SUBSCRIBEDOWNLOADLOGFILEREQUEST']._serialized_start=227 - _globals['_SUBSCRIBEDOWNLOADLOGFILEREQUEST']._serialized_end=318 - _globals['_DOWNLOADLOGFILERESPONSE']._serialized_start=321 - _globals['_DOWNLOADLOGFILERESPONSE']._serialized_end=464 - _globals['_ERASEALLLOGFILESREQUEST']._serialized_start=466 - _globals['_ERASEALLLOGFILESREQUEST']._serialized_end=491 - _globals['_ERASEALLLOGFILESRESPONSE']._serialized_start=493 - _globals['_ERASEALLLOGFILESRESPONSE']._serialized_end=583 - _globals['_PROGRESSDATA']._serialized_start=585 - _globals['_PROGRESSDATA']._serialized_end=626 - _globals['_ENTRY']._serialized_start=628 - _globals['_ENTRY']._serialized_end=681 - _globals['_LOGFILESRESULT']._serialized_start=684 - _globals['_LOGFILESRESULT']._serialized_end=973 - _globals['_LOGFILESRESULT_RESULT']._serialized_start=784 - _globals['_LOGFILESRESULT_RESULT']._serialized_end=973 - _globals['_LOGFILESSERVICE']._serialized_start=976 - _globals['_LOGFILESSERVICE']._serialized_end=1356 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\023io.mavsdk.log_filesB\rLogFilesProto" + _globals["_PROGRESSDATA"].fields_by_name["progress"]._loaded_options = None + _globals["_PROGRESSDATA"].fields_by_name[ + "progress" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_LOGFILESSERVICE"].methods_by_name[ + "SubscribeDownloadLogFile" + ]._loaded_options = None + _globals["_LOGFILESSERVICE"].methods_by_name[ + "SubscribeDownloadLogFile" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_LOGFILESSERVICE"].methods_by_name[ + "EraseAllLogFiles" + ]._loaded_options = None + _globals["_LOGFILESSERVICE"].methods_by_name[ + "EraseAllLogFiles" + ]._serialized_options = b"\200\265\030\001" + _globals["_GETENTRIESREQUEST"]._serialized_start = 73 + _globals["_GETENTRIESREQUEST"]._serialized_end = 92 + _globals["_GETENTRIESRESPONSE"]._serialized_start = 95 + _globals["_GETENTRIESRESPONSE"]._serialized_end = 225 + _globals["_SUBSCRIBEDOWNLOADLOGFILEREQUEST"]._serialized_start = 227 + _globals["_SUBSCRIBEDOWNLOADLOGFILEREQUEST"]._serialized_end = 318 + _globals["_DOWNLOADLOGFILERESPONSE"]._serialized_start = 321 + _globals["_DOWNLOADLOGFILERESPONSE"]._serialized_end = 464 + _globals["_ERASEALLLOGFILESREQUEST"]._serialized_start = 466 + _globals["_ERASEALLLOGFILESREQUEST"]._serialized_end = 491 + _globals["_ERASEALLLOGFILESRESPONSE"]._serialized_start = 493 + _globals["_ERASEALLLOGFILESRESPONSE"]._serialized_end = 583 + _globals["_PROGRESSDATA"]._serialized_start = 585 + _globals["_PROGRESSDATA"]._serialized_end = 626 + _globals["_ENTRY"]._serialized_start = 628 + _globals["_ENTRY"]._serialized_end = 681 + _globals["_LOGFILESRESULT"]._serialized_start = 684 + _globals["_LOGFILESRESULT"]._serialized_end = 973 + _globals["_LOGFILESRESULT_RESULT"]._serialized_start = 784 + _globals["_LOGFILESRESULT_RESULT"]._serialized_end = 973 + _globals["_LOGFILESSERVICE"]._serialized_start = 976 + _globals["_LOGFILESSERVICE"]._serialized_end = 1356 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/log_files_pb2_grpc.py b/mavsdk/log_files_pb2_grpc.py index 013133bd..a585ed38 100644 --- a/mavsdk/log_files_pb2_grpc.py +++ b/mavsdk/log_files_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import log_files_pb2 as log__files_dot_log__files__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in log_files/log_files_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in log_files/log_files_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -37,20 +41,23 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.GetEntries = channel.unary_unary( - '/mavsdk.rpc.log_files.LogFilesService/GetEntries', - request_serializer=log__files_dot_log__files__pb2.GetEntriesRequest.SerializeToString, - response_deserializer=log__files_dot_log__files__pb2.GetEntriesResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.log_files.LogFilesService/GetEntries", + request_serializer=log__files_dot_log__files__pb2.GetEntriesRequest.SerializeToString, + response_deserializer=log__files_dot_log__files__pb2.GetEntriesResponse.FromString, + _registered_method=True, + ) self.SubscribeDownloadLogFile = channel.unary_stream( - '/mavsdk.rpc.log_files.LogFilesService/SubscribeDownloadLogFile', - request_serializer=log__files_dot_log__files__pb2.SubscribeDownloadLogFileRequest.SerializeToString, - response_deserializer=log__files_dot_log__files__pb2.DownloadLogFileResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.log_files.LogFilesService/SubscribeDownloadLogFile", + request_serializer=log__files_dot_log__files__pb2.SubscribeDownloadLogFileRequest.SerializeToString, + response_deserializer=log__files_dot_log__files__pb2.DownloadLogFileResponse.FromString, + _registered_method=True, + ) self.EraseAllLogFiles = channel.unary_unary( - '/mavsdk.rpc.log_files.LogFilesService/EraseAllLogFiles', - request_serializer=log__files_dot_log__files__pb2.EraseAllLogFilesRequest.SerializeToString, - response_deserializer=log__files_dot_log__files__pb2.EraseAllLogFilesResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.log_files.LogFilesService/EraseAllLogFiles", + request_serializer=log__files_dot_log__files__pb2.EraseAllLogFilesRequest.SerializeToString, + response_deserializer=log__files_dot_log__files__pb2.EraseAllLogFilesResponse.FromString, + _registered_method=True, + ) class LogFilesServiceServicer(object): @@ -59,72 +66,74 @@ class LogFilesServiceServicer(object): """ def GetEntries(self, request, context): - """Get List of log files. - """ + """Get List of log files.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeDownloadLogFile(self, request, context): - """Download log file. - """ + """Download log file.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def EraseAllLogFiles(self, request, context): - """Erase all log files. - """ + """Erase all log files.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_LogFilesServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'GetEntries': grpc.unary_unary_rpc_method_handler( - servicer.GetEntries, - request_deserializer=log__files_dot_log__files__pb2.GetEntriesRequest.FromString, - response_serializer=log__files_dot_log__files__pb2.GetEntriesResponse.SerializeToString, - ), - 'SubscribeDownloadLogFile': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeDownloadLogFile, - request_deserializer=log__files_dot_log__files__pb2.SubscribeDownloadLogFileRequest.FromString, - response_serializer=log__files_dot_log__files__pb2.DownloadLogFileResponse.SerializeToString, - ), - 'EraseAllLogFiles': grpc.unary_unary_rpc_method_handler( - servicer.EraseAllLogFiles, - request_deserializer=log__files_dot_log__files__pb2.EraseAllLogFilesRequest.FromString, - response_serializer=log__files_dot_log__files__pb2.EraseAllLogFilesResponse.SerializeToString, - ), + "GetEntries": grpc.unary_unary_rpc_method_handler( + servicer.GetEntries, + request_deserializer=log__files_dot_log__files__pb2.GetEntriesRequest.FromString, + response_serializer=log__files_dot_log__files__pb2.GetEntriesResponse.SerializeToString, + ), + "SubscribeDownloadLogFile": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeDownloadLogFile, + request_deserializer=log__files_dot_log__files__pb2.SubscribeDownloadLogFileRequest.FromString, + response_serializer=log__files_dot_log__files__pb2.DownloadLogFileResponse.SerializeToString, + ), + "EraseAllLogFiles": grpc.unary_unary_rpc_method_handler( + servicer.EraseAllLogFiles, + request_deserializer=log__files_dot_log__files__pb2.EraseAllLogFilesRequest.FromString, + response_serializer=log__files_dot_log__files__pb2.EraseAllLogFilesResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.log_files.LogFilesService', rpc_method_handlers) + "mavsdk.rpc.log_files.LogFilesService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.log_files.LogFilesService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.log_files.LogFilesService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class LogFilesService(object): """Allow to download log files from the vehicle after a flight is complete. For log streaming during flight check the logging plugin. """ @staticmethod - def GetEntries(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetEntries( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.log_files.LogFilesService/GetEntries', + "/mavsdk.rpc.log_files.LogFilesService/GetEntries", log__files_dot_log__files__pb2.GetEntriesRequest.SerializeToString, log__files_dot_log__files__pb2.GetEntriesResponse.FromString, options, @@ -135,23 +144,26 @@ def GetEntries(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeDownloadLogFile(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeDownloadLogFile( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.log_files.LogFilesService/SubscribeDownloadLogFile', + "/mavsdk.rpc.log_files.LogFilesService/SubscribeDownloadLogFile", log__files_dot_log__files__pb2.SubscribeDownloadLogFileRequest.SerializeToString, log__files_dot_log__files__pb2.DownloadLogFileResponse.FromString, options, @@ -162,23 +174,26 @@ def SubscribeDownloadLogFile(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def EraseAllLogFiles(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def EraseAllLogFiles( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.log_files.LogFilesService/EraseAllLogFiles', + "/mavsdk.rpc.log_files.LogFilesService/EraseAllLogFiles", log__files_dot_log__files__pb2.EraseAllLogFilesRequest.SerializeToString, log__files_dot_log__files__pb2.EraseAllLogFilesResponse.FromString, options, @@ -189,4 +204,5 @@ def EraseAllLogFiles(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/log_streaming.py b/mavsdk/log_streaming.py index 966880bd..0a97a725 100644 --- a/mavsdk/log_streaming.py +++ b/mavsdk/log_streaming.py @@ -8,111 +8,92 @@ class LogStreamingRaw: """ - Raw logging data type + Raw logging data type - Parameters - ---------- - data_base64 : std::string - Ulog file stream data encoded as base64 + Parameters + ---------- + data_base64 : std::string + Ulog file stream data encoded as base64 - """ - - + """ - def __init__( - self, - data_base64): - """ Initializes the LogStreamingRaw object """ + def __init__(self, data_base64): + """Initializes the LogStreamingRaw object""" self.data_base64 = data_base64 def __eq__(self, to_compare): - """ Checks if two LogStreamingRaw are the same """ + """Checks if two LogStreamingRaw are the same""" try: # Try to compare - this likely fails when it is compared to a non # LogStreamingRaw object - return \ - (self.data_base64 == to_compare.data_base64) + return self.data_base64 == to_compare.data_base64 except AttributeError: return False def __str__(self): - """ LogStreamingRaw in string representation """ - struct_repr = ", ".join([ - "data_base64: " + str(self.data_base64) - ]) + """LogStreamingRaw in string representation""" + struct_repr = ", ".join(["data_base64: " + str(self.data_base64)]) return f"LogStreamingRaw: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcLogStreamingRaw): - """ Translates a gRPC struct to the SDK equivalent """ - return LogStreamingRaw( - - rpcLogStreamingRaw.data_base64 - ) + """Translates a gRPC struct to the SDK equivalent""" + return LogStreamingRaw(rpcLogStreamingRaw.data_base64) def translate_to_rpc(self, rpcLogStreamingRaw): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcLogStreamingRaw.data_base64 = self.data_base64 - - - class LogStreamingResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for logging requests + Possible results returned for logging requests - Values - ------ - SUCCESS - Request succeeded + Values + ------ + SUCCESS + Request succeeded - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - System busy + BUSY + System busy - COMMAND_DENIED - Command denied + COMMAND_DENIED + Command denied - TIMEOUT - Timeout + TIMEOUT + Timeout - UNSUPPORTED - Unsupported + UNSUPPORTED + Unsupported - UNKNOWN - Unknown error + UNKNOWN + Unknown error - """ + """ - SUCCESS = 0 NO_SYSTEM = 1 CONNECTION_ERROR = 2 @@ -142,89 +123,79 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_SUCCESS: return LogStreamingResult.Result.SUCCESS if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_NO_SYSTEM: return LogStreamingResult.Result.NO_SYSTEM - if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == log_streaming_pb2.LogStreamingResult.RESULT_CONNECTION_ERROR + ): return LogStreamingResult.Result.CONNECTION_ERROR if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_BUSY: return LogStreamingResult.Result.BUSY - if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_COMMAND_DENIED: + if ( + rpc_enum_value + == log_streaming_pb2.LogStreamingResult.RESULT_COMMAND_DENIED + ): return LogStreamingResult.Result.COMMAND_DENIED if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_TIMEOUT: return LogStreamingResult.Result.TIMEOUT - if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_UNSUPPORTED: + if ( + rpc_enum_value + == log_streaming_pb2.LogStreamingResult.RESULT_UNSUPPORTED + ): return LogStreamingResult.Result.UNSUPPORTED if rpc_enum_value == log_streaming_pb2.LogStreamingResult.RESULT_UNKNOWN: return LogStreamingResult.Result.UNKNOWN def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the LogStreamingResult object """ + def __init__(self, result, result_str): + """Initializes the LogStreamingResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two LogStreamingResult are the same """ + """Checks if two LogStreamingResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # LogStreamingResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ LogStreamingResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """LogStreamingResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"LogStreamingResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcLogStreamingResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return LogStreamingResult( - - LogStreamingResult.Result.translate_from_rpc(rpcLogStreamingResult.result), - - - rpcLogStreamingResult.result_str - ) + LogStreamingResult.Result.translate_from_rpc(rpcLogStreamingResult.result), + rpcLogStreamingResult.result_str, + ) def translate_to_rpc(self, rpcLogStreamingResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcLogStreamingResult.result = self.result.translate_to_rpc() - - - - - - rpcLogStreamingResult.result_str = self.result_str - - - + rpcLogStreamingResult.result_str = self.result_str class LogStreamingError(Exception): - """ Raised when a LogStreamingResult is a fail code """ + """Raised when a LogStreamingResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -237,74 +208,68 @@ def __str__(self): class LogStreaming(AsyncBase): """ - Provide log streaming data. + Provide log streaming data. - Generated by dcsdkgen - MAVSDK LogStreaming API + Generated by dcsdkgen - MAVSDK LogStreaming API """ # Plugin name name = "LogStreaming" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = log_streaming_pb2_grpc.LogStreamingServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return LogStreamingResult.translate_from_rpc(response.log_streaming_result) - async def start_log_streaming(self): """ - Start streaming logging data. + Start streaming logging data. - Raises - ------ - LogStreamingError - If the request fails. The error contains the reason for the failure. + Raises + ------ + LogStreamingError + If the request fails. The error contains the reason for the failure. """ request = log_streaming_pb2.StartLogStreamingRequest() response = await self._stub.StartLogStreaming(request) - result = self._extract_result(response) if result.result != LogStreamingResult.Result.SUCCESS: raise LogStreamingError(result, "start_log_streaming()") - async def stop_log_streaming(self): """ - Stop streaming logging data. + Stop streaming logging data. - Raises - ------ - LogStreamingError - If the request fails. The error contains the reason for the failure. + Raises + ------ + LogStreamingError + If the request fails. The error contains the reason for the failure. """ request = log_streaming_pb2.StopLogStreamingRequest() response = await self._stub.StopLogStreaming(request) - result = self._extract_result(response) if result.result != LogStreamingResult.Result.SUCCESS: raise LogStreamingError(result, "stop_log_streaming()") - async def log_streaming_raw(self): """ - Subscribe to logging messages + Subscribe to logging messages + + Yields + ------- + logging_raw : LogStreamingRaw + A message containing logged data - Yields - ------- - logging_raw : LogStreamingRaw - A message containing logged data - """ request = log_streaming_pb2.SubscribeLogStreamingRawRequest() @@ -312,9 +277,6 @@ async def log_streaming_raw(self): try: async for response in log_streaming_raw_stream: - - - yield LogStreamingRaw.translate_from_rpc(response.logging_raw) finally: - log_streaming_raw_stream.cancel() \ No newline at end of file + log_streaming_raw_stream.cancel() diff --git a/mavsdk/log_streaming_pb2.py b/mavsdk/log_streaming_pb2.py index 6277fba3..13dc7f12 100644 --- a/mavsdk/log_streaming_pb2.py +++ b/mavsdk/log_streaming_pb2.py @@ -4,18 +4,15 @@ # source: log_streaming/log_streaming.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'log_streaming/log_streaming.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "log_streaming/log_streaming.proto" ) # @@protoc_insertion_point(imports) @@ -25,34 +22,44 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'log_streaming.log_streaming_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "log_streaming.log_streaming_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\027io.mavsdk.log_streamingB\021LogStreamingProto' - _globals['_LOGSTREAMINGSERVICE'].methods_by_name['SubscribeLogStreamingRaw']._loaded_options = None - _globals['_LOGSTREAMINGSERVICE'].methods_by_name['SubscribeLogStreamingRaw']._serialized_options = b'\200\265\030\000' - _globals['_STARTLOGSTREAMINGREQUEST']._serialized_start=85 - _globals['_STARTLOGSTREAMINGREQUEST']._serialized_end=111 - _globals['_STARTLOGSTREAMINGRESPONSE']._serialized_start=113 - _globals['_STARTLOGSTREAMINGRESPONSE']._serialized_end=216 - _globals['_STOPLOGSTREAMINGREQUEST']._serialized_start=218 - _globals['_STOPLOGSTREAMINGREQUEST']._serialized_end=243 - _globals['_STOPLOGSTREAMINGRESPONSE']._serialized_start=245 - _globals['_STOPLOGSTREAMINGRESPONSE']._serialized_end=347 - _globals['_SUBSCRIBELOGSTREAMINGRAWREQUEST']._serialized_start=349 - _globals['_SUBSCRIBELOGSTREAMINGRAWREQUEST']._serialized_end=382 - _globals['_LOGSTREAMINGRAWRESPONSE']._serialized_start=384 - _globals['_LOGSTREAMINGRAWRESPONSE']._serialized_end=473 - _globals['_LOGSTREAMINGRAW']._serialized_start=475 - _globals['_LOGSTREAMINGRAW']._serialized_end=513 - _globals['_LOGSTREAMINGRESULT']._serialized_start=516 - _globals['_LOGSTREAMINGRESULT']._serialized_end=815 - _globals['_LOGSTREAMINGRESULT_RESULT']._serialized_start=628 - _globals['_LOGSTREAMINGRESULT_RESULT']._serialized_end=815 - _globals['_LOGSTREAMINGSERVICE']._serialized_start=818 - _globals['_LOGSTREAMINGSERVICE']._serialized_end=1239 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\027io.mavsdk.log_streamingB\021LogStreamingProto" + _globals["_LOGSTREAMINGSERVICE"].methods_by_name[ + "SubscribeLogStreamingRaw" + ]._loaded_options = None + _globals["_LOGSTREAMINGSERVICE"].methods_by_name[ + "SubscribeLogStreamingRaw" + ]._serialized_options = b"\200\265\030\000" + _globals["_STARTLOGSTREAMINGREQUEST"]._serialized_start = 85 + _globals["_STARTLOGSTREAMINGREQUEST"]._serialized_end = 111 + _globals["_STARTLOGSTREAMINGRESPONSE"]._serialized_start = 113 + _globals["_STARTLOGSTREAMINGRESPONSE"]._serialized_end = 216 + _globals["_STOPLOGSTREAMINGREQUEST"]._serialized_start = 218 + _globals["_STOPLOGSTREAMINGREQUEST"]._serialized_end = 243 + _globals["_STOPLOGSTREAMINGRESPONSE"]._serialized_start = 245 + _globals["_STOPLOGSTREAMINGRESPONSE"]._serialized_end = 347 + _globals["_SUBSCRIBELOGSTREAMINGRAWREQUEST"]._serialized_start = 349 + _globals["_SUBSCRIBELOGSTREAMINGRAWREQUEST"]._serialized_end = 382 + _globals["_LOGSTREAMINGRAWRESPONSE"]._serialized_start = 384 + _globals["_LOGSTREAMINGRAWRESPONSE"]._serialized_end = 473 + _globals["_LOGSTREAMINGRAW"]._serialized_start = 475 + _globals["_LOGSTREAMINGRAW"]._serialized_end = 513 + _globals["_LOGSTREAMINGRESULT"]._serialized_start = 516 + _globals["_LOGSTREAMINGRESULT"]._serialized_end = 815 + _globals["_LOGSTREAMINGRESULT_RESULT"]._serialized_start = 628 + _globals["_LOGSTREAMINGRESULT_RESULT"]._serialized_end = 815 + _globals["_LOGSTREAMINGSERVICE"]._serialized_start = 818 + _globals["_LOGSTREAMINGSERVICE"]._serialized_end = 1239 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/log_streaming_pb2_grpc.py b/mavsdk/log_streaming_pb2_grpc.py index d98abb22..cf7f9016 100644 --- a/mavsdk/log_streaming_pb2_grpc.py +++ b/mavsdk/log_streaming_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import log_streaming_pb2 as log__streaming_dot_log__streaming__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in log_streaming/log_streaming_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in log_streaming/log_streaming_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class LogStreamingServiceStub(object): - """Provide log streaming data. - """ + """Provide log streaming data.""" def __init__(self, channel): """Constructor. @@ -36,92 +39,95 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.StartLogStreaming = channel.unary_unary( - '/mavsdk.rpc.log_streaming.LogStreamingService/StartLogStreaming', - request_serializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingRequest.SerializeToString, - response_deserializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.log_streaming.LogStreamingService/StartLogStreaming", + request_serializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingRequest.SerializeToString, + response_deserializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingResponse.FromString, + _registered_method=True, + ) self.StopLogStreaming = channel.unary_unary( - '/mavsdk.rpc.log_streaming.LogStreamingService/StopLogStreaming', - request_serializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingRequest.SerializeToString, - response_deserializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.log_streaming.LogStreamingService/StopLogStreaming", + request_serializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingRequest.SerializeToString, + response_deserializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingResponse.FromString, + _registered_method=True, + ) self.SubscribeLogStreamingRaw = channel.unary_stream( - '/mavsdk.rpc.log_streaming.LogStreamingService/SubscribeLogStreamingRaw', - request_serializer=log__streaming_dot_log__streaming__pb2.SubscribeLogStreamingRawRequest.SerializeToString, - response_deserializer=log__streaming_dot_log__streaming__pb2.LogStreamingRawResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.log_streaming.LogStreamingService/SubscribeLogStreamingRaw", + request_serializer=log__streaming_dot_log__streaming__pb2.SubscribeLogStreamingRawRequest.SerializeToString, + response_deserializer=log__streaming_dot_log__streaming__pb2.LogStreamingRawResponse.FromString, + _registered_method=True, + ) class LogStreamingServiceServicer(object): - """Provide log streaming data. - """ + """Provide log streaming data.""" def StartLogStreaming(self, request, context): - """Start streaming logging data. - """ + """Start streaming logging data.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StopLogStreaming(self, request, context): - """Stop streaming logging data. - """ + """Stop streaming logging data.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeLogStreamingRaw(self, request, context): - """Subscribe to logging messages - """ + """Subscribe to logging messages""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_LogStreamingServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'StartLogStreaming': grpc.unary_unary_rpc_method_handler( - servicer.StartLogStreaming, - request_deserializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingRequest.FromString, - response_serializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingResponse.SerializeToString, - ), - 'StopLogStreaming': grpc.unary_unary_rpc_method_handler( - servicer.StopLogStreaming, - request_deserializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingRequest.FromString, - response_serializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingResponse.SerializeToString, - ), - 'SubscribeLogStreamingRaw': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeLogStreamingRaw, - request_deserializer=log__streaming_dot_log__streaming__pb2.SubscribeLogStreamingRawRequest.FromString, - response_serializer=log__streaming_dot_log__streaming__pb2.LogStreamingRawResponse.SerializeToString, - ), + "StartLogStreaming": grpc.unary_unary_rpc_method_handler( + servicer.StartLogStreaming, + request_deserializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingRequest.FromString, + response_serializer=log__streaming_dot_log__streaming__pb2.StartLogStreamingResponse.SerializeToString, + ), + "StopLogStreaming": grpc.unary_unary_rpc_method_handler( + servicer.StopLogStreaming, + request_deserializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingRequest.FromString, + response_serializer=log__streaming_dot_log__streaming__pb2.StopLogStreamingResponse.SerializeToString, + ), + "SubscribeLogStreamingRaw": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeLogStreamingRaw, + request_deserializer=log__streaming_dot_log__streaming__pb2.SubscribeLogStreamingRawRequest.FromString, + response_serializer=log__streaming_dot_log__streaming__pb2.LogStreamingRawResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.log_streaming.LogStreamingService', rpc_method_handlers) + "mavsdk.rpc.log_streaming.LogStreamingService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.log_streaming.LogStreamingService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.log_streaming.LogStreamingService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class LogStreamingService(object): - """Provide log streaming data. - """ + """Provide log streaming data.""" @staticmethod - def StartLogStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartLogStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.log_streaming.LogStreamingService/StartLogStreaming', + "/mavsdk.rpc.log_streaming.LogStreamingService/StartLogStreaming", log__streaming_dot_log__streaming__pb2.StartLogStreamingRequest.SerializeToString, log__streaming_dot_log__streaming__pb2.StartLogStreamingResponse.FromString, options, @@ -132,23 +138,26 @@ def StartLogStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StopLogStreaming(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StopLogStreaming( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.log_streaming.LogStreamingService/StopLogStreaming', + "/mavsdk.rpc.log_streaming.LogStreamingService/StopLogStreaming", log__streaming_dot_log__streaming__pb2.StopLogStreamingRequest.SerializeToString, log__streaming_dot_log__streaming__pb2.StopLogStreamingResponse.FromString, options, @@ -159,23 +168,26 @@ def StopLogStreaming(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeLogStreamingRaw(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeLogStreamingRaw( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.log_streaming.LogStreamingService/SubscribeLogStreamingRaw', + "/mavsdk.rpc.log_streaming.LogStreamingService/SubscribeLogStreamingRaw", log__streaming_dot_log__streaming__pb2.SubscribeLogStreamingRawRequest.SerializeToString, log__streaming_dot_log__streaming__pb2.LogStreamingRawResponse.FromString, options, @@ -186,4 +198,5 @@ def SubscribeLogStreamingRaw(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/manual_control.py b/mavsdk/manual_control.py index 577bfbcb..cf03ff6f 100644 --- a/mavsdk/manual_control.py +++ b/mavsdk/manual_control.py @@ -8,56 +8,53 @@ class ManualControlResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for manual control requests. + Possible results returned for manual control requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request was successful + SUCCESS + Request was successful - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - TIMEOUT - Request timed out + TIMEOUT + Request timed out - INPUT_OUT_OF_RANGE - Input out of range + INPUT_OUT_OF_RANGE + Input out of range - INPUT_NOT_SET - No Input set + INPUT_NOT_SET + No Input set - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -90,91 +87,89 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_UNKNOWN: return ManualControlResult.Result.UNKNOWN if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_SUCCESS: return ManualControlResult.Result.SUCCESS - if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == manual_control_pb2.ManualControlResult.RESULT_NO_SYSTEM + ): return ManualControlResult.Result.NO_SYSTEM - if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == manual_control_pb2.ManualControlResult.RESULT_CONNECTION_ERROR + ): return ManualControlResult.Result.CONNECTION_ERROR if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_BUSY: return ManualControlResult.Result.BUSY - if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_COMMAND_DENIED: + if ( + rpc_enum_value + == manual_control_pb2.ManualControlResult.RESULT_COMMAND_DENIED + ): return ManualControlResult.Result.COMMAND_DENIED if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_TIMEOUT: return ManualControlResult.Result.TIMEOUT - if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_INPUT_OUT_OF_RANGE: + if ( + rpc_enum_value + == manual_control_pb2.ManualControlResult.RESULT_INPUT_OUT_OF_RANGE + ): return ManualControlResult.Result.INPUT_OUT_OF_RANGE - if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_INPUT_NOT_SET: + if ( + rpc_enum_value + == manual_control_pb2.ManualControlResult.RESULT_INPUT_NOT_SET + ): return ManualControlResult.Result.INPUT_NOT_SET def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ManualControlResult object """ + def __init__(self, result, result_str): + """Initializes the ManualControlResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ManualControlResult are the same """ + """Checks if two ManualControlResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ManualControlResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ManualControlResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ManualControlResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ManualControlResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcManualControlResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ManualControlResult( - - ManualControlResult.Result.translate_from_rpc(rpcManualControlResult.result), - - - rpcManualControlResult.result_str - ) + ManualControlResult.Result.translate_from_rpc( + rpcManualControlResult.result + ), + rpcManualControlResult.result_str, + ) def translate_to_rpc(self, rpcManualControlResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcManualControlResult.result = self.result.translate_to_rpc() - - - - - - rpcManualControlResult.result_str = self.result_str - - - + rpcManualControlResult.result_str = self.result_str class ManualControlError(Exception): - """ Raised when a ManualControlResult is a fail code """ + """Raised when a ManualControlResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -187,95 +182,89 @@ def __str__(self): class ManualControl(AsyncBase): """ - Enable manual control using e.g. a joystick or gamepad. + Enable manual control using e.g. a joystick or gamepad. - Generated by dcsdkgen - MAVSDK ManualControl API + Generated by dcsdkgen - MAVSDK ManualControl API """ # Plugin name name = "ManualControl" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = manual_control_pb2_grpc.ManualControlServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ManualControlResult.translate_from_rpc(response.manual_control_result) - async def start_position_control(self): """ - Start position control using e.g. joystick input. + Start position control using e.g. joystick input. - Requires manual control input to be sent regularly already. - Requires a valid position using e.g. GPS, external vision, or optical flow. + Requires manual control input to be sent regularly already. + Requires a valid position using e.g. GPS, external vision, or optical flow. - Raises - ------ - ManualControlError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ManualControlError + If the request fails. The error contains the reason for the failure. """ request = manual_control_pb2.StartPositionControlRequest() response = await self._stub.StartPositionControl(request) - result = self._extract_result(response) if result.result != ManualControlResult.Result.SUCCESS: raise ManualControlError(result, "start_position_control()") - async def start_altitude_control(self): """ - Start altitude control + Start altitude control - Requires manual control input to be sent regularly already. - Does not require a valid position e.g. GPS. + Requires manual control input to be sent regularly already. + Does not require a valid position e.g. GPS. - Raises - ------ - ManualControlError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ManualControlError + If the request fails. The error contains the reason for the failure. """ request = manual_control_pb2.StartAltitudeControlRequest() response = await self._stub.StartAltitudeControl(request) - result = self._extract_result(response) if result.result != ManualControlResult.Result.SUCCESS: raise ManualControlError(result, "start_altitude_control()") - async def set_manual_control_input(self, x, y, z, r): """ - Set manual control input + Set manual control input - The manual control input needs to be sent at a rate high enough to prevent - triggering of RC loss, a good minimum rate is 10 Hz. + The manual control input needs to be sent at a rate high enough to prevent + triggering of RC loss, a good minimum rate is 10 Hz. - Parameters - ---------- - x : float - value between -1. to 1. negative -> backwards, positive -> forwards + Parameters + ---------- + x : float + value between -1. to 1. negative -> backwards, positive -> forwards - y : float - value between -1. to 1. negative -> left, positive -> right + y : float + value between -1. to 1. negative -> left, positive -> right - z : float - value between -1. to 1. negative -> down, positive -> up (usually for now, for multicopter 0 to 1 is expected) + z : float + value between -1. to 1. negative -> down, positive -> up (usually for now, for multicopter 0 to 1 is expected) - r : float - value between -1. to 1. negative -> turn anti-clockwise (towards the left), positive -> turn clockwise (towards the right) + r : float + value between -1. to 1. negative -> turn anti-clockwise (towards the left), positive -> turn clockwise (towards the right) - Raises - ------ - ManualControlError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ManualControlError + If the request fails. The error contains the reason for the failure. """ request = manual_control_pb2.SetManualControlInputRequest() @@ -285,9 +274,7 @@ async def set_manual_control_input(self, x, y, z, r): request.r = r response = await self._stub.SetManualControlInput(request) - result = self._extract_result(response) if result.result != ManualControlResult.Result.SUCCESS: raise ManualControlError(result, "set_manual_control_input()", x, y, z, r) - \ No newline at end of file diff --git a/mavsdk/manual_control_pb2.py b/mavsdk/manual_control_pb2.py index 87fd97bd..3fd38b94 100644 --- a/mavsdk/manual_control_pb2.py +++ b/mavsdk/manual_control_pb2.py @@ -4,18 +4,15 @@ # source: manual_control/manual_control.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'manual_control/manual_control.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "manual_control/manual_control.proto" ) # @@protoc_insertion_point(imports) @@ -25,32 +22,42 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'manual_control.manual_control_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "manual_control.manual_control_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\030io.mavsdk.manual_controlB\022ManualControlProto' - _globals['_MANUALCONTROLSERVICE'].methods_by_name['SetManualControlInput']._loaded_options = None - _globals['_MANUALCONTROLSERVICE'].methods_by_name['SetManualControlInput']._serialized_options = b'\200\265\030\001' - _globals['_STARTPOSITIONCONTROLREQUEST']._serialized_start=88 - _globals['_STARTPOSITIONCONTROLREQUEST']._serialized_end=117 - _globals['_STARTPOSITIONCONTROLRESPONSE']._serialized_start=119 - _globals['_STARTPOSITIONCONTROLRESPONSE']._serialized_end=228 - _globals['_STARTALTITUDECONTROLREQUEST']._serialized_start=230 - _globals['_STARTALTITUDECONTROLREQUEST']._serialized_end=259 - _globals['_STARTALTITUDECONTROLRESPONSE']._serialized_start=261 - _globals['_STARTALTITUDECONTROLRESPONSE']._serialized_end=370 - _globals['_SETMANUALCONTROLINPUTREQUEST']._serialized_start=372 - _globals['_SETMANUALCONTROLINPUTREQUEST']._serialized_end=446 - _globals['_SETMANUALCONTROLINPUTRESPONSE']._serialized_start=448 - _globals['_SETMANUALCONTROLINPUTRESPONSE']._serialized_end=558 - _globals['_MANUALCONTROLRESULT']._serialized_start=561 - _globals['_MANUALCONTROLRESULT']._serialized_end=896 - _globals['_MANUALCONTROLRESULT_RESULT']._serialized_start=676 - _globals['_MANUALCONTROLRESULT_RESULT']._serialized_end=896 - _globals['_MANUALCONTROLSERVICE']._serialized_start=899 - _globals['_MANUALCONTROLSERVICE']._serialized_end=1348 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\030io.mavsdk.manual_controlB\022ManualControlProto" + _globals["_MANUALCONTROLSERVICE"].methods_by_name[ + "SetManualControlInput" + ]._loaded_options = None + _globals["_MANUALCONTROLSERVICE"].methods_by_name[ + "SetManualControlInput" + ]._serialized_options = b"\200\265\030\001" + _globals["_STARTPOSITIONCONTROLREQUEST"]._serialized_start = 88 + _globals["_STARTPOSITIONCONTROLREQUEST"]._serialized_end = 117 + _globals["_STARTPOSITIONCONTROLRESPONSE"]._serialized_start = 119 + _globals["_STARTPOSITIONCONTROLRESPONSE"]._serialized_end = 228 + _globals["_STARTALTITUDECONTROLREQUEST"]._serialized_start = 230 + _globals["_STARTALTITUDECONTROLREQUEST"]._serialized_end = 259 + _globals["_STARTALTITUDECONTROLRESPONSE"]._serialized_start = 261 + _globals["_STARTALTITUDECONTROLRESPONSE"]._serialized_end = 370 + _globals["_SETMANUALCONTROLINPUTREQUEST"]._serialized_start = 372 + _globals["_SETMANUALCONTROLINPUTREQUEST"]._serialized_end = 446 + _globals["_SETMANUALCONTROLINPUTRESPONSE"]._serialized_start = 448 + _globals["_SETMANUALCONTROLINPUTRESPONSE"]._serialized_end = 558 + _globals["_MANUALCONTROLRESULT"]._serialized_start = 561 + _globals["_MANUALCONTROLRESULT"]._serialized_end = 896 + _globals["_MANUALCONTROLRESULT_RESULT"]._serialized_start = 676 + _globals["_MANUALCONTROLRESULT_RESULT"]._serialized_end = 896 + _globals["_MANUALCONTROLSERVICE"]._serialized_start = 899 + _globals["_MANUALCONTROLSERVICE"]._serialized_end = 1348 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/manual_control_pb2_grpc.py b/mavsdk/manual_control_pb2_grpc.py index 32144c33..4b2d2ec6 100644 --- a/mavsdk/manual_control_pb2_grpc.py +++ b/mavsdk/manual_control_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import manual_control_pb2 as manual__control_dot_manual__control__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in manual_control/manual_control_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in manual_control/manual_control_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ManualControlServiceStub(object): - """Enable manual control using e.g. a joystick or gamepad. - """ + """Enable manual control using e.g. a joystick or gamepad.""" def __init__(self, channel): """Constructor. @@ -36,25 +39,27 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.StartPositionControl = channel.unary_unary( - '/mavsdk.rpc.manual_control.ManualControlService/StartPositionControl', - request_serializer=manual__control_dot_manual__control__pb2.StartPositionControlRequest.SerializeToString, - response_deserializer=manual__control_dot_manual__control__pb2.StartPositionControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.manual_control.ManualControlService/StartPositionControl", + request_serializer=manual__control_dot_manual__control__pb2.StartPositionControlRequest.SerializeToString, + response_deserializer=manual__control_dot_manual__control__pb2.StartPositionControlResponse.FromString, + _registered_method=True, + ) self.StartAltitudeControl = channel.unary_unary( - '/mavsdk.rpc.manual_control.ManualControlService/StartAltitudeControl', - request_serializer=manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.SerializeToString, - response_deserializer=manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.manual_control.ManualControlService/StartAltitudeControl", + request_serializer=manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.SerializeToString, + response_deserializer=manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.FromString, + _registered_method=True, + ) self.SetManualControlInput = channel.unary_unary( - '/mavsdk.rpc.manual_control.ManualControlService/SetManualControlInput', - request_serializer=manual__control_dot_manual__control__pb2.SetManualControlInputRequest.SerializeToString, - response_deserializer=manual__control_dot_manual__control__pb2.SetManualControlInputResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.manual_control.ManualControlService/SetManualControlInput", + request_serializer=manual__control_dot_manual__control__pb2.SetManualControlInputRequest.SerializeToString, + response_deserializer=manual__control_dot_manual__control__pb2.SetManualControlInputResponse.FromString, + _registered_method=True, + ) class ManualControlServiceServicer(object): - """Enable manual control using e.g. a joystick or gamepad. - """ + """Enable manual control using e.g. a joystick or gamepad.""" def StartPositionControl(self, request, context): """ @@ -64,8 +69,8 @@ def StartPositionControl(self, request, context): Requires a valid position using e.g. GPS, external vision, or optical flow. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StartAltitudeControl(self, request, context): """ @@ -75,8 +80,8 @@ def StartAltitudeControl(self, request, context): Does not require a valid position e.g. GPS. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetManualControlInput(self, request, context): """ @@ -86,54 +91,58 @@ def SetManualControlInput(self, request, context): triggering of RC loss, a good minimum rate is 10 Hz. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ManualControlServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'StartPositionControl': grpc.unary_unary_rpc_method_handler( - servicer.StartPositionControl, - request_deserializer=manual__control_dot_manual__control__pb2.StartPositionControlRequest.FromString, - response_serializer=manual__control_dot_manual__control__pb2.StartPositionControlResponse.SerializeToString, - ), - 'StartAltitudeControl': grpc.unary_unary_rpc_method_handler( - servicer.StartAltitudeControl, - request_deserializer=manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.FromString, - response_serializer=manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.SerializeToString, - ), - 'SetManualControlInput': grpc.unary_unary_rpc_method_handler( - servicer.SetManualControlInput, - request_deserializer=manual__control_dot_manual__control__pb2.SetManualControlInputRequest.FromString, - response_serializer=manual__control_dot_manual__control__pb2.SetManualControlInputResponse.SerializeToString, - ), + "StartPositionControl": grpc.unary_unary_rpc_method_handler( + servicer.StartPositionControl, + request_deserializer=manual__control_dot_manual__control__pb2.StartPositionControlRequest.FromString, + response_serializer=manual__control_dot_manual__control__pb2.StartPositionControlResponse.SerializeToString, + ), + "StartAltitudeControl": grpc.unary_unary_rpc_method_handler( + servicer.StartAltitudeControl, + request_deserializer=manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.FromString, + response_serializer=manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.SerializeToString, + ), + "SetManualControlInput": grpc.unary_unary_rpc_method_handler( + servicer.SetManualControlInput, + request_deserializer=manual__control_dot_manual__control__pb2.SetManualControlInputRequest.FromString, + response_serializer=manual__control_dot_manual__control__pb2.SetManualControlInputResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.manual_control.ManualControlService', rpc_method_handlers) + "mavsdk.rpc.manual_control.ManualControlService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.manual_control.ManualControlService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.manual_control.ManualControlService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ManualControlService(object): - """Enable manual control using e.g. a joystick or gamepad. - """ + """Enable manual control using e.g. a joystick or gamepad.""" @staticmethod - def StartPositionControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartPositionControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.manual_control.ManualControlService/StartPositionControl', + "/mavsdk.rpc.manual_control.ManualControlService/StartPositionControl", manual__control_dot_manual__control__pb2.StartPositionControlRequest.SerializeToString, manual__control_dot_manual__control__pb2.StartPositionControlResponse.FromString, options, @@ -144,23 +153,26 @@ def StartPositionControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StartAltitudeControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartAltitudeControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.manual_control.ManualControlService/StartAltitudeControl', + "/mavsdk.rpc.manual_control.ManualControlService/StartAltitudeControl", manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.SerializeToString, manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.FromString, options, @@ -171,23 +183,26 @@ def StartAltitudeControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetManualControlInput(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetManualControlInput( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.manual_control.ManualControlService/SetManualControlInput', + "/mavsdk.rpc.manual_control.ManualControlService/SetManualControlInput", manual__control_dot_manual__control__pb2.SetManualControlInputRequest.SerializeToString, manual__control_dot_manual__control__pb2.SetManualControlInputResponse.FromString, options, @@ -198,4 +213,5 @@ def SetManualControlInput(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/mavlink_direct.py b/mavsdk/mavlink_direct.py index 2bf45cf9..91a9c441 100644 --- a/mavsdk/mavlink_direct.py +++ b/mavsdk/mavlink_direct.py @@ -8,41 +8,40 @@ class MavlinkMessage: """ - A complete MAVLink message with all header information and fields + A complete MAVLink message with all header information and fields - Parameters - ---------- - message_name : std::string - MAVLink message name (e.g., "HEARTBEAT", "GLOBAL_POSITION_INT") + Parameters + ---------- + message_name : std::string + MAVLink message name (e.g., "HEARTBEAT", "GLOBAL_POSITION_INT") - system_id : uint32_t - System ID of the sender (for received messages) + system_id : uint32_t + System ID of the sender (for received messages) - component_id : uint32_t - Component ID of the sender (for received messages) + component_id : uint32_t + Component ID of the sender (for received messages) - target_system_id : uint32_t - Target system ID (for sending, 0 for broadcast) + target_system_id : uint32_t + Target system ID (for sending, 0 for broadcast) - target_component_id : uint32_t - Target component ID (for sending, 0 for broadcast) + target_component_id : uint32_t + Target component ID (for sending, 0 for broadcast) - fields_json : std::string - All message fields as single JSON object + fields_json : std::string + All message fields as single JSON object - """ - - + """ def __init__( - self, - message_name, - system_id, - component_id, - target_system_id, - target_component_id, - fields_json): - """ Initializes the MavlinkMessage object """ + self, + message_name, + system_id, + component_id, + target_system_id, + target_component_id, + fields_json, + ): + """Initializes the MavlinkMessage object""" self.message_name = message_name self.system_id = system_id self.component_id = component_id @@ -51,148 +50,111 @@ def __init__( self.fields_json = fields_json def __eq__(self, to_compare): - """ Checks if two MavlinkMessage are the same """ + """Checks if two MavlinkMessage are the same""" try: # Try to compare - this likely fails when it is compared to a non # MavlinkMessage object - return \ - (self.message_name == to_compare.message_name) and \ - (self.system_id == to_compare.system_id) and \ - (self.component_id == to_compare.component_id) and \ - (self.target_system_id == to_compare.target_system_id) and \ - (self.target_component_id == to_compare.target_component_id) and \ - (self.fields_json == to_compare.fields_json) + return ( + (self.message_name == to_compare.message_name) + and (self.system_id == to_compare.system_id) + and (self.component_id == to_compare.component_id) + and (self.target_system_id == to_compare.target_system_id) + and (self.target_component_id == to_compare.target_component_id) + and (self.fields_json == to_compare.fields_json) + ) except AttributeError: return False def __str__(self): - """ MavlinkMessage in string representation """ - struct_repr = ", ".join([ + """MavlinkMessage in string representation""" + struct_repr = ", ".join( + [ "message_name: " + str(self.message_name), "system_id: " + str(self.system_id), "component_id: " + str(self.component_id), "target_system_id: " + str(self.target_system_id), "target_component_id: " + str(self.target_component_id), - "fields_json: " + str(self.fields_json) - ]) + "fields_json: " + str(self.fields_json), + ] + ) return f"MavlinkMessage: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMavlinkMessage): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MavlinkMessage( - - rpcMavlinkMessage.message_name, - - - rpcMavlinkMessage.system_id, - - - rpcMavlinkMessage.component_id, - - - rpcMavlinkMessage.target_system_id, - - - rpcMavlinkMessage.target_component_id, - - - rpcMavlinkMessage.fields_json - ) + rpcMavlinkMessage.message_name, + rpcMavlinkMessage.system_id, + rpcMavlinkMessage.component_id, + rpcMavlinkMessage.target_system_id, + rpcMavlinkMessage.target_component_id, + rpcMavlinkMessage.fields_json, + ) def translate_to_rpc(self, rpcMavlinkMessage): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMavlinkMessage.message_name = self.message_name - - - - - + rpcMavlinkMessage.system_id = self.system_id - - - - - + rpcMavlinkMessage.component_id = self.component_id - - - - - + rpcMavlinkMessage.target_system_id = self.target_system_id - - - - - + rpcMavlinkMessage.target_component_id = self.target_component_id - - - - - + rpcMavlinkMessage.fields_json = self.fields_json - - - class MavlinkDirectResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - ERROR - Error + ERROR + Error - INVALID_MESSAGE - Invalid MAVLink message + INVALID_MESSAGE + Invalid MAVLink message - INVALID_FIELD - Invalid field name or value + INVALID_FIELD + Invalid field name or value - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - TIMEOUT - Request timed out + TIMEOUT + Request timed out - """ + """ - UNKNOWN = 0 SUCCESS = 1 ERROR = 2 @@ -222,89 +184,84 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_UNKNOWN: return MavlinkDirectResult.Result.UNKNOWN if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_SUCCESS: return MavlinkDirectResult.Result.SUCCESS if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_ERROR: return MavlinkDirectResult.Result.ERROR - if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_INVALID_MESSAGE: + if ( + rpc_enum_value + == mavlink_direct_pb2.MavlinkDirectResult.RESULT_INVALID_MESSAGE + ): return MavlinkDirectResult.Result.INVALID_MESSAGE - if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_INVALID_FIELD: + if ( + rpc_enum_value + == mavlink_direct_pb2.MavlinkDirectResult.RESULT_INVALID_FIELD + ): return MavlinkDirectResult.Result.INVALID_FIELD - if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == mavlink_direct_pb2.MavlinkDirectResult.RESULT_CONNECTION_ERROR + ): return MavlinkDirectResult.Result.CONNECTION_ERROR - if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == mavlink_direct_pb2.MavlinkDirectResult.RESULT_NO_SYSTEM + ): return MavlinkDirectResult.Result.NO_SYSTEM if rpc_enum_value == mavlink_direct_pb2.MavlinkDirectResult.RESULT_TIMEOUT: return MavlinkDirectResult.Result.TIMEOUT def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the MavlinkDirectResult object """ + def __init__(self, result, result_str): + """Initializes the MavlinkDirectResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two MavlinkDirectResult are the same """ + """Checks if two MavlinkDirectResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # MavlinkDirectResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ MavlinkDirectResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """MavlinkDirectResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"MavlinkDirectResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMavlinkDirectResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MavlinkDirectResult( - - MavlinkDirectResult.Result.translate_from_rpc(rpcMavlinkDirectResult.result), - - - rpcMavlinkDirectResult.result_str - ) + MavlinkDirectResult.Result.translate_from_rpc( + rpcMavlinkDirectResult.result + ), + rpcMavlinkDirectResult.result_str, + ) def translate_to_rpc(self, rpcMavlinkDirectResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMavlinkDirectResult.result = self.result.translate_to_rpc() - - - - - - rpcMavlinkDirectResult.result_str = self.result_str - - - + rpcMavlinkDirectResult.result_str = self.result_str class MavlinkDirectError(Exception): - """ Raised when a MavlinkDirectResult is a fail code """ + """Raised when a MavlinkDirectResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -317,74 +274,69 @@ def __str__(self): class MavlinkDirect(AsyncBase): """ - Enable direct MAVLink communication using libmav. + Enable direct MAVLink communication using libmav. - Generated by dcsdkgen - MAVSDK MavlinkDirect API + Generated by dcsdkgen - MAVSDK MavlinkDirect API """ # Plugin name name = "MavlinkDirect" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = mavlink_direct_pb2_grpc.MavlinkDirectServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return MavlinkDirectResult.translate_from_rpc(response.mavlink_direct_result) - async def send_message(self, message): """ - Send a MAVLink message directly to the system. + Send a MAVLink message directly to the system. - This allows sending any MAVLink message with full control over the message content. + This allows sending any MAVLink message with full control over the message content. - Parameters - ---------- - message : MavlinkMessage - The MAVLink message to send + Parameters + ---------- + message : MavlinkMessage + The MAVLink message to send - Raises - ------ - MavlinkDirectError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MavlinkDirectError + If the request fails. The error contains the reason for the failure. """ request = mavlink_direct_pb2.SendMessageRequest() - + message.translate_to_rpc(request.message) - - + response = await self._stub.SendMessage(request) - result = self._extract_result(response) if result.result != MavlinkDirectResult.Result.SUCCESS: raise MavlinkDirectError(result, "send_message()", message) - async def message(self, message_name): """ - Subscribe to incoming MAVLink messages. + Subscribe to incoming MAVLink messages. - This provides direct access to incoming MAVLink messages. Use an empty string - in message_name to subscribe to all messages, or specify a message name - (e.g., "HEARTBEAT") to filter for specific message types. + This provides direct access to incoming MAVLink messages. Use an empty string + in message_name to subscribe to all messages, or specify a message name + (e.g., "HEARTBEAT") to filter for specific message types. - Parameters - ---------- - message_name : std::string - MAVLink message name to filter for (e.g., "HEARTBEAT"), empty string = all messages + Parameters + ---------- + message_name : std::string + MAVLink message name to filter for (e.g., "HEARTBEAT"), empty string = all messages + + Yields + ------- + message : MavlinkMessage + The received MAVLink message - Yields - ------- - message : MavlinkMessage - The received MAVLink message - """ request = mavlink_direct_pb2.SubscribeMessageRequest() @@ -393,38 +345,33 @@ async def message(self, message_name): try: async for response in message_stream: - - - yield MavlinkMessage.translate_from_rpc(response.message) finally: message_stream.cancel() async def load_custom_xml(self, xml_content): """ - Load custom MAVLink message definitions from XML. + Load custom MAVLink message definitions from XML. - This allows loading custom MAVLink message definitions at runtime, - extending the available message types beyond the built-in definitions. + This allows loading custom MAVLink message definitions at runtime, + extending the available message types beyond the built-in definitions. - Parameters - ---------- - xml_content : std::string - The custom MAVLink XML definition content + Parameters + ---------- + xml_content : std::string + The custom MAVLink XML definition content - Raises - ------ - MavlinkDirectError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MavlinkDirectError + If the request fails. The error contains the reason for the failure. """ request = mavlink_direct_pb2.LoadCustomXmlRequest() request.xml_content = xml_content response = await self._stub.LoadCustomXml(request) - result = self._extract_result(response) if result.result != MavlinkDirectResult.Result.SUCCESS: raise MavlinkDirectError(result, "load_custom_xml()", xml_content) - \ No newline at end of file diff --git a/mavsdk/mavlink_direct_pb2.py b/mavsdk/mavlink_direct_pb2.py index a756e14f..ff0adcd8 100644 --- a/mavsdk/mavlink_direct_pb2.py +++ b/mavsdk/mavlink_direct_pb2.py @@ -4,18 +4,15 @@ # source: mavlink_direct/mavlink_direct.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'mavlink_direct/mavlink_direct.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "mavlink_direct/mavlink_direct.proto" ) # @@protoc_insertion_point(imports) @@ -25,38 +22,56 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n#mavlink_direct/mavlink_direct.proto\x12\x19mavsdk.rpc.mavlink_direct\x1a\x14mavsdk_options.proto\"P\n\x12SendMessageRequest\x12:\n\x07message\x18\x01 \x01(\x0b\x32).mavsdk.rpc.mavlink_direct.MavlinkMessage\"d\n\x13SendMessageResponse\x12M\n\x15mavlink_direct_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.mavlink_direct.MavlinkDirectResult\"/\n\x17SubscribeMessageRequest\x12\x14\n\x0cmessage_name\x18\x01 \x01(\t\"M\n\x0fMessageResponse\x12:\n\x07message\x18\x01 \x01(\x0b\x32).mavsdk.rpc.mavlink_direct.MavlinkMessage\"+\n\x14LoadCustomXmlRequest\x12\x13\n\x0bxml_content\x18\x01 \x01(\t\"f\n\x15LoadCustomXmlResponse\x12M\n\x15mavlink_direct_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.mavlink_direct.MavlinkDirectResult\"\x9b\x01\n\x0eMavlinkMessage\x12\x14\n\x0cmessage_name\x18\x01 \x01(\t\x12\x11\n\tsystem_id\x18\x02 \x01(\r\x12\x14\n\x0c\x63omponent_id\x18\x03 \x01(\r\x12\x18\n\x10target_system_id\x18\x04 \x01(\r\x12\x1b\n\x13target_component_id\x18\x05 \x01(\r\x12\x13\n\x0b\x66ields_json\x18\x06 \x01(\t\"\xb2\x02\n\x13MavlinkDirectResult\x12\x45\n\x06result\x18\x01 \x01(\x0e\x32\x35.mavsdk.rpc.mavlink_direct.MavlinkDirectResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xbf\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\x1a\n\x16RESULT_INVALID_MESSAGE\x10\x03\x12\x18\n\x14RESULT_INVALID_FIELD\x10\x04\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x05\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x06\x12\x12\n\x0eRESULT_TIMEOUT\x10\x07\x32\x80\x03\n\x14MavlinkDirectService\x12r\n\x0bSendMessage\x12-.mavsdk.rpc.mavlink_direct.SendMessageRequest\x1a..mavsdk.rpc.mavlink_direct.SendMessageResponse\"\x04\x80\xb5\x18\x01\x12z\n\x10SubscribeMessage\x12\x32.mavsdk.rpc.mavlink_direct.SubscribeMessageRequest\x1a*.mavsdk.rpc.mavlink_direct.MessageResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12x\n\rLoadCustomXml\x12/.mavsdk.rpc.mavlink_direct.LoadCustomXmlRequest\x1a\x30.mavsdk.rpc.mavlink_direct.LoadCustomXmlResponse\"\x04\x80\xb5\x18\x01\x42.\n\x18io.mavsdk.mavlink_directB\x12MavlinkDirectProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n#mavlink_direct/mavlink_direct.proto\x12\x19mavsdk.rpc.mavlink_direct\x1a\x14mavsdk_options.proto"P\n\x12SendMessageRequest\x12:\n\x07message\x18\x01 \x01(\x0b\x32).mavsdk.rpc.mavlink_direct.MavlinkMessage"d\n\x13SendMessageResponse\x12M\n\x15mavlink_direct_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.mavlink_direct.MavlinkDirectResult"/\n\x17SubscribeMessageRequest\x12\x14\n\x0cmessage_name\x18\x01 \x01(\t"M\n\x0fMessageResponse\x12:\n\x07message\x18\x01 \x01(\x0b\x32).mavsdk.rpc.mavlink_direct.MavlinkMessage"+\n\x14LoadCustomXmlRequest\x12\x13\n\x0bxml_content\x18\x01 \x01(\t"f\n\x15LoadCustomXmlResponse\x12M\n\x15mavlink_direct_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.mavlink_direct.MavlinkDirectResult"\x9b\x01\n\x0eMavlinkMessage\x12\x14\n\x0cmessage_name\x18\x01 \x01(\t\x12\x11\n\tsystem_id\x18\x02 \x01(\r\x12\x14\n\x0c\x63omponent_id\x18\x03 \x01(\r\x12\x18\n\x10target_system_id\x18\x04 \x01(\r\x12\x1b\n\x13target_component_id\x18\x05 \x01(\r\x12\x13\n\x0b\x66ields_json\x18\x06 \x01(\t"\xb2\x02\n\x13MavlinkDirectResult\x12\x45\n\x06result\x18\x01 \x01(\x0e\x32\x35.mavsdk.rpc.mavlink_direct.MavlinkDirectResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xbf\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\x1a\n\x16RESULT_INVALID_MESSAGE\x10\x03\x12\x18\n\x14RESULT_INVALID_FIELD\x10\x04\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x05\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x06\x12\x12\n\x0eRESULT_TIMEOUT\x10\x07\x32\x80\x03\n\x14MavlinkDirectService\x12r\n\x0bSendMessage\x12-.mavsdk.rpc.mavlink_direct.SendMessageRequest\x1a..mavsdk.rpc.mavlink_direct.SendMessageResponse"\x04\x80\xb5\x18\x01\x12z\n\x10SubscribeMessage\x12\x32.mavsdk.rpc.mavlink_direct.SubscribeMessageRequest\x1a*.mavsdk.rpc.mavlink_direct.MessageResponse"\x04\x80\xb5\x18\x00\x30\x01\x12x\n\rLoadCustomXml\x12/.mavsdk.rpc.mavlink_direct.LoadCustomXmlRequest\x1a\x30.mavsdk.rpc.mavlink_direct.LoadCustomXmlResponse"\x04\x80\xb5\x18\x01\x42.\n\x18io.mavsdk.mavlink_directB\x12MavlinkDirectProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mavlink_direct.mavlink_direct_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "mavlink_direct.mavlink_direct_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\030io.mavsdk.mavlink_directB\022MavlinkDirectProto' - _globals['_MAVLINKDIRECTSERVICE'].methods_by_name['SendMessage']._loaded_options = None - _globals['_MAVLINKDIRECTSERVICE'].methods_by_name['SendMessage']._serialized_options = b'\200\265\030\001' - _globals['_MAVLINKDIRECTSERVICE'].methods_by_name['SubscribeMessage']._loaded_options = None - _globals['_MAVLINKDIRECTSERVICE'].methods_by_name['SubscribeMessage']._serialized_options = b'\200\265\030\000' - _globals['_MAVLINKDIRECTSERVICE'].methods_by_name['LoadCustomXml']._loaded_options = None - _globals['_MAVLINKDIRECTSERVICE'].methods_by_name['LoadCustomXml']._serialized_options = b'\200\265\030\001' - _globals['_SENDMESSAGEREQUEST']._serialized_start=88 - _globals['_SENDMESSAGEREQUEST']._serialized_end=168 - _globals['_SENDMESSAGERESPONSE']._serialized_start=170 - _globals['_SENDMESSAGERESPONSE']._serialized_end=270 - _globals['_SUBSCRIBEMESSAGEREQUEST']._serialized_start=272 - _globals['_SUBSCRIBEMESSAGEREQUEST']._serialized_end=319 - _globals['_MESSAGERESPONSE']._serialized_start=321 - _globals['_MESSAGERESPONSE']._serialized_end=398 - _globals['_LOADCUSTOMXMLREQUEST']._serialized_start=400 - _globals['_LOADCUSTOMXMLREQUEST']._serialized_end=443 - _globals['_LOADCUSTOMXMLRESPONSE']._serialized_start=445 - _globals['_LOADCUSTOMXMLRESPONSE']._serialized_end=547 - _globals['_MAVLINKMESSAGE']._serialized_start=550 - _globals['_MAVLINKMESSAGE']._serialized_end=705 - _globals['_MAVLINKDIRECTRESULT']._serialized_start=708 - _globals['_MAVLINKDIRECTRESULT']._serialized_end=1014 - _globals['_MAVLINKDIRECTRESULT_RESULT']._serialized_start=823 - _globals['_MAVLINKDIRECTRESULT_RESULT']._serialized_end=1014 - _globals['_MAVLINKDIRECTSERVICE']._serialized_start=1017 - _globals['_MAVLINKDIRECTSERVICE']._serialized_end=1401 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\030io.mavsdk.mavlink_directB\022MavlinkDirectProto" + _globals["_MAVLINKDIRECTSERVICE"].methods_by_name[ + "SendMessage" + ]._loaded_options = None + _globals["_MAVLINKDIRECTSERVICE"].methods_by_name[ + "SendMessage" + ]._serialized_options = b"\200\265\030\001" + _globals["_MAVLINKDIRECTSERVICE"].methods_by_name[ + "SubscribeMessage" + ]._loaded_options = None + _globals["_MAVLINKDIRECTSERVICE"].methods_by_name[ + "SubscribeMessage" + ]._serialized_options = b"\200\265\030\000" + _globals["_MAVLINKDIRECTSERVICE"].methods_by_name[ + "LoadCustomXml" + ]._loaded_options = None + _globals["_MAVLINKDIRECTSERVICE"].methods_by_name[ + "LoadCustomXml" + ]._serialized_options = b"\200\265\030\001" + _globals["_SENDMESSAGEREQUEST"]._serialized_start = 88 + _globals["_SENDMESSAGEREQUEST"]._serialized_end = 168 + _globals["_SENDMESSAGERESPONSE"]._serialized_start = 170 + _globals["_SENDMESSAGERESPONSE"]._serialized_end = 270 + _globals["_SUBSCRIBEMESSAGEREQUEST"]._serialized_start = 272 + _globals["_SUBSCRIBEMESSAGEREQUEST"]._serialized_end = 319 + _globals["_MESSAGERESPONSE"]._serialized_start = 321 + _globals["_MESSAGERESPONSE"]._serialized_end = 398 + _globals["_LOADCUSTOMXMLREQUEST"]._serialized_start = 400 + _globals["_LOADCUSTOMXMLREQUEST"]._serialized_end = 443 + _globals["_LOADCUSTOMXMLRESPONSE"]._serialized_start = 445 + _globals["_LOADCUSTOMXMLRESPONSE"]._serialized_end = 547 + _globals["_MAVLINKMESSAGE"]._serialized_start = 550 + _globals["_MAVLINKMESSAGE"]._serialized_end = 705 + _globals["_MAVLINKDIRECTRESULT"]._serialized_start = 708 + _globals["_MAVLINKDIRECTRESULT"]._serialized_end = 1014 + _globals["_MAVLINKDIRECTRESULT_RESULT"]._serialized_start = 823 + _globals["_MAVLINKDIRECTRESULT_RESULT"]._serialized_end = 1014 + _globals["_MAVLINKDIRECTSERVICE"]._serialized_start = 1017 + _globals["_MAVLINKDIRECTSERVICE"]._serialized_end = 1401 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/mavlink_direct_pb2_grpc.py b/mavsdk/mavlink_direct_pb2_grpc.py index 7e36c55d..499374b5 100644 --- a/mavsdk/mavlink_direct_pb2_grpc.py +++ b/mavsdk/mavlink_direct_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import mavlink_direct_pb2 as mavlink__direct_dot_mavlink__direct__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in mavlink_direct/mavlink_direct_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in mavlink_direct/mavlink_direct_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class MavlinkDirectServiceStub(object): - """Enable direct MAVLink communication using libmav. - """ + """Enable direct MAVLink communication using libmav.""" def __init__(self, channel): """Constructor. @@ -36,25 +39,27 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SendMessage = channel.unary_unary( - '/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SendMessage', - request_serializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageRequest.SerializeToString, - response_deserializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SendMessage", + request_serializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageRequest.SerializeToString, + response_deserializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageResponse.FromString, + _registered_method=True, + ) self.SubscribeMessage = channel.unary_stream( - '/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SubscribeMessage', - request_serializer=mavlink__direct_dot_mavlink__direct__pb2.SubscribeMessageRequest.SerializeToString, - response_deserializer=mavlink__direct_dot_mavlink__direct__pb2.MessageResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SubscribeMessage", + request_serializer=mavlink__direct_dot_mavlink__direct__pb2.SubscribeMessageRequest.SerializeToString, + response_deserializer=mavlink__direct_dot_mavlink__direct__pb2.MessageResponse.FromString, + _registered_method=True, + ) self.LoadCustomXml = channel.unary_unary( - '/mavsdk.rpc.mavlink_direct.MavlinkDirectService/LoadCustomXml', - request_serializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlRequest.SerializeToString, - response_deserializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mavlink_direct.MavlinkDirectService/LoadCustomXml", + request_serializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlRequest.SerializeToString, + response_deserializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlResponse.FromString, + _registered_method=True, + ) class MavlinkDirectServiceServicer(object): - """Enable direct MAVLink communication using libmav. - """ + """Enable direct MAVLink communication using libmav.""" def SendMessage(self, request, context): """ @@ -63,8 +68,8 @@ def SendMessage(self, request, context): This allows sending any MAVLink message with full control over the message content. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeMessage(self, request, context): """ @@ -75,8 +80,8 @@ def SubscribeMessage(self, request, context): (e.g., "HEARTBEAT") to filter for specific message types. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def LoadCustomXml(self, request, context): """ @@ -86,54 +91,58 @@ def LoadCustomXml(self, request, context): extending the available message types beyond the built-in definitions. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_MavlinkDirectServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SendMessage': grpc.unary_unary_rpc_method_handler( - servicer.SendMessage, - request_deserializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageRequest.FromString, - response_serializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageResponse.SerializeToString, - ), - 'SubscribeMessage': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeMessage, - request_deserializer=mavlink__direct_dot_mavlink__direct__pb2.SubscribeMessageRequest.FromString, - response_serializer=mavlink__direct_dot_mavlink__direct__pb2.MessageResponse.SerializeToString, - ), - 'LoadCustomXml': grpc.unary_unary_rpc_method_handler( - servicer.LoadCustomXml, - request_deserializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlRequest.FromString, - response_serializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlResponse.SerializeToString, - ), + "SendMessage": grpc.unary_unary_rpc_method_handler( + servicer.SendMessage, + request_deserializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageRequest.FromString, + response_serializer=mavlink__direct_dot_mavlink__direct__pb2.SendMessageResponse.SerializeToString, + ), + "SubscribeMessage": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeMessage, + request_deserializer=mavlink__direct_dot_mavlink__direct__pb2.SubscribeMessageRequest.FromString, + response_serializer=mavlink__direct_dot_mavlink__direct__pb2.MessageResponse.SerializeToString, + ), + "LoadCustomXml": grpc.unary_unary_rpc_method_handler( + servicer.LoadCustomXml, + request_deserializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlRequest.FromString, + response_serializer=mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.mavlink_direct.MavlinkDirectService', rpc_method_handlers) + "mavsdk.rpc.mavlink_direct.MavlinkDirectService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.mavlink_direct.MavlinkDirectService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.mavlink_direct.MavlinkDirectService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class MavlinkDirectService(object): - """Enable direct MAVLink communication using libmav. - """ + """Enable direct MAVLink communication using libmav.""" @staticmethod - def SendMessage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SendMessage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SendMessage', + "/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SendMessage", mavlink__direct_dot_mavlink__direct__pb2.SendMessageRequest.SerializeToString, mavlink__direct_dot_mavlink__direct__pb2.SendMessageResponse.FromString, options, @@ -144,23 +153,26 @@ def SendMessage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeMessage(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeMessage( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SubscribeMessage', + "/mavsdk.rpc.mavlink_direct.MavlinkDirectService/SubscribeMessage", mavlink__direct_dot_mavlink__direct__pb2.SubscribeMessageRequest.SerializeToString, mavlink__direct_dot_mavlink__direct__pb2.MessageResponse.FromString, options, @@ -171,23 +183,26 @@ def SubscribeMessage(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def LoadCustomXml(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def LoadCustomXml( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mavlink_direct.MavlinkDirectService/LoadCustomXml', + "/mavsdk.rpc.mavlink_direct.MavlinkDirectService/LoadCustomXml", mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlRequest.SerializeToString, mavlink__direct_dot_mavlink__direct__pb2.LoadCustomXmlResponse.FromString, options, @@ -198,4 +213,5 @@ def LoadCustomXml(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/mavsdk_options_pb2.py b/mavsdk/mavsdk_options_pb2.py index d3eafff3..0bfa12ab 100644 --- a/mavsdk/mavsdk_options_pb2.py +++ b/mavsdk/mavsdk_options_pb2.py @@ -4,18 +4,15 @@ # source: mavsdk_options.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'mavsdk_options.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "mavsdk_options.proto" ) # @@protoc_insertion_point(imports) @@ -25,14 +22,16 @@ from google.protobuf import descriptor_pb2 as google_dot_protobuf_dot_descriptor__pb2 -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') +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" +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mavsdk_options_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "mavsdk_options_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\016options.mavsdk' - _globals['_ASYNCTYPE']._serialized_start=74 - _globals['_ASYNCTYPE']._serialized_end=116 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\016options.mavsdk" + _globals["_ASYNCTYPE"]._serialized_start = 74 + _globals["_ASYNCTYPE"]._serialized_end = 116 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/mavsdk_options_pb2_grpc.py b/mavsdk/mavsdk_options_pb2_grpc.py index 7920a96b..860f9e34 100644 --- a/mavsdk/mavsdk_options_pb2_grpc.py +++ b/mavsdk/mavsdk_options_pb2_grpc.py @@ -1,24 +1,28 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in mavsdk_options_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in mavsdk_options_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) diff --git a/mavsdk/mission.py b/mavsdk/mission.py index 9e407116..b9dc98bf 100644 --- a/mavsdk/mission.py +++ b/mavsdk/mission.py @@ -8,94 +8,91 @@ class MissionItem: """ - Type representing a mission item. + Type representing a mission item. - A MissionItem can contain a position and/or actions. - Mission items are building blocks to assemble a mission, - which can be sent to (or received from) a system. - They cannot be used independently. + A MissionItem can contain a position and/or actions. + Mission items are building blocks to assemble a mission, + which can be sent to (or received from) a system. + They cannot be used independently. - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - longitude_deg : double - Longitude in degrees (range: -180 to +180) + longitude_deg : double + Longitude in degrees (range: -180 to +180) - relative_altitude_m : float - Altitude relative to takeoff altitude in metres + relative_altitude_m : float + Altitude relative to takeoff altitude in metres - speed_m_s : float - Speed to use after this mission item (in metres/second) + speed_m_s : float + Speed to use after this mission item (in metres/second) - is_fly_through : bool - True will make the drone fly through without stopping, while false will make the drone stop on the waypoint + is_fly_through : bool + True will make the drone fly through without stopping, while false will make the drone stop on the waypoint - gimbal_pitch_deg : float - Gimbal pitch (in degrees) + gimbal_pitch_deg : float + Gimbal pitch (in degrees) - gimbal_yaw_deg : float - Gimbal yaw (in degrees) + gimbal_yaw_deg : float + Gimbal yaw (in degrees) - camera_action : CameraAction - Camera action to trigger at this mission item + camera_action : CameraAction + Camera action to trigger at this mission item - loiter_time_s : float - Loiter time (in seconds) + loiter_time_s : float + Loiter time (in seconds) - camera_photo_interval_s : double - Camera photo interval to use after this mission item (in seconds) + camera_photo_interval_s : double + Camera photo interval to use after this mission item (in seconds) - acceptance_radius_m : float - Radius for completing a mission item (in metres) + acceptance_radius_m : float + Radius for completing a mission item (in metres) - yaw_deg : float - Absolute yaw angle (in degrees) + yaw_deg : float + Absolute yaw angle (in degrees) - camera_photo_distance_m : float - Camera photo distance to use after this mission item (in meters) + camera_photo_distance_m : float + Camera photo distance to use after this mission item (in meters) - vehicle_action : VehicleAction - Vehicle action to trigger at this mission item. + vehicle_action : VehicleAction + Vehicle action to trigger at this mission item. - """ + """ - - class CameraAction(Enum): """ - Possible camera actions at a mission item. + Possible camera actions at a mission item. - Values - ------ - NONE - No action + Values + ------ + NONE + No action - TAKE_PHOTO - Take a single photo + TAKE_PHOTO + Take a single photo - START_PHOTO_INTERVAL - Start capturing photos at regular intervals + START_PHOTO_INTERVAL + Start capturing photos at regular intervals - STOP_PHOTO_INTERVAL - Stop capturing photos at regular intervals + STOP_PHOTO_INTERVAL + Stop capturing photos at regular intervals - START_VIDEO - Start capturing video + START_VIDEO + Start capturing video - STOP_VIDEO - Stop capturing video + STOP_VIDEO + Stop capturing video - START_PHOTO_DISTANCE - Start capturing photos at regular distance + START_PHOTO_DISTANCE + Start capturing photos at regular distance - STOP_PHOTO_DISTANCE - Stop capturing photos at regular distance + STOP_PHOTO_DISTANCE + Stop capturing photos at regular distance - """ + """ - NONE = 0 TAKE_PHOTO = 1 START_PHOTO_INTERVAL = 2 @@ -125,52 +122,62 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_NONE: return MissionItem.CameraAction.NONE if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_TAKE_PHOTO: return MissionItem.CameraAction.TAKE_PHOTO - if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_START_PHOTO_INTERVAL: + if ( + rpc_enum_value + == mission_pb2.MissionItem.CAMERA_ACTION_START_PHOTO_INTERVAL + ): return MissionItem.CameraAction.START_PHOTO_INTERVAL - if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_STOP_PHOTO_INTERVAL: + if ( + rpc_enum_value + == mission_pb2.MissionItem.CAMERA_ACTION_STOP_PHOTO_INTERVAL + ): return MissionItem.CameraAction.STOP_PHOTO_INTERVAL if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_START_VIDEO: return MissionItem.CameraAction.START_VIDEO if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_STOP_VIDEO: return MissionItem.CameraAction.STOP_VIDEO - if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_START_PHOTO_DISTANCE: + if ( + rpc_enum_value + == mission_pb2.MissionItem.CAMERA_ACTION_START_PHOTO_DISTANCE + ): return MissionItem.CameraAction.START_PHOTO_DISTANCE - if rpc_enum_value == mission_pb2.MissionItem.CAMERA_ACTION_STOP_PHOTO_DISTANCE: + if ( + rpc_enum_value + == mission_pb2.MissionItem.CAMERA_ACTION_STOP_PHOTO_DISTANCE + ): return MissionItem.CameraAction.STOP_PHOTO_DISTANCE def __str__(self): return self.name - - + class VehicleAction(Enum): """ - Possible vehicle actions at a mission item + Possible vehicle actions at a mission item - Values - ------ - NONE - No action + Values + ------ + NONE + No action - TAKEOFF - Vehicle will takeoff and go to defined waypoint + TAKEOFF + Vehicle will takeoff and go to defined waypoint - LAND - When a waypoint is reached vehicle will land at current position + LAND + When a waypoint is reached vehicle will land at current position - TRANSITION_TO_FW - When a waypoint is reached vehicle will transition to fixed-wing mode + TRANSITION_TO_FW + When a waypoint is reached vehicle will transition to fixed-wing mode - TRANSITION_TO_MC - When a waypoint is reached vehicle will transition to multi-copter mode + TRANSITION_TO_MC + When a waypoint is reached vehicle will transition to multi-copter mode - """ + """ - NONE = 0 TAKEOFF = 1 LAND = 2 @@ -191,39 +198,45 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mission_pb2.MissionItem.VEHICLE_ACTION_NONE: return MissionItem.VehicleAction.NONE if rpc_enum_value == mission_pb2.MissionItem.VEHICLE_ACTION_TAKEOFF: return MissionItem.VehicleAction.TAKEOFF if rpc_enum_value == mission_pb2.MissionItem.VEHICLE_ACTION_LAND: return MissionItem.VehicleAction.LAND - if rpc_enum_value == mission_pb2.MissionItem.VEHICLE_ACTION_TRANSITION_TO_FW: + if ( + rpc_enum_value + == mission_pb2.MissionItem.VEHICLE_ACTION_TRANSITION_TO_FW + ): return MissionItem.VehicleAction.TRANSITION_TO_FW - if rpc_enum_value == mission_pb2.MissionItem.VEHICLE_ACTION_TRANSITION_TO_MC: + if ( + rpc_enum_value + == mission_pb2.MissionItem.VEHICLE_ACTION_TRANSITION_TO_MC + ): return MissionItem.VehicleAction.TRANSITION_TO_MC def __str__(self): return self.name - def __init__( - self, - latitude_deg, - longitude_deg, - relative_altitude_m, - speed_m_s, - is_fly_through, - gimbal_pitch_deg, - gimbal_yaw_deg, - camera_action, - loiter_time_s, - camera_photo_interval_s, - acceptance_radius_m, - yaw_deg, - camera_photo_distance_m, - vehicle_action): - """ Initializes the MissionItem object """ + self, + latitude_deg, + longitude_deg, + relative_altitude_m, + speed_m_s, + is_fly_through, + gimbal_pitch_deg, + gimbal_yaw_deg, + camera_action, + loiter_time_s, + camera_photo_interval_s, + acceptance_radius_m, + yaw_deg, + camera_photo_distance_m, + vehicle_action, + ): + """Initializes the MissionItem object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.relative_altitude_m = relative_altitude_m @@ -240,32 +253,34 @@ def __init__( self.vehicle_action = vehicle_action def __eq__(self, to_compare): - """ Checks if two MissionItem are the same """ + """Checks if two MissionItem are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionItem object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.relative_altitude_m == to_compare.relative_altitude_m) and \ - (self.speed_m_s == to_compare.speed_m_s) and \ - (self.is_fly_through == to_compare.is_fly_through) and \ - (self.gimbal_pitch_deg == to_compare.gimbal_pitch_deg) and \ - (self.gimbal_yaw_deg == to_compare.gimbal_yaw_deg) and \ - (self.camera_action == to_compare.camera_action) and \ - (self.loiter_time_s == to_compare.loiter_time_s) and \ - (self.camera_photo_interval_s == to_compare.camera_photo_interval_s) and \ - (self.acceptance_radius_m == to_compare.acceptance_radius_m) and \ - (self.yaw_deg == to_compare.yaw_deg) and \ - (self.camera_photo_distance_m == to_compare.camera_photo_distance_m) and \ - (self.vehicle_action == to_compare.vehicle_action) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.relative_altitude_m == to_compare.relative_altitude_m) + and (self.speed_m_s == to_compare.speed_m_s) + and (self.is_fly_through == to_compare.is_fly_through) + and (self.gimbal_pitch_deg == to_compare.gimbal_pitch_deg) + and (self.gimbal_yaw_deg == to_compare.gimbal_yaw_deg) + and (self.camera_action == to_compare.camera_action) + and (self.loiter_time_s == to_compare.loiter_time_s) + and (self.camera_photo_interval_s == to_compare.camera_photo_interval_s) + and (self.acceptance_radius_m == to_compare.acceptance_radius_m) + and (self.yaw_deg == to_compare.yaw_deg) + and (self.camera_photo_distance_m == to_compare.camera_photo_distance_m) + and (self.vehicle_action == to_compare.vehicle_action) + ) except AttributeError: return False def __str__(self): - """ MissionItem in string representation """ - struct_repr = ", ".join([ + """MissionItem in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), "relative_altitude_m: " + str(self.relative_altitude_m), @@ -279,360 +294,241 @@ def __str__(self): "acceptance_radius_m: " + str(self.acceptance_radius_m), "yaw_deg: " + str(self.yaw_deg), "camera_photo_distance_m: " + str(self.camera_photo_distance_m), - "vehicle_action: " + str(self.vehicle_action) - ]) + "vehicle_action: " + str(self.vehicle_action), + ] + ) return f"MissionItem: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionItem): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionItem( - - rpcMissionItem.latitude_deg, - - - rpcMissionItem.longitude_deg, - - - rpcMissionItem.relative_altitude_m, - - - rpcMissionItem.speed_m_s, - - - rpcMissionItem.is_fly_through, - - - rpcMissionItem.gimbal_pitch_deg, - - - rpcMissionItem.gimbal_yaw_deg, - - - MissionItem.CameraAction.translate_from_rpc(rpcMissionItem.camera_action), - - - rpcMissionItem.loiter_time_s, - - - rpcMissionItem.camera_photo_interval_s, - - - rpcMissionItem.acceptance_radius_m, - - - rpcMissionItem.yaw_deg, - - - rpcMissionItem.camera_photo_distance_m, - - - MissionItem.VehicleAction.translate_from_rpc(rpcMissionItem.vehicle_action) - ) + rpcMissionItem.latitude_deg, + rpcMissionItem.longitude_deg, + rpcMissionItem.relative_altitude_m, + rpcMissionItem.speed_m_s, + rpcMissionItem.is_fly_through, + rpcMissionItem.gimbal_pitch_deg, + rpcMissionItem.gimbal_yaw_deg, + MissionItem.CameraAction.translate_from_rpc(rpcMissionItem.camera_action), + rpcMissionItem.loiter_time_s, + rpcMissionItem.camera_photo_interval_s, + rpcMissionItem.acceptance_radius_m, + rpcMissionItem.yaw_deg, + rpcMissionItem.camera_photo_distance_m, + MissionItem.VehicleAction.translate_from_rpc(rpcMissionItem.vehicle_action), + ) def translate_to_rpc(self, rpcMissionItem): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionItem.latitude_deg = self.latitude_deg - - - - - + rpcMissionItem.longitude_deg = self.longitude_deg - - - - - + rpcMissionItem.relative_altitude_m = self.relative_altitude_m - - - - - + rpcMissionItem.speed_m_s = self.speed_m_s - - - - - + rpcMissionItem.is_fly_through = self.is_fly_through - - - - - + rpcMissionItem.gimbal_pitch_deg = self.gimbal_pitch_deg - - - - - + rpcMissionItem.gimbal_yaw_deg = self.gimbal_yaw_deg - - - - - + rpcMissionItem.camera_action = self.camera_action.translate_to_rpc() - - - - - + rpcMissionItem.loiter_time_s = self.loiter_time_s - - - - - + rpcMissionItem.camera_photo_interval_s = self.camera_photo_interval_s - - - - - + rpcMissionItem.acceptance_radius_m = self.acceptance_radius_m - - - - - + rpcMissionItem.yaw_deg = self.yaw_deg - - - - - + rpcMissionItem.camera_photo_distance_m = self.camera_photo_distance_m - - - - - + rpcMissionItem.vehicle_action = self.vehicle_action.translate_to_rpc() - - - class MissionPlan: """ - Mission plan type - - Parameters - ---------- - mission_items : [MissionItem] - The mission items + Mission plan type - """ + Parameters + ---------- + mission_items : [MissionItem] + The mission items - + """ - def __init__( - self, - mission_items): - """ Initializes the MissionPlan object """ + def __init__(self, mission_items): + """Initializes the MissionPlan object""" self.mission_items = mission_items def __eq__(self, to_compare): - """ Checks if two MissionPlan are the same """ + """Checks if two MissionPlan are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionPlan object - return \ - (self.mission_items == to_compare.mission_items) + return self.mission_items == to_compare.mission_items except AttributeError: return False def __str__(self): - """ MissionPlan in string representation """ - struct_repr = ", ".join([ - "mission_items: " + str(self.mission_items) - ]) + """MissionPlan in string representation""" + struct_repr = ", ".join(["mission_items: " + str(self.mission_items)]) return f"MissionPlan: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionPlan): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionPlan( - - list(map(lambda elem: MissionItem.translate_from_rpc(elem), rpcMissionPlan.mission_items)) + list( + map( + lambda elem: MissionItem.translate_from_rpc(elem), + rpcMissionPlan.mission_items, ) + ) + ) def translate_to_rpc(self, rpcMissionPlan): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.mission_items: - rpc_elem = mission_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcMissionPlan.mission_items.extend(rpc_elems_list) - - - class MissionProgress: """ - Mission progress type. + Mission progress type. - Parameters - ---------- - current : int32_t - Current mission item index (0-based), if equal to total, the mission is finished + Parameters + ---------- + current : int32_t + Current mission item index (0-based), if equal to total, the mission is finished - total : int32_t - Total number of mission items + total : int32_t + Total number of mission items - """ - - + """ - def __init__( - self, - current, - total): - """ Initializes the MissionProgress object """ + def __init__(self, current, total): + """Initializes the MissionProgress object""" self.current = current self.total = total def __eq__(self, to_compare): - """ Checks if two MissionProgress are the same """ + """Checks if two MissionProgress are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionProgress object - return \ - (self.current == to_compare.current) and \ - (self.total == to_compare.total) + return (self.current == to_compare.current) and ( + self.total == to_compare.total + ) except AttributeError: return False def __str__(self): - """ MissionProgress in string representation """ - struct_repr = ", ".join([ - "current: " + str(self.current), - "total: " + str(self.total) - ]) + """MissionProgress in string representation""" + struct_repr = ", ".join( + ["current: " + str(self.current), "total: " + str(self.total)] + ) return f"MissionProgress: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionProgress): - """ Translates a gRPC struct to the SDK equivalent """ - return MissionProgress( - - rpcMissionProgress.current, - - - rpcMissionProgress.total - ) + """Translates a gRPC struct to the SDK equivalent""" + return MissionProgress(rpcMissionProgress.current, rpcMissionProgress.total) def translate_to_rpc(self, rpcMissionProgress): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionProgress.current = self.current - - - - - + rpcMissionProgress.total = self.total - - - class MissionResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - ERROR - Error + ERROR + Error - TOO_MANY_MISSION_ITEMS - Too many mission items in the mission + TOO_MANY_MISSION_ITEMS + Too many mission items in the mission - BUSY - Vehicle is busy + BUSY + Vehicle is busy - TIMEOUT - Request timed out + TIMEOUT + Request timed out - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - UNSUPPORTED - Mission downloaded from the system is not supported + UNSUPPORTED + Mission downloaded from the system is not supported - NO_MISSION_AVAILABLE - No mission available on the system + NO_MISSION_AVAILABLE + No mission available on the system - UNSUPPORTED_MISSION_CMD - Unsupported mission command + UNSUPPORTED_MISSION_CMD + Unsupported mission command - TRANSFER_CANCELLED - Mission transfer (upload or download) has been cancelled + TRANSFER_CANCELLED + Mission transfer (upload or download) has been cancelled - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - NEXT - Intermediate message showing progress + NEXT + Intermediate message showing progress - DENIED - Request denied + DENIED + Request denied - PROTOCOL_ERROR - There was a protocol error + PROTOCOL_ERROR + There was a protocol error - INT_MESSAGES_NOT_SUPPORTED - The system does not support the MISSION_INT protocol + INT_MESSAGES_NOT_SUPPORTED + The system does not support the MISSION_INT protocol - """ + """ - UNKNOWN = 0 SUCCESS = 1 ERROR = 2 @@ -686,14 +582,17 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mission_pb2.MissionResult.RESULT_UNKNOWN: return MissionResult.Result.UNKNOWN if rpc_enum_value == mission_pb2.MissionResult.RESULT_SUCCESS: return MissionResult.Result.SUCCESS if rpc_enum_value == mission_pb2.MissionResult.RESULT_ERROR: return MissionResult.Result.ERROR - if rpc_enum_value == mission_pb2.MissionResult.RESULT_TOO_MANY_MISSION_ITEMS: + if ( + rpc_enum_value + == mission_pb2.MissionResult.RESULT_TOO_MANY_MISSION_ITEMS + ): return MissionResult.Result.TOO_MANY_MISSION_ITEMS if rpc_enum_value == mission_pb2.MissionResult.RESULT_BUSY: return MissionResult.Result.BUSY @@ -705,7 +604,10 @@ def translate_from_rpc(rpc_enum_value): return MissionResult.Result.UNSUPPORTED if rpc_enum_value == mission_pb2.MissionResult.RESULT_NO_MISSION_AVAILABLE: return MissionResult.Result.NO_MISSION_AVAILABLE - if rpc_enum_value == mission_pb2.MissionResult.RESULT_UNSUPPORTED_MISSION_CMD: + if ( + rpc_enum_value + == mission_pb2.MissionResult.RESULT_UNSUPPORTED_MISSION_CMD + ): return MissionResult.Result.UNSUPPORTED_MISSION_CMD if rpc_enum_value == mission_pb2.MissionResult.RESULT_TRANSFER_CANCELLED: return MissionResult.Result.TRANSFER_CANCELLED @@ -717,238 +619,177 @@ def translate_from_rpc(rpc_enum_value): return MissionResult.Result.DENIED if rpc_enum_value == mission_pb2.MissionResult.RESULT_PROTOCOL_ERROR: return MissionResult.Result.PROTOCOL_ERROR - if rpc_enum_value == mission_pb2.MissionResult.RESULT_INT_MESSAGES_NOT_SUPPORTED: + if ( + rpc_enum_value + == mission_pb2.MissionResult.RESULT_INT_MESSAGES_NOT_SUPPORTED + ): return MissionResult.Result.INT_MESSAGES_NOT_SUPPORTED def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the MissionResult object """ + def __init__(self, result, result_str): + """Initializes the MissionResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two MissionResult are the same """ + """Checks if two MissionResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ MissionResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """MissionResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"MissionResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionResult( - - MissionResult.Result.translate_from_rpc(rpcMissionResult.result), - - - rpcMissionResult.result_str - ) + MissionResult.Result.translate_from_rpc(rpcMissionResult.result), + rpcMissionResult.result_str, + ) def translate_to_rpc(self, rpcMissionResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionResult.result = self.result.translate_to_rpc() - - - - - + rpcMissionResult.result_str = self.result_str - - - class ProgressData: """ - Progress data coming from mission upload. + Progress data coming from mission upload. - Parameters - ---------- - progress : float - Progress (0..1.0) + Parameters + ---------- + progress : float + Progress (0..1.0) - """ - - + """ - def __init__( - self, - progress): - """ Initializes the ProgressData object """ + def __init__(self, progress): + """Initializes the ProgressData object""" self.progress = progress def __eq__(self, to_compare): - """ Checks if two ProgressData are the same """ + """Checks if two ProgressData are the same""" try: # Try to compare - this likely fails when it is compared to a non # ProgressData object - return \ - (self.progress == to_compare.progress) + return self.progress == to_compare.progress except AttributeError: return False def __str__(self): - """ ProgressData in string representation """ - struct_repr = ", ".join([ - "progress: " + str(self.progress) - ]) + """ProgressData in string representation""" + struct_repr = ", ".join(["progress: " + str(self.progress)]) return f"ProgressData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcProgressData): - """ Translates a gRPC struct to the SDK equivalent """ - return ProgressData( - - rpcProgressData.progress - ) + """Translates a gRPC struct to the SDK equivalent""" + return ProgressData(rpcProgressData.progress) def translate_to_rpc(self, rpcProgressData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcProgressData.progress = self.progress - - - class ProgressDataOrMission: """ - Progress data coming from mission download, or the mission itself (if the transfer succeeds). - - Parameters - ---------- - has_progress : bool - Whether this ProgressData contains a 'progress' status or not + Progress data coming from mission download, or the mission itself (if the transfer succeeds). - progress : float - Progress (0..1.0) + Parameters + ---------- + has_progress : bool + Whether this ProgressData contains a 'progress' status or not - has_mission : bool - Whether this ProgressData contains a 'mission_plan' or not + progress : float + Progress (0..1.0) - mission_plan : MissionPlan - Mission plan + has_mission : bool + Whether this ProgressData contains a 'mission_plan' or not - """ + mission_plan : MissionPlan + Mission plan - + """ - def __init__( - self, - has_progress, - progress, - has_mission, - mission_plan): - """ Initializes the ProgressDataOrMission object """ + def __init__(self, has_progress, progress, has_mission, mission_plan): + """Initializes the ProgressDataOrMission object""" self.has_progress = has_progress self.progress = progress self.has_mission = has_mission self.mission_plan = mission_plan def __eq__(self, to_compare): - """ Checks if two ProgressDataOrMission are the same """ + """Checks if two ProgressDataOrMission are the same""" try: # Try to compare - this likely fails when it is compared to a non # ProgressDataOrMission object - return \ - (self.has_progress == to_compare.has_progress) and \ - (self.progress == to_compare.progress) and \ - (self.has_mission == to_compare.has_mission) and \ - (self.mission_plan == to_compare.mission_plan) + return ( + (self.has_progress == to_compare.has_progress) + and (self.progress == to_compare.progress) + and (self.has_mission == to_compare.has_mission) + and (self.mission_plan == to_compare.mission_plan) + ) except AttributeError: return False def __str__(self): - """ ProgressDataOrMission in string representation """ - struct_repr = ", ".join([ + """ProgressDataOrMission in string representation""" + struct_repr = ", ".join( + [ "has_progress: " + str(self.has_progress), "progress: " + str(self.progress), "has_mission: " + str(self.has_mission), - "mission_plan: " + str(self.mission_plan) - ]) + "mission_plan: " + str(self.mission_plan), + ] + ) return f"ProgressDataOrMission: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcProgressDataOrMission): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ProgressDataOrMission( - - rpcProgressDataOrMission.has_progress, - - - rpcProgressDataOrMission.progress, - - - rpcProgressDataOrMission.has_mission, - - - MissionPlan.translate_from_rpc(rpcProgressDataOrMission.mission_plan) - ) + rpcProgressDataOrMission.has_progress, + rpcProgressDataOrMission.progress, + rpcProgressDataOrMission.has_mission, + MissionPlan.translate_from_rpc(rpcProgressDataOrMission.mission_plan), + ) def translate_to_rpc(self, rpcProgressDataOrMission): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcProgressDataOrMission.has_progress = self.has_progress - - - - - + rpcProgressDataOrMission.progress = self.progress - - - - - + rpcProgressDataOrMission.has_mission = self.has_mission - - - - - - self.mission_plan.translate_to_rpc(rpcProgressDataOrMission.mission_plan) - - - + self.mission_plan.translate_to_rpc(rpcProgressDataOrMission.mission_plan) class MissionError(Exception): - """ Raised when a MissionResult is a fail code """ + """Raised when a MissionResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -961,359 +802,335 @@ def __str__(self): class Mission(AsyncBase): """ - Enable waypoint missions. + Enable waypoint missions. - Generated by dcsdkgen - MAVSDK Mission API + Generated by dcsdkgen - MAVSDK Mission API """ # Plugin name name = "Mission" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = mission_pb2_grpc.MissionServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return MissionResult.translate_from_rpc(response.mission_result) - async def upload_mission(self, mission_plan): """ - Upload a list of mission items to the system. + Upload a list of mission items to the system. - The mission items are uploaded to a drone. Once uploaded the mission can be started and - executed even if the connection is lost. + The mission items are uploaded to a drone. Once uploaded the mission can be started and + executed even if the connection is lost. - Parameters - ---------- - mission_plan : MissionPlan - The mission plan + Parameters + ---------- + mission_plan : MissionPlan + The mission plan - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.UploadMissionRequest() - + mission_plan.translate_to_rpc(request.mission_plan) - - + response = await self._stub.UploadMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "upload_mission()", mission_plan) - async def upload_mission_with_progress(self, mission_plan): """ - Upload a list of mission items to the system and report upload progress. + Upload a list of mission items to the system and report upload progress. - The mission items are uploaded to a drone. Once uploaded the mission can be started and - executed even if the connection is lost. + The mission items are uploaded to a drone. Once uploaded the mission can be started and + executed even if the connection is lost. - Parameters - ---------- - mission_plan : MissionPlan - The mission plan + Parameters + ---------- + mission_plan : MissionPlan + The mission plan - Yields - ------- - progress_data : ProgressData - The progress data + Yields + ------- + progress_data : ProgressData + The progress data - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.SubscribeUploadMissionWithProgressRequest() - + mission_plan.translate_to_rpc(request.mission_plan) - - - upload_mission_with_progress_stream = self._stub.SubscribeUploadMissionWithProgress(request) + + upload_mission_with_progress_stream = ( + self._stub.SubscribeUploadMissionWithProgress(request) + ) try: async for response in upload_mission_with_progress_stream: - result = self._extract_result(response) success_codes = [MissionResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in MissionResult.Result]: + if "NEXT" in [return_code.name for return_code in MissionResult.Result]: success_codes.append(MissionResult.Result.NEXT) if result.result not in success_codes: - raise MissionError(result, "upload_mission_with_progress()", mission_plan) + raise MissionError( + result, "upload_mission_with_progress()", mission_plan + ) if result.result == MissionResult.Result.SUCCESS: - upload_mission_with_progress_stream.cancel(); + upload_mission_with_progress_stream.cancel() return - - yield ProgressData.translate_from_rpc(response.progress_data) finally: upload_mission_with_progress_stream.cancel() async def cancel_mission_upload(self): """ - Cancel an ongoing mission upload. + Cancel an ongoing mission upload. - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.CancelMissionUploadRequest() response = await self._stub.CancelMissionUpload(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "cancel_mission_upload()") - async def download_mission(self): """ - Download a list of mission items from the system (asynchronous). + Download a list of mission items from the system (asynchronous). - Will fail if any of the downloaded mission items are not supported - by the MAVSDK API. + Will fail if any of the downloaded mission items are not supported + by the MAVSDK API. - Returns - ------- - mission_plan : MissionPlan - The mission plan + Returns + ------- + mission_plan : MissionPlan + The mission plan - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.DownloadMissionRequest() response = await self._stub.DownloadMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "download_mission()") - return MissionPlan.translate_from_rpc(response.mission_plan) - async def download_mission_with_progress(self): """ - Download a list of mission items from the system (asynchronous) and report progress. + Download a list of mission items from the system (asynchronous) and report progress. - Will fail if any of the downloaded mission items are not supported - by the MAVSDK API. + Will fail if any of the downloaded mission items are not supported + by the MAVSDK API. - Yields - ------- - progress_data : ProgressDataOrMission - The progress data, or the mission plan (when the download is finished) + Yields + ------- + progress_data : ProgressDataOrMission + The progress data, or the mission plan (when the download is finished) - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.SubscribeDownloadMissionWithProgressRequest() - download_mission_with_progress_stream = self._stub.SubscribeDownloadMissionWithProgress(request) + download_mission_with_progress_stream = ( + self._stub.SubscribeDownloadMissionWithProgress(request) + ) try: async for response in download_mission_with_progress_stream: - result = self._extract_result(response) success_codes = [MissionResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in MissionResult.Result]: + if "NEXT" in [return_code.name for return_code in MissionResult.Result]: success_codes.append(MissionResult.Result.NEXT) if result.result not in success_codes: raise MissionError(result, "download_mission_with_progress()") if result.result == MissionResult.Result.SUCCESS: - download_mission_with_progress_stream.cancel(); + download_mission_with_progress_stream.cancel() return - - yield ProgressDataOrMission.translate_from_rpc(response.progress_data) finally: download_mission_with_progress_stream.cancel() async def cancel_mission_download(self): """ - Cancel an ongoing mission download. + Cancel an ongoing mission download. - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.CancelMissionDownloadRequest() response = await self._stub.CancelMissionDownload(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "cancel_mission_download()") - async def start_mission(self): """ - Start the mission. + Start the mission. - A mission must be uploaded to the vehicle before this can be called. + A mission must be uploaded to the vehicle before this can be called. - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.StartMissionRequest() response = await self._stub.StartMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "start_mission()") - async def pause_mission(self): """ - Pause the mission. + Pause the mission. - Pausing the mission puts the vehicle into - [HOLD mode](https://docs.px4.io/en/flight_modes/hold.html). - A multicopter should just hover at the spot while a fixedwing vehicle should loiter - around the location where it paused. + Pausing the mission puts the vehicle into + [HOLD mode](https://docs.px4.io/en/flight_modes/hold.html). + A multicopter should just hover at the spot while a fixedwing vehicle should loiter + around the location where it paused. - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.PauseMissionRequest() response = await self._stub.PauseMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "pause_mission()") - async def clear_mission(self): """ - Clear the mission saved on the vehicle. + Clear the mission saved on the vehicle. - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.ClearMissionRequest() response = await self._stub.ClearMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "clear_mission()") - async def set_current_mission_item(self, index): """ - Sets the mission item index to go to. + Sets the mission item index to go to. - By setting the current index to 0, the mission is restarted from the beginning. If it is set - to a specific index of a mission item, the mission will be set to this item. + By setting the current index to 0, the mission is restarted from the beginning. If it is set + to a specific index of a mission item, the mission will be set to this item. - Note that this is not necessarily true for general missions using MAVLink if loop counters - are used. + Note that this is not necessarily true for general missions using MAVLink if loop counters + are used. - Parameters - ---------- - index : int32_t - Index of the mission item to be set as the next one (0-based) + Parameters + ---------- + index : int32_t + Index of the mission item to be set as the next one (0-based) - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.SetCurrentMissionItemRequest() request.index = index response = await self._stub.SetCurrentMissionItem(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "set_current_mission_item()", index) - async def is_mission_finished(self): """ - Check if the mission has been finished. + Check if the mission has been finished. - Returns - ------- - is_finished : bool - True if the mission is finished and the last mission item has been reached + Returns + ------- + is_finished : bool + True if the mission is finished and the last mission item has been reached - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.IsMissionFinishedRequest() response = await self._stub.IsMissionFinished(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "is_mission_finished()") - return response.is_finished - async def mission_progress(self): """ - Subscribe to mission progress updates. + Subscribe to mission progress updates. + + Yields + ------- + mission_progress : MissionProgress + Mission progress - Yields - ------- - mission_progress : MissionProgress - Mission progress - """ request = mission_pb2.SubscribeMissionProgressRequest() @@ -1321,69 +1138,61 @@ async def mission_progress(self): try: async for response in mission_progress_stream: - - - yield MissionProgress.translate_from_rpc(response.mission_progress) finally: mission_progress_stream.cancel() async def get_return_to_launch_after_mission(self): """ - Get whether to trigger Return-to-Launch (RTL) after mission is complete. + Get whether to trigger Return-to-Launch (RTL) after mission is complete. - Before getting this option, it needs to be set, or a mission - needs to be downloaded. + Before getting this option, it needs to be set, or a mission + needs to be downloaded. - Returns - ------- - enable : bool - If true, trigger an RTL at the end of the mission + Returns + ------- + enable : bool + If true, trigger an RTL at the end of the mission - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.GetReturnToLaunchAfterMissionRequest() response = await self._stub.GetReturnToLaunchAfterMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "get_return_to_launch_after_mission()") - return response.enable - async def set_return_to_launch_after_mission(self, enable): """ - Set whether to trigger Return-to-Launch (RTL) after the mission is complete. + Set whether to trigger Return-to-Launch (RTL) after the mission is complete. - This will only take effect for the next mission upload, meaning that - the mission may have to be uploaded again. + This will only take effect for the next mission upload, meaning that + the mission may have to be uploaded again. - Parameters - ---------- - enable : bool - If true, trigger an RTL at the end of the mission + Parameters + ---------- + enable : bool + If true, trigger an RTL at the end of the mission - Raises - ------ - MissionError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionError + If the request fails. The error contains the reason for the failure. """ request = mission_pb2.SetReturnToLaunchAfterMissionRequest() request.enable = enable response = await self._stub.SetReturnToLaunchAfterMission(request) - result = self._extract_result(response) if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "set_return_to_launch_after_mission()", enable) - \ No newline at end of file diff --git a/mavsdk/mission_pb2.py b/mavsdk/mission_pb2.py index 419a1ace..308ca92e 100644 --- a/mavsdk/mission_pb2.py +++ b/mavsdk/mission_pb2.py @@ -4,18 +4,15 @@ # source: mission/mission.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'mission/mission.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "mission/mission.proto" ) # @@protoc_insertion_point(imports) @@ -25,132 +22,204 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x15mission/mission.proto\x12\x12mavsdk.rpc.mission\x1a\x14mavsdk_options.proto\"M\n\x14UploadMissionRequest\x12\x35\n\x0cmission_plan\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan\"R\n\x15UploadMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"b\n)SubscribeUploadMissionWithProgressRequest\x12\x35\n\x0cmission_plan\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan\"\x97\x01\n!UploadMissionWithProgressResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x37\n\rprogress_data\x18\x02 \x01(\x0b\x32 .mavsdk.rpc.mission.ProgressData\"\x1c\n\x1a\x43\x61ncelMissionUploadRequest\"X\n\x1b\x43\x61ncelMissionUploadResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"\x18\n\x16\x44ownloadMissionRequest\"\x8b\x01\n\x17\x44ownloadMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x35\n\x0cmission_plan\x18\x02 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan\"-\n+SubscribeDownloadMissionWithProgressRequest\"\xa2\x01\n#DownloadMissionWithProgressResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12@\n\rprogress_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission.ProgressDataOrMission\"\x1e\n\x1c\x43\x61ncelMissionDownloadRequest\"Z\n\x1d\x43\x61ncelMissionDownloadResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"\x15\n\x13StartMissionRequest\"Q\n\x14StartMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"\x15\n\x13PauseMissionRequest\"Q\n\x14PauseMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"\x15\n\x13\x43learMissionRequest\"Q\n\x14\x43learMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"-\n\x1cSetCurrentMissionItemRequest\x12\r\n\x05index\x18\x01 \x01(\x05\"Z\n\x1dSetCurrentMissionItemResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"\x1a\n\x18IsMissionFinishedRequest\"k\n\x19IsMissionFinishedResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x13\n\x0bis_finished\x18\x02 \x01(\x08\"!\n\x1fSubscribeMissionProgressRequest\"X\n\x17MissionProgressResponse\x12=\n\x10mission_progress\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.mission.MissionProgress\"&\n$GetReturnToLaunchAfterMissionRequest\"r\n%GetReturnToLaunchAfterMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x0e\n\x06\x65nable\x18\x02 \x01(\x08\"6\n$SetReturnToLaunchAfterMissionRequest\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08\"b\n%SetReturnToLaunchAfterMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\"\xad\x08\n\x0bMissionItem\x12(\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18H\xaf\xbc\x9a\xf2\xd7z>\x12)\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18H\xaf\xbc\x9a\xf2\xd7z>\x12$\n\x13relative_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tspeed_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12!\n\x0eis_fly_through\x18\x05 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12,\n\x10gimbal_pitch_deg\x18\x06 \x01(\x02\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18-C\x1c\xeb\xe2\x36\x1a?\x12*\n\x0egimbal_yaw_deg\x18\x07 \x01(\x02\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18-C\x1c\xeb\xe2\x36\x1a?\x12\x43\n\rcamera_action\x18\x08 \x01(\x0e\x32,.mavsdk.rpc.mission.MissionItem.CameraAction\x12\x1e\n\rloiter_time_s\x18\t \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12(\n\x17\x63\x61mera_photo_interval_s\x18\n \x01(\x01\x42\x07\x82\xb5\x18\x03\x31.0\x12$\n\x13\x61\x63\x63\x65ptance_radius_m\x18\x0b \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x0c \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12(\n\x17\x63\x61mera_photo_distance_m\x18\r \x01(\x02\x42\x07\x82\xb5\x18\x03NAN\x12\x45\n\x0evehicle_action\x18\x0e \x01(\x0e\x32-.mavsdk.rpc.mission.MissionItem.VehicleAction\"\x9f\x02\n\x0c\x43\x61meraAction\x12\x16\n\x12\x43\x41MERA_ACTION_NONE\x10\x00\x12\x1c\n\x18\x43\x41MERA_ACTION_TAKE_PHOTO\x10\x01\x12&\n\"CAMERA_ACTION_START_PHOTO_INTERVAL\x10\x02\x12%\n!CAMERA_ACTION_STOP_PHOTO_INTERVAL\x10\x03\x12\x1d\n\x19\x43\x41MERA_ACTION_START_VIDEO\x10\x04\x12\x1c\n\x18\x43\x41MERA_ACTION_STOP_VIDEO\x10\x05\x12&\n\"CAMERA_ACTION_START_PHOTO_DISTANCE\x10\x06\x12%\n!CAMERA_ACTION_STOP_PHOTO_DISTANCE\x10\x07\"\xa7\x01\n\rVehicleAction\x12\x17\n\x13VEHICLE_ACTION_NONE\x10\x00\x12\x1a\n\x16VEHICLE_ACTION_TAKEOFF\x10\x01\x12\x17\n\x13VEHICLE_ACTION_LAND\x10\x02\x12#\n\x1fVEHICLE_ACTION_TRANSITION_TO_FW\x10\x03\x12#\n\x1fVEHICLE_ACTION_TRANSITION_TO_MC\x10\x04\"E\n\x0bMissionPlan\x12\x36\n\rmission_items\x18\x01 \x03(\x0b\x32\x1f.mavsdk.rpc.mission.MissionItem\"1\n\x0fMissionProgress\x12\x0f\n\x07\x63urrent\x18\x01 \x01(\x05\x12\r\n\x05total\x18\x02 \x01(\x05\"\xff\x03\n\rMissionResult\x12\x38\n\x06result\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.mission.MissionResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x9f\x03\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\x1dRESULT_TOO_MANY_MISSION_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\x16\n\x12RESULT_UNSUPPORTED\x10\x07\x12\x1f\n\x1bRESULT_NO_MISSION_AVAILABLE\x10\x08\x12\"\n\x1eRESULT_UNSUPPORTED_MISSION_CMD\x10\x0b\x12\x1d\n\x19RESULT_TRANSFER_CANCELLED\x10\x0c\x12\x14\n\x10RESULT_NO_SYSTEM\x10\r\x12\x0f\n\x0bRESULT_NEXT\x10\x0e\x12\x11\n\rRESULT_DENIED\x10\x0f\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x10\x12%\n!RESULT_INT_MESSAGES_NOT_SUPPORTED\x10\x11\")\n\x0cProgressData\x12\x19\n\x08progress\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\x9f\x01\n\x15ProgressDataOrMission\x12\x1f\n\x0chas_progress\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x19\n\x08progress\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x13\n\x0bhas_mission\x18\x03 \x01(\x08\x12\x35\n\x0cmission_plan\x18\x04 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan2\xa5\x0e\n\x0eMissionService\x12\x66\n\rUploadMission\x12(.mavsdk.rpc.mission.UploadMissionRequest\x1a).mavsdk.rpc.mission.UploadMissionResponse\"\x00\x12\xa6\x01\n\"SubscribeUploadMissionWithProgress\x12=.mavsdk.rpc.mission.SubscribeUploadMissionWithProgressRequest\x1a\x35.mavsdk.rpc.mission.UploadMissionWithProgressResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12|\n\x13\x43\x61ncelMissionUpload\x12..mavsdk.rpc.mission.CancelMissionUploadRequest\x1a/.mavsdk.rpc.mission.CancelMissionUploadResponse\"\x04\x80\xb5\x18\x01\x12l\n\x0f\x44ownloadMission\x12*.mavsdk.rpc.mission.DownloadMissionRequest\x1a+.mavsdk.rpc.mission.DownloadMissionResponse\"\x00\x12\xac\x01\n$SubscribeDownloadMissionWithProgress\x12?.mavsdk.rpc.mission.SubscribeDownloadMissionWithProgressRequest\x1a\x37.mavsdk.rpc.mission.DownloadMissionWithProgressResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\x82\x01\n\x15\x43\x61ncelMissionDownload\x12\x30.mavsdk.rpc.mission.CancelMissionDownloadRequest\x1a\x31.mavsdk.rpc.mission.CancelMissionDownloadResponse\"\x04\x80\xb5\x18\x01\x12\x63\n\x0cStartMission\x12\'.mavsdk.rpc.mission.StartMissionRequest\x1a(.mavsdk.rpc.mission.StartMissionResponse\"\x00\x12\x63\n\x0cPauseMission\x12\'.mavsdk.rpc.mission.PauseMissionRequest\x1a(.mavsdk.rpc.mission.PauseMissionResponse\"\x00\x12\x63\n\x0c\x43learMission\x12\'.mavsdk.rpc.mission.ClearMissionRequest\x1a(.mavsdk.rpc.mission.ClearMissionResponse\"\x00\x12~\n\x15SetCurrentMissionItem\x12\x30.mavsdk.rpc.mission.SetCurrentMissionItemRequest\x1a\x31.mavsdk.rpc.mission.SetCurrentMissionItemResponse\"\x00\x12v\n\x11IsMissionFinished\x12,.mavsdk.rpc.mission.IsMissionFinishedRequest\x1a-.mavsdk.rpc.mission.IsMissionFinishedResponse\"\x04\x80\xb5\x18\x01\x12\x80\x01\n\x18SubscribeMissionProgress\x12\x33.mavsdk.rpc.mission.SubscribeMissionProgressRequest\x1a+.mavsdk.rpc.mission.MissionProgressResponse\"\x00\x30\x01\x12\x9a\x01\n\x1dGetReturnToLaunchAfterMission\x12\x38.mavsdk.rpc.mission.GetReturnToLaunchAfterMissionRequest\x1a\x39.mavsdk.rpc.mission.GetReturnToLaunchAfterMissionResponse\"\x04\x80\xb5\x18\x01\x12\x9a\x01\n\x1dSetReturnToLaunchAfterMission\x12\x38.mavsdk.rpc.mission.SetReturnToLaunchAfterMissionRequest\x1a\x39.mavsdk.rpc.mission.SetReturnToLaunchAfterMissionResponse\"\x04\x80\xb5\x18\x01\x42!\n\x11io.mavsdk.missionB\x0cMissionProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x15mission/mission.proto\x12\x12mavsdk.rpc.mission\x1a\x14mavsdk_options.proto"M\n\x14UploadMissionRequest\x12\x35\n\x0cmission_plan\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan"R\n\x15UploadMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"b\n)SubscribeUploadMissionWithProgressRequest\x12\x35\n\x0cmission_plan\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan"\x97\x01\n!UploadMissionWithProgressResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x37\n\rprogress_data\x18\x02 \x01(\x0b\x32 .mavsdk.rpc.mission.ProgressData"\x1c\n\x1a\x43\x61ncelMissionUploadRequest"X\n\x1b\x43\x61ncelMissionUploadResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"\x18\n\x16\x44ownloadMissionRequest"\x8b\x01\n\x17\x44ownloadMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x35\n\x0cmission_plan\x18\x02 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan"-\n+SubscribeDownloadMissionWithProgressRequest"\xa2\x01\n#DownloadMissionWithProgressResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12@\n\rprogress_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission.ProgressDataOrMission"\x1e\n\x1c\x43\x61ncelMissionDownloadRequest"Z\n\x1d\x43\x61ncelMissionDownloadResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"\x15\n\x13StartMissionRequest"Q\n\x14StartMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"\x15\n\x13PauseMissionRequest"Q\n\x14PauseMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"\x15\n\x13\x43learMissionRequest"Q\n\x14\x43learMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"-\n\x1cSetCurrentMissionItemRequest\x12\r\n\x05index\x18\x01 \x01(\x05"Z\n\x1dSetCurrentMissionItemResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"\x1a\n\x18IsMissionFinishedRequest"k\n\x19IsMissionFinishedResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x13\n\x0bis_finished\x18\x02 \x01(\x08"!\n\x1fSubscribeMissionProgressRequest"X\n\x17MissionProgressResponse\x12=\n\x10mission_progress\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.mission.MissionProgress"&\n$GetReturnToLaunchAfterMissionRequest"r\n%GetReturnToLaunchAfterMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult\x12\x0e\n\x06\x65nable\x18\x02 \x01(\x08"6\n$SetReturnToLaunchAfterMissionRequest\x12\x0e\n\x06\x65nable\x18\x01 \x01(\x08"b\n%SetReturnToLaunchAfterMissionResponse\x12\x39\n\x0emission_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.mission.MissionResult"\xad\x08\n\x0bMissionItem\x12(\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18H\xaf\xbc\x9a\xf2\xd7z>\x12)\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18H\xaf\xbc\x9a\xf2\xd7z>\x12$\n\x13relative_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tspeed_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12!\n\x0eis_fly_through\x18\x05 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12,\n\x10gimbal_pitch_deg\x18\x06 \x01(\x02\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18-C\x1c\xeb\xe2\x36\x1a?\x12*\n\x0egimbal_yaw_deg\x18\x07 \x01(\x02\x42\x12\x82\xb5\x18\x03NaN\x89\xb5\x18-C\x1c\xeb\xe2\x36\x1a?\x12\x43\n\rcamera_action\x18\x08 \x01(\x0e\x32,.mavsdk.rpc.mission.MissionItem.CameraAction\x12\x1e\n\rloiter_time_s\x18\t \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12(\n\x17\x63\x61mera_photo_interval_s\x18\n \x01(\x01\x42\x07\x82\xb5\x18\x03\x31.0\x12$\n\x13\x61\x63\x63\x65ptance_radius_m\x18\x0b \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x0c \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12(\n\x17\x63\x61mera_photo_distance_m\x18\r \x01(\x02\x42\x07\x82\xb5\x18\x03NAN\x12\x45\n\x0evehicle_action\x18\x0e \x01(\x0e\x32-.mavsdk.rpc.mission.MissionItem.VehicleAction"\x9f\x02\n\x0c\x43\x61meraAction\x12\x16\n\x12\x43\x41MERA_ACTION_NONE\x10\x00\x12\x1c\n\x18\x43\x41MERA_ACTION_TAKE_PHOTO\x10\x01\x12&\n"CAMERA_ACTION_START_PHOTO_INTERVAL\x10\x02\x12%\n!CAMERA_ACTION_STOP_PHOTO_INTERVAL\x10\x03\x12\x1d\n\x19\x43\x41MERA_ACTION_START_VIDEO\x10\x04\x12\x1c\n\x18\x43\x41MERA_ACTION_STOP_VIDEO\x10\x05\x12&\n"CAMERA_ACTION_START_PHOTO_DISTANCE\x10\x06\x12%\n!CAMERA_ACTION_STOP_PHOTO_DISTANCE\x10\x07"\xa7\x01\n\rVehicleAction\x12\x17\n\x13VEHICLE_ACTION_NONE\x10\x00\x12\x1a\n\x16VEHICLE_ACTION_TAKEOFF\x10\x01\x12\x17\n\x13VEHICLE_ACTION_LAND\x10\x02\x12#\n\x1fVEHICLE_ACTION_TRANSITION_TO_FW\x10\x03\x12#\n\x1fVEHICLE_ACTION_TRANSITION_TO_MC\x10\x04"E\n\x0bMissionPlan\x12\x36\n\rmission_items\x18\x01 \x03(\x0b\x32\x1f.mavsdk.rpc.mission.MissionItem"1\n\x0fMissionProgress\x12\x0f\n\x07\x63urrent\x18\x01 \x01(\x05\x12\r\n\x05total\x18\x02 \x01(\x05"\xff\x03\n\rMissionResult\x12\x38\n\x06result\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.mission.MissionResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\x9f\x03\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\x1dRESULT_TOO_MANY_MISSION_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\x16\n\x12RESULT_UNSUPPORTED\x10\x07\x12\x1f\n\x1bRESULT_NO_MISSION_AVAILABLE\x10\x08\x12"\n\x1eRESULT_UNSUPPORTED_MISSION_CMD\x10\x0b\x12\x1d\n\x19RESULT_TRANSFER_CANCELLED\x10\x0c\x12\x14\n\x10RESULT_NO_SYSTEM\x10\r\x12\x0f\n\x0bRESULT_NEXT\x10\x0e\x12\x11\n\rRESULT_DENIED\x10\x0f\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x10\x12%\n!RESULT_INT_MESSAGES_NOT_SUPPORTED\x10\x11")\n\x0cProgressData\x12\x19\n\x08progress\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\x9f\x01\n\x15ProgressDataOrMission\x12\x1f\n\x0chas_progress\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x19\n\x08progress\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x13\n\x0bhas_mission\x18\x03 \x01(\x08\x12\x35\n\x0cmission_plan\x18\x04 \x01(\x0b\x32\x1f.mavsdk.rpc.mission.MissionPlan2\xa5\x0e\n\x0eMissionService\x12\x66\n\rUploadMission\x12(.mavsdk.rpc.mission.UploadMissionRequest\x1a).mavsdk.rpc.mission.UploadMissionResponse"\x00\x12\xa6\x01\n"SubscribeUploadMissionWithProgress\x12=.mavsdk.rpc.mission.SubscribeUploadMissionWithProgressRequest\x1a\x35.mavsdk.rpc.mission.UploadMissionWithProgressResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12|\n\x13\x43\x61ncelMissionUpload\x12..mavsdk.rpc.mission.CancelMissionUploadRequest\x1a/.mavsdk.rpc.mission.CancelMissionUploadResponse"\x04\x80\xb5\x18\x01\x12l\n\x0f\x44ownloadMission\x12*.mavsdk.rpc.mission.DownloadMissionRequest\x1a+.mavsdk.rpc.mission.DownloadMissionResponse"\x00\x12\xac\x01\n$SubscribeDownloadMissionWithProgress\x12?.mavsdk.rpc.mission.SubscribeDownloadMissionWithProgressRequest\x1a\x37.mavsdk.rpc.mission.DownloadMissionWithProgressResponse"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\x82\x01\n\x15\x43\x61ncelMissionDownload\x12\x30.mavsdk.rpc.mission.CancelMissionDownloadRequest\x1a\x31.mavsdk.rpc.mission.CancelMissionDownloadResponse"\x04\x80\xb5\x18\x01\x12\x63\n\x0cStartMission\x12\'.mavsdk.rpc.mission.StartMissionRequest\x1a(.mavsdk.rpc.mission.StartMissionResponse"\x00\x12\x63\n\x0cPauseMission\x12\'.mavsdk.rpc.mission.PauseMissionRequest\x1a(.mavsdk.rpc.mission.PauseMissionResponse"\x00\x12\x63\n\x0c\x43learMission\x12\'.mavsdk.rpc.mission.ClearMissionRequest\x1a(.mavsdk.rpc.mission.ClearMissionResponse"\x00\x12~\n\x15SetCurrentMissionItem\x12\x30.mavsdk.rpc.mission.SetCurrentMissionItemRequest\x1a\x31.mavsdk.rpc.mission.SetCurrentMissionItemResponse"\x00\x12v\n\x11IsMissionFinished\x12,.mavsdk.rpc.mission.IsMissionFinishedRequest\x1a-.mavsdk.rpc.mission.IsMissionFinishedResponse"\x04\x80\xb5\x18\x01\x12\x80\x01\n\x18SubscribeMissionProgress\x12\x33.mavsdk.rpc.mission.SubscribeMissionProgressRequest\x1a+.mavsdk.rpc.mission.MissionProgressResponse"\x00\x30\x01\x12\x9a\x01\n\x1dGetReturnToLaunchAfterMission\x12\x38.mavsdk.rpc.mission.GetReturnToLaunchAfterMissionRequest\x1a\x39.mavsdk.rpc.mission.GetReturnToLaunchAfterMissionResponse"\x04\x80\xb5\x18\x01\x12\x9a\x01\n\x1dSetReturnToLaunchAfterMission\x12\x38.mavsdk.rpc.mission.SetReturnToLaunchAfterMissionRequest\x1a\x39.mavsdk.rpc.mission.SetReturnToLaunchAfterMissionResponse"\x04\x80\xb5\x18\x01\x42!\n\x11io.mavsdk.missionB\x0cMissionProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mission.mission_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "mission.mission_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\021io.mavsdk.missionB\014MissionProto' - _globals['_MISSIONITEM'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN\211\265\030H\257\274\232\362\327z>' - _globals['_MISSIONITEM'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN\211\265\030H\257\274\232\362\327z>' - _globals['_MISSIONITEM'].fields_by_name['relative_altitude_m']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['relative_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_MISSIONITEM'].fields_by_name['speed_m_s']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['speed_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_MISSIONITEM'].fields_by_name['is_fly_through']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['is_fly_through']._serialized_options = b'\202\265\030\005false' - _globals['_MISSIONITEM'].fields_by_name['gimbal_pitch_deg']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['gimbal_pitch_deg']._serialized_options = b'\202\265\030\003NaN\211\265\030-C\034\353\3426\032?' - _globals['_MISSIONITEM'].fields_by_name['gimbal_yaw_deg']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['gimbal_yaw_deg']._serialized_options = b'\202\265\030\003NaN\211\265\030-C\034\353\3426\032?' - _globals['_MISSIONITEM'].fields_by_name['loiter_time_s']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['loiter_time_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_MISSIONITEM'].fields_by_name['camera_photo_interval_s']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['camera_photo_interval_s']._serialized_options = b'\202\265\030\0031.0' - _globals['_MISSIONITEM'].fields_by_name['acceptance_radius_m']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['acceptance_radius_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_MISSIONITEM'].fields_by_name['yaw_deg']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['yaw_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_MISSIONITEM'].fields_by_name['camera_photo_distance_m']._loaded_options = None - _globals['_MISSIONITEM'].fields_by_name['camera_photo_distance_m']._serialized_options = b'\202\265\030\003NAN' - _globals['_PROGRESSDATA'].fields_by_name['progress']._loaded_options = None - _globals['_PROGRESSDATA'].fields_by_name['progress']._serialized_options = b'\202\265\030\003NaN' - _globals['_PROGRESSDATAORMISSION'].fields_by_name['has_progress']._loaded_options = None - _globals['_PROGRESSDATAORMISSION'].fields_by_name['has_progress']._serialized_options = b'\202\265\030\005false' - _globals['_PROGRESSDATAORMISSION'].fields_by_name['progress']._loaded_options = None - _globals['_PROGRESSDATAORMISSION'].fields_by_name['progress']._serialized_options = b'\202\265\030\003NaN' - _globals['_MISSIONSERVICE'].methods_by_name['SubscribeUploadMissionWithProgress']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['SubscribeUploadMissionWithProgress']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_MISSIONSERVICE'].methods_by_name['CancelMissionUpload']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['CancelMissionUpload']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONSERVICE'].methods_by_name['SubscribeDownloadMissionWithProgress']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['SubscribeDownloadMissionWithProgress']._serialized_options = b'\200\265\030\000\210\265\030\001' - _globals['_MISSIONSERVICE'].methods_by_name['CancelMissionDownload']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['CancelMissionDownload']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONSERVICE'].methods_by_name['IsMissionFinished']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['IsMissionFinished']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONSERVICE'].methods_by_name['GetReturnToLaunchAfterMission']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['GetReturnToLaunchAfterMission']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONSERVICE'].methods_by_name['SetReturnToLaunchAfterMission']._loaded_options = None - _globals['_MISSIONSERVICE'].methods_by_name['SetReturnToLaunchAfterMission']._serialized_options = b'\200\265\030\001' - _globals['_UPLOADMISSIONREQUEST']._serialized_start=67 - _globals['_UPLOADMISSIONREQUEST']._serialized_end=144 - _globals['_UPLOADMISSIONRESPONSE']._serialized_start=146 - _globals['_UPLOADMISSIONRESPONSE']._serialized_end=228 - _globals['_SUBSCRIBEUPLOADMISSIONWITHPROGRESSREQUEST']._serialized_start=230 - _globals['_SUBSCRIBEUPLOADMISSIONWITHPROGRESSREQUEST']._serialized_end=328 - _globals['_UPLOADMISSIONWITHPROGRESSRESPONSE']._serialized_start=331 - _globals['_UPLOADMISSIONWITHPROGRESSRESPONSE']._serialized_end=482 - _globals['_CANCELMISSIONUPLOADREQUEST']._serialized_start=484 - _globals['_CANCELMISSIONUPLOADREQUEST']._serialized_end=512 - _globals['_CANCELMISSIONUPLOADRESPONSE']._serialized_start=514 - _globals['_CANCELMISSIONUPLOADRESPONSE']._serialized_end=602 - _globals['_DOWNLOADMISSIONREQUEST']._serialized_start=604 - _globals['_DOWNLOADMISSIONREQUEST']._serialized_end=628 - _globals['_DOWNLOADMISSIONRESPONSE']._serialized_start=631 - _globals['_DOWNLOADMISSIONRESPONSE']._serialized_end=770 - _globals['_SUBSCRIBEDOWNLOADMISSIONWITHPROGRESSREQUEST']._serialized_start=772 - _globals['_SUBSCRIBEDOWNLOADMISSIONWITHPROGRESSREQUEST']._serialized_end=817 - _globals['_DOWNLOADMISSIONWITHPROGRESSRESPONSE']._serialized_start=820 - _globals['_DOWNLOADMISSIONWITHPROGRESSRESPONSE']._serialized_end=982 - _globals['_CANCELMISSIONDOWNLOADREQUEST']._serialized_start=984 - _globals['_CANCELMISSIONDOWNLOADREQUEST']._serialized_end=1014 - _globals['_CANCELMISSIONDOWNLOADRESPONSE']._serialized_start=1016 - _globals['_CANCELMISSIONDOWNLOADRESPONSE']._serialized_end=1106 - _globals['_STARTMISSIONREQUEST']._serialized_start=1108 - _globals['_STARTMISSIONREQUEST']._serialized_end=1129 - _globals['_STARTMISSIONRESPONSE']._serialized_start=1131 - _globals['_STARTMISSIONRESPONSE']._serialized_end=1212 - _globals['_PAUSEMISSIONREQUEST']._serialized_start=1214 - _globals['_PAUSEMISSIONREQUEST']._serialized_end=1235 - _globals['_PAUSEMISSIONRESPONSE']._serialized_start=1237 - _globals['_PAUSEMISSIONRESPONSE']._serialized_end=1318 - _globals['_CLEARMISSIONREQUEST']._serialized_start=1320 - _globals['_CLEARMISSIONREQUEST']._serialized_end=1341 - _globals['_CLEARMISSIONRESPONSE']._serialized_start=1343 - _globals['_CLEARMISSIONRESPONSE']._serialized_end=1424 - _globals['_SETCURRENTMISSIONITEMREQUEST']._serialized_start=1426 - _globals['_SETCURRENTMISSIONITEMREQUEST']._serialized_end=1471 - _globals['_SETCURRENTMISSIONITEMRESPONSE']._serialized_start=1473 - _globals['_SETCURRENTMISSIONITEMRESPONSE']._serialized_end=1563 - _globals['_ISMISSIONFINISHEDREQUEST']._serialized_start=1565 - _globals['_ISMISSIONFINISHEDREQUEST']._serialized_end=1591 - _globals['_ISMISSIONFINISHEDRESPONSE']._serialized_start=1593 - _globals['_ISMISSIONFINISHEDRESPONSE']._serialized_end=1700 - _globals['_SUBSCRIBEMISSIONPROGRESSREQUEST']._serialized_start=1702 - _globals['_SUBSCRIBEMISSIONPROGRESSREQUEST']._serialized_end=1735 - _globals['_MISSIONPROGRESSRESPONSE']._serialized_start=1737 - _globals['_MISSIONPROGRESSRESPONSE']._serialized_end=1825 - _globals['_GETRETURNTOLAUNCHAFTERMISSIONREQUEST']._serialized_start=1827 - _globals['_GETRETURNTOLAUNCHAFTERMISSIONREQUEST']._serialized_end=1865 - _globals['_GETRETURNTOLAUNCHAFTERMISSIONRESPONSE']._serialized_start=1867 - _globals['_GETRETURNTOLAUNCHAFTERMISSIONRESPONSE']._serialized_end=1981 - _globals['_SETRETURNTOLAUNCHAFTERMISSIONREQUEST']._serialized_start=1983 - _globals['_SETRETURNTOLAUNCHAFTERMISSIONREQUEST']._serialized_end=2037 - _globals['_SETRETURNTOLAUNCHAFTERMISSIONRESPONSE']._serialized_start=2039 - _globals['_SETRETURNTOLAUNCHAFTERMISSIONRESPONSE']._serialized_end=2137 - _globals['_MISSIONITEM']._serialized_start=2140 - _globals['_MISSIONITEM']._serialized_end=3209 - _globals['_MISSIONITEM_CAMERAACTION']._serialized_start=2752 - _globals['_MISSIONITEM_CAMERAACTION']._serialized_end=3039 - _globals['_MISSIONITEM_VEHICLEACTION']._serialized_start=3042 - _globals['_MISSIONITEM_VEHICLEACTION']._serialized_end=3209 - _globals['_MISSIONPLAN']._serialized_start=3211 - _globals['_MISSIONPLAN']._serialized_end=3280 - _globals['_MISSIONPROGRESS']._serialized_start=3282 - _globals['_MISSIONPROGRESS']._serialized_end=3331 - _globals['_MISSIONRESULT']._serialized_start=3334 - _globals['_MISSIONRESULT']._serialized_end=3845 - _globals['_MISSIONRESULT_RESULT']._serialized_start=3430 - _globals['_MISSIONRESULT_RESULT']._serialized_end=3845 - _globals['_PROGRESSDATA']._serialized_start=3847 - _globals['_PROGRESSDATA']._serialized_end=3888 - _globals['_PROGRESSDATAORMISSION']._serialized_start=3891 - _globals['_PROGRESSDATAORMISSION']._serialized_end=4050 - _globals['_MISSIONSERVICE']._serialized_start=4053 - _globals['_MISSIONSERVICE']._serialized_end=5882 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\021io.mavsdk.missionB\014MissionProto" + _globals["_MISSIONITEM"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN\211\265\030H\257\274\232\362\327z>" + _globals["_MISSIONITEM"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN\211\265\030H\257\274\232\362\327z>" + _globals["_MISSIONITEM"].fields_by_name[ + "relative_altitude_m" + ]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "relative_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MISSIONITEM"].fields_by_name["speed_m_s"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "speed_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MISSIONITEM"].fields_by_name["is_fly_through"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "is_fly_through" + ]._serialized_options = b"\202\265\030\005false" + _globals["_MISSIONITEM"].fields_by_name["gimbal_pitch_deg"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "gimbal_pitch_deg" + ]._serialized_options = b"\202\265\030\003NaN\211\265\030-C\034\353\3426\032?" + _globals["_MISSIONITEM"].fields_by_name["gimbal_yaw_deg"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "gimbal_yaw_deg" + ]._serialized_options = b"\202\265\030\003NaN\211\265\030-C\034\353\3426\032?" + _globals["_MISSIONITEM"].fields_by_name["loiter_time_s"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "loiter_time_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MISSIONITEM"].fields_by_name[ + "camera_photo_interval_s" + ]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "camera_photo_interval_s" + ]._serialized_options = b"\202\265\030\0031.0" + _globals["_MISSIONITEM"].fields_by_name[ + "acceptance_radius_m" + ]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "acceptance_radius_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MISSIONITEM"].fields_by_name["yaw_deg"]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "yaw_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MISSIONITEM"].fields_by_name[ + "camera_photo_distance_m" + ]._loaded_options = None + _globals["_MISSIONITEM"].fields_by_name[ + "camera_photo_distance_m" + ]._serialized_options = b"\202\265\030\003NAN" + _globals["_PROGRESSDATA"].fields_by_name["progress"]._loaded_options = None + _globals["_PROGRESSDATA"].fields_by_name[ + "progress" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_PROGRESSDATAORMISSION"].fields_by_name[ + "has_progress" + ]._loaded_options = None + _globals["_PROGRESSDATAORMISSION"].fields_by_name[ + "has_progress" + ]._serialized_options = b"\202\265\030\005false" + _globals["_PROGRESSDATAORMISSION"].fields_by_name["progress"]._loaded_options = None + _globals["_PROGRESSDATAORMISSION"].fields_by_name[ + "progress" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MISSIONSERVICE"].methods_by_name[ + "SubscribeUploadMissionWithProgress" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "SubscribeUploadMissionWithProgress" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_MISSIONSERVICE"].methods_by_name[ + "CancelMissionUpload" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "CancelMissionUpload" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONSERVICE"].methods_by_name[ + "SubscribeDownloadMissionWithProgress" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "SubscribeDownloadMissionWithProgress" + ]._serialized_options = b"\200\265\030\000\210\265\030\001" + _globals["_MISSIONSERVICE"].methods_by_name[ + "CancelMissionDownload" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "CancelMissionDownload" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONSERVICE"].methods_by_name[ + "IsMissionFinished" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "IsMissionFinished" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONSERVICE"].methods_by_name[ + "GetReturnToLaunchAfterMission" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "GetReturnToLaunchAfterMission" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONSERVICE"].methods_by_name[ + "SetReturnToLaunchAfterMission" + ]._loaded_options = None + _globals["_MISSIONSERVICE"].methods_by_name[ + "SetReturnToLaunchAfterMission" + ]._serialized_options = b"\200\265\030\001" + _globals["_UPLOADMISSIONREQUEST"]._serialized_start = 67 + _globals["_UPLOADMISSIONREQUEST"]._serialized_end = 144 + _globals["_UPLOADMISSIONRESPONSE"]._serialized_start = 146 + _globals["_UPLOADMISSIONRESPONSE"]._serialized_end = 228 + _globals["_SUBSCRIBEUPLOADMISSIONWITHPROGRESSREQUEST"]._serialized_start = 230 + _globals["_SUBSCRIBEUPLOADMISSIONWITHPROGRESSREQUEST"]._serialized_end = 328 + _globals["_UPLOADMISSIONWITHPROGRESSRESPONSE"]._serialized_start = 331 + _globals["_UPLOADMISSIONWITHPROGRESSRESPONSE"]._serialized_end = 482 + _globals["_CANCELMISSIONUPLOADREQUEST"]._serialized_start = 484 + _globals["_CANCELMISSIONUPLOADREQUEST"]._serialized_end = 512 + _globals["_CANCELMISSIONUPLOADRESPONSE"]._serialized_start = 514 + _globals["_CANCELMISSIONUPLOADRESPONSE"]._serialized_end = 602 + _globals["_DOWNLOADMISSIONREQUEST"]._serialized_start = 604 + _globals["_DOWNLOADMISSIONREQUEST"]._serialized_end = 628 + _globals["_DOWNLOADMISSIONRESPONSE"]._serialized_start = 631 + _globals["_DOWNLOADMISSIONRESPONSE"]._serialized_end = 770 + _globals["_SUBSCRIBEDOWNLOADMISSIONWITHPROGRESSREQUEST"]._serialized_start = 772 + _globals["_SUBSCRIBEDOWNLOADMISSIONWITHPROGRESSREQUEST"]._serialized_end = 817 + _globals["_DOWNLOADMISSIONWITHPROGRESSRESPONSE"]._serialized_start = 820 + _globals["_DOWNLOADMISSIONWITHPROGRESSRESPONSE"]._serialized_end = 982 + _globals["_CANCELMISSIONDOWNLOADREQUEST"]._serialized_start = 984 + _globals["_CANCELMISSIONDOWNLOADREQUEST"]._serialized_end = 1014 + _globals["_CANCELMISSIONDOWNLOADRESPONSE"]._serialized_start = 1016 + _globals["_CANCELMISSIONDOWNLOADRESPONSE"]._serialized_end = 1106 + _globals["_STARTMISSIONREQUEST"]._serialized_start = 1108 + _globals["_STARTMISSIONREQUEST"]._serialized_end = 1129 + _globals["_STARTMISSIONRESPONSE"]._serialized_start = 1131 + _globals["_STARTMISSIONRESPONSE"]._serialized_end = 1212 + _globals["_PAUSEMISSIONREQUEST"]._serialized_start = 1214 + _globals["_PAUSEMISSIONREQUEST"]._serialized_end = 1235 + _globals["_PAUSEMISSIONRESPONSE"]._serialized_start = 1237 + _globals["_PAUSEMISSIONRESPONSE"]._serialized_end = 1318 + _globals["_CLEARMISSIONREQUEST"]._serialized_start = 1320 + _globals["_CLEARMISSIONREQUEST"]._serialized_end = 1341 + _globals["_CLEARMISSIONRESPONSE"]._serialized_start = 1343 + _globals["_CLEARMISSIONRESPONSE"]._serialized_end = 1424 + _globals["_SETCURRENTMISSIONITEMREQUEST"]._serialized_start = 1426 + _globals["_SETCURRENTMISSIONITEMREQUEST"]._serialized_end = 1471 + _globals["_SETCURRENTMISSIONITEMRESPONSE"]._serialized_start = 1473 + _globals["_SETCURRENTMISSIONITEMRESPONSE"]._serialized_end = 1563 + _globals["_ISMISSIONFINISHEDREQUEST"]._serialized_start = 1565 + _globals["_ISMISSIONFINISHEDREQUEST"]._serialized_end = 1591 + _globals["_ISMISSIONFINISHEDRESPONSE"]._serialized_start = 1593 + _globals["_ISMISSIONFINISHEDRESPONSE"]._serialized_end = 1700 + _globals["_SUBSCRIBEMISSIONPROGRESSREQUEST"]._serialized_start = 1702 + _globals["_SUBSCRIBEMISSIONPROGRESSREQUEST"]._serialized_end = 1735 + _globals["_MISSIONPROGRESSRESPONSE"]._serialized_start = 1737 + _globals["_MISSIONPROGRESSRESPONSE"]._serialized_end = 1825 + _globals["_GETRETURNTOLAUNCHAFTERMISSIONREQUEST"]._serialized_start = 1827 + _globals["_GETRETURNTOLAUNCHAFTERMISSIONREQUEST"]._serialized_end = 1865 + _globals["_GETRETURNTOLAUNCHAFTERMISSIONRESPONSE"]._serialized_start = 1867 + _globals["_GETRETURNTOLAUNCHAFTERMISSIONRESPONSE"]._serialized_end = 1981 + _globals["_SETRETURNTOLAUNCHAFTERMISSIONREQUEST"]._serialized_start = 1983 + _globals["_SETRETURNTOLAUNCHAFTERMISSIONREQUEST"]._serialized_end = 2037 + _globals["_SETRETURNTOLAUNCHAFTERMISSIONRESPONSE"]._serialized_start = 2039 + _globals["_SETRETURNTOLAUNCHAFTERMISSIONRESPONSE"]._serialized_end = 2137 + _globals["_MISSIONITEM"]._serialized_start = 2140 + _globals["_MISSIONITEM"]._serialized_end = 3209 + _globals["_MISSIONITEM_CAMERAACTION"]._serialized_start = 2752 + _globals["_MISSIONITEM_CAMERAACTION"]._serialized_end = 3039 + _globals["_MISSIONITEM_VEHICLEACTION"]._serialized_start = 3042 + _globals["_MISSIONITEM_VEHICLEACTION"]._serialized_end = 3209 + _globals["_MISSIONPLAN"]._serialized_start = 3211 + _globals["_MISSIONPLAN"]._serialized_end = 3280 + _globals["_MISSIONPROGRESS"]._serialized_start = 3282 + _globals["_MISSIONPROGRESS"]._serialized_end = 3331 + _globals["_MISSIONRESULT"]._serialized_start = 3334 + _globals["_MISSIONRESULT"]._serialized_end = 3845 + _globals["_MISSIONRESULT_RESULT"]._serialized_start = 3430 + _globals["_MISSIONRESULT_RESULT"]._serialized_end = 3845 + _globals["_PROGRESSDATA"]._serialized_start = 3847 + _globals["_PROGRESSDATA"]._serialized_end = 3888 + _globals["_PROGRESSDATAORMISSION"]._serialized_start = 3891 + _globals["_PROGRESSDATAORMISSION"]._serialized_end = 4050 + _globals["_MISSIONSERVICE"]._serialized_start = 4053 + _globals["_MISSIONSERVICE"]._serialized_end = 5882 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/mission_pb2_grpc.py b/mavsdk/mission_pb2_grpc.py index aba441e6..45fabf90 100644 --- a/mavsdk/mission_pb2_grpc.py +++ b/mavsdk/mission_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import mission_pb2 as mission_dot_mission__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in mission/mission_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in mission/mission_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class MissionServiceStub(object): - """Enable waypoint missions. - """ + """Enable waypoint missions.""" def __init__(self, channel): """Constructor. @@ -36,80 +39,93 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.UploadMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/UploadMission', - request_serializer=mission_dot_mission__pb2.UploadMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.UploadMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/UploadMission", + request_serializer=mission_dot_mission__pb2.UploadMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.UploadMissionResponse.FromString, + _registered_method=True, + ) self.SubscribeUploadMissionWithProgress = channel.unary_stream( - '/mavsdk.rpc.mission.MissionService/SubscribeUploadMissionWithProgress', - request_serializer=mission_dot_mission__pb2.SubscribeUploadMissionWithProgressRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.UploadMissionWithProgressResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/SubscribeUploadMissionWithProgress", + request_serializer=mission_dot_mission__pb2.SubscribeUploadMissionWithProgressRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.UploadMissionWithProgressResponse.FromString, + _registered_method=True, + ) self.CancelMissionUpload = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/CancelMissionUpload', - request_serializer=mission_dot_mission__pb2.CancelMissionUploadRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.CancelMissionUploadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/CancelMissionUpload", + request_serializer=mission_dot_mission__pb2.CancelMissionUploadRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.CancelMissionUploadResponse.FromString, + _registered_method=True, + ) self.DownloadMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/DownloadMission', - request_serializer=mission_dot_mission__pb2.DownloadMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.DownloadMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/DownloadMission", + request_serializer=mission_dot_mission__pb2.DownloadMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.DownloadMissionResponse.FromString, + _registered_method=True, + ) self.SubscribeDownloadMissionWithProgress = channel.unary_stream( - '/mavsdk.rpc.mission.MissionService/SubscribeDownloadMissionWithProgress', - request_serializer=mission_dot_mission__pb2.SubscribeDownloadMissionWithProgressRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.DownloadMissionWithProgressResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/SubscribeDownloadMissionWithProgress", + request_serializer=mission_dot_mission__pb2.SubscribeDownloadMissionWithProgressRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.DownloadMissionWithProgressResponse.FromString, + _registered_method=True, + ) self.CancelMissionDownload = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/CancelMissionDownload', - request_serializer=mission_dot_mission__pb2.CancelMissionDownloadRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.CancelMissionDownloadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/CancelMissionDownload", + request_serializer=mission_dot_mission__pb2.CancelMissionDownloadRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.CancelMissionDownloadResponse.FromString, + _registered_method=True, + ) self.StartMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/StartMission', - request_serializer=mission_dot_mission__pb2.StartMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.StartMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/StartMission", + request_serializer=mission_dot_mission__pb2.StartMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.StartMissionResponse.FromString, + _registered_method=True, + ) self.PauseMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/PauseMission', - request_serializer=mission_dot_mission__pb2.PauseMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.PauseMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/PauseMission", + request_serializer=mission_dot_mission__pb2.PauseMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.PauseMissionResponse.FromString, + _registered_method=True, + ) self.ClearMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/ClearMission', - request_serializer=mission_dot_mission__pb2.ClearMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.ClearMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/ClearMission", + request_serializer=mission_dot_mission__pb2.ClearMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.ClearMissionResponse.FromString, + _registered_method=True, + ) self.SetCurrentMissionItem = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/SetCurrentMissionItem', - request_serializer=mission_dot_mission__pb2.SetCurrentMissionItemRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.SetCurrentMissionItemResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/SetCurrentMissionItem", + request_serializer=mission_dot_mission__pb2.SetCurrentMissionItemRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.SetCurrentMissionItemResponse.FromString, + _registered_method=True, + ) self.IsMissionFinished = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/IsMissionFinished', - request_serializer=mission_dot_mission__pb2.IsMissionFinishedRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.IsMissionFinishedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/IsMissionFinished", + request_serializer=mission_dot_mission__pb2.IsMissionFinishedRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.IsMissionFinishedResponse.FromString, + _registered_method=True, + ) self.SubscribeMissionProgress = channel.unary_stream( - '/mavsdk.rpc.mission.MissionService/SubscribeMissionProgress', - request_serializer=mission_dot_mission__pb2.SubscribeMissionProgressRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.MissionProgressResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/SubscribeMissionProgress", + request_serializer=mission_dot_mission__pb2.SubscribeMissionProgressRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.MissionProgressResponse.FromString, + _registered_method=True, + ) self.GetReturnToLaunchAfterMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/GetReturnToLaunchAfterMission', - request_serializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/GetReturnToLaunchAfterMission", + request_serializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionResponse.FromString, + _registered_method=True, + ) self.SetReturnToLaunchAfterMission = channel.unary_unary( - '/mavsdk.rpc.mission.MissionService/SetReturnToLaunchAfterMission', - request_serializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionRequest.SerializeToString, - response_deserializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission.MissionService/SetReturnToLaunchAfterMission", + request_serializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionRequest.SerializeToString, + response_deserializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionResponse.FromString, + _registered_method=True, + ) class MissionServiceServicer(object): - """Enable waypoint missions. - """ + """Enable waypoint missions.""" def UploadMission(self, request, context): """ @@ -119,8 +135,8 @@ def UploadMission(self, request, context): executed even if the connection is lost. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeUploadMissionWithProgress(self, request, context): """ @@ -130,16 +146,16 @@ def SubscribeUploadMissionWithProgress(self, request, context): executed even if the connection is lost. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def CancelMissionUpload(self, request, context): """ Cancel an ongoing mission upload. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def DownloadMission(self, request, context): """ @@ -149,8 +165,8 @@ def DownloadMission(self, request, context): by the MAVSDK API. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeDownloadMissionWithProgress(self, request, context): """ @@ -160,16 +176,16 @@ def SubscribeDownloadMissionWithProgress(self, request, context): by the MAVSDK API. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def CancelMissionDownload(self, request, context): """ Cancel an ongoing mission download. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StartMission(self, request, context): """ @@ -178,8 +194,8 @@ def StartMission(self, request, context): A mission must be uploaded to the vehicle before this can be called. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PauseMission(self, request, context): """ @@ -191,16 +207,16 @@ def PauseMission(self, request, context): around the location where it paused. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ClearMission(self, request, context): """ Clear the mission saved on the vehicle. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetCurrentMissionItem(self, request, context): """ @@ -213,24 +229,24 @@ def SetCurrentMissionItem(self, request, context): are used. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def IsMissionFinished(self, request, context): """ Check if the mission has been finished. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeMissionProgress(self, request, context): """ Subscribe to mission progress updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetReturnToLaunchAfterMission(self, request, context): """ @@ -240,8 +256,8 @@ def GetReturnToLaunchAfterMission(self, request, context): needs to be downloaded. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetReturnToLaunchAfterMission(self, request, context): """ @@ -251,109 +267,113 @@ def SetReturnToLaunchAfterMission(self, request, context): the mission may have to be uploaded again. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_MissionServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'UploadMission': grpc.unary_unary_rpc_method_handler( - servicer.UploadMission, - request_deserializer=mission_dot_mission__pb2.UploadMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.UploadMissionResponse.SerializeToString, - ), - 'SubscribeUploadMissionWithProgress': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeUploadMissionWithProgress, - request_deserializer=mission_dot_mission__pb2.SubscribeUploadMissionWithProgressRequest.FromString, - response_serializer=mission_dot_mission__pb2.UploadMissionWithProgressResponse.SerializeToString, - ), - 'CancelMissionUpload': grpc.unary_unary_rpc_method_handler( - servicer.CancelMissionUpload, - request_deserializer=mission_dot_mission__pb2.CancelMissionUploadRequest.FromString, - response_serializer=mission_dot_mission__pb2.CancelMissionUploadResponse.SerializeToString, - ), - 'DownloadMission': grpc.unary_unary_rpc_method_handler( - servicer.DownloadMission, - request_deserializer=mission_dot_mission__pb2.DownloadMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.DownloadMissionResponse.SerializeToString, - ), - 'SubscribeDownloadMissionWithProgress': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeDownloadMissionWithProgress, - request_deserializer=mission_dot_mission__pb2.SubscribeDownloadMissionWithProgressRequest.FromString, - response_serializer=mission_dot_mission__pb2.DownloadMissionWithProgressResponse.SerializeToString, - ), - 'CancelMissionDownload': grpc.unary_unary_rpc_method_handler( - servicer.CancelMissionDownload, - request_deserializer=mission_dot_mission__pb2.CancelMissionDownloadRequest.FromString, - response_serializer=mission_dot_mission__pb2.CancelMissionDownloadResponse.SerializeToString, - ), - 'StartMission': grpc.unary_unary_rpc_method_handler( - servicer.StartMission, - request_deserializer=mission_dot_mission__pb2.StartMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.StartMissionResponse.SerializeToString, - ), - 'PauseMission': grpc.unary_unary_rpc_method_handler( - servicer.PauseMission, - request_deserializer=mission_dot_mission__pb2.PauseMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.PauseMissionResponse.SerializeToString, - ), - 'ClearMission': grpc.unary_unary_rpc_method_handler( - servicer.ClearMission, - request_deserializer=mission_dot_mission__pb2.ClearMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.ClearMissionResponse.SerializeToString, - ), - 'SetCurrentMissionItem': grpc.unary_unary_rpc_method_handler( - servicer.SetCurrentMissionItem, - request_deserializer=mission_dot_mission__pb2.SetCurrentMissionItemRequest.FromString, - response_serializer=mission_dot_mission__pb2.SetCurrentMissionItemResponse.SerializeToString, - ), - 'IsMissionFinished': grpc.unary_unary_rpc_method_handler( - servicer.IsMissionFinished, - request_deserializer=mission_dot_mission__pb2.IsMissionFinishedRequest.FromString, - response_serializer=mission_dot_mission__pb2.IsMissionFinishedResponse.SerializeToString, - ), - 'SubscribeMissionProgress': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeMissionProgress, - request_deserializer=mission_dot_mission__pb2.SubscribeMissionProgressRequest.FromString, - response_serializer=mission_dot_mission__pb2.MissionProgressResponse.SerializeToString, - ), - 'GetReturnToLaunchAfterMission': grpc.unary_unary_rpc_method_handler( - servicer.GetReturnToLaunchAfterMission, - request_deserializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionResponse.SerializeToString, - ), - 'SetReturnToLaunchAfterMission': grpc.unary_unary_rpc_method_handler( - servicer.SetReturnToLaunchAfterMission, - request_deserializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionRequest.FromString, - response_serializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionResponse.SerializeToString, - ), + "UploadMission": grpc.unary_unary_rpc_method_handler( + servicer.UploadMission, + request_deserializer=mission_dot_mission__pb2.UploadMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.UploadMissionResponse.SerializeToString, + ), + "SubscribeUploadMissionWithProgress": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeUploadMissionWithProgress, + request_deserializer=mission_dot_mission__pb2.SubscribeUploadMissionWithProgressRequest.FromString, + response_serializer=mission_dot_mission__pb2.UploadMissionWithProgressResponse.SerializeToString, + ), + "CancelMissionUpload": grpc.unary_unary_rpc_method_handler( + servicer.CancelMissionUpload, + request_deserializer=mission_dot_mission__pb2.CancelMissionUploadRequest.FromString, + response_serializer=mission_dot_mission__pb2.CancelMissionUploadResponse.SerializeToString, + ), + "DownloadMission": grpc.unary_unary_rpc_method_handler( + servicer.DownloadMission, + request_deserializer=mission_dot_mission__pb2.DownloadMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.DownloadMissionResponse.SerializeToString, + ), + "SubscribeDownloadMissionWithProgress": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeDownloadMissionWithProgress, + request_deserializer=mission_dot_mission__pb2.SubscribeDownloadMissionWithProgressRequest.FromString, + response_serializer=mission_dot_mission__pb2.DownloadMissionWithProgressResponse.SerializeToString, + ), + "CancelMissionDownload": grpc.unary_unary_rpc_method_handler( + servicer.CancelMissionDownload, + request_deserializer=mission_dot_mission__pb2.CancelMissionDownloadRequest.FromString, + response_serializer=mission_dot_mission__pb2.CancelMissionDownloadResponse.SerializeToString, + ), + "StartMission": grpc.unary_unary_rpc_method_handler( + servicer.StartMission, + request_deserializer=mission_dot_mission__pb2.StartMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.StartMissionResponse.SerializeToString, + ), + "PauseMission": grpc.unary_unary_rpc_method_handler( + servicer.PauseMission, + request_deserializer=mission_dot_mission__pb2.PauseMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.PauseMissionResponse.SerializeToString, + ), + "ClearMission": grpc.unary_unary_rpc_method_handler( + servicer.ClearMission, + request_deserializer=mission_dot_mission__pb2.ClearMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.ClearMissionResponse.SerializeToString, + ), + "SetCurrentMissionItem": grpc.unary_unary_rpc_method_handler( + servicer.SetCurrentMissionItem, + request_deserializer=mission_dot_mission__pb2.SetCurrentMissionItemRequest.FromString, + response_serializer=mission_dot_mission__pb2.SetCurrentMissionItemResponse.SerializeToString, + ), + "IsMissionFinished": grpc.unary_unary_rpc_method_handler( + servicer.IsMissionFinished, + request_deserializer=mission_dot_mission__pb2.IsMissionFinishedRequest.FromString, + response_serializer=mission_dot_mission__pb2.IsMissionFinishedResponse.SerializeToString, + ), + "SubscribeMissionProgress": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeMissionProgress, + request_deserializer=mission_dot_mission__pb2.SubscribeMissionProgressRequest.FromString, + response_serializer=mission_dot_mission__pb2.MissionProgressResponse.SerializeToString, + ), + "GetReturnToLaunchAfterMission": grpc.unary_unary_rpc_method_handler( + servicer.GetReturnToLaunchAfterMission, + request_deserializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.GetReturnToLaunchAfterMissionResponse.SerializeToString, + ), + "SetReturnToLaunchAfterMission": grpc.unary_unary_rpc_method_handler( + servicer.SetReturnToLaunchAfterMission, + request_deserializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionRequest.FromString, + response_serializer=mission_dot_mission__pb2.SetReturnToLaunchAfterMissionResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.mission.MissionService', rpc_method_handlers) + "mavsdk.rpc.mission.MissionService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.mission.MissionService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.mission.MissionService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class MissionService(object): - """Enable waypoint missions. - """ + """Enable waypoint missions.""" @staticmethod - def UploadMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def UploadMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/UploadMission', + "/mavsdk.rpc.mission.MissionService/UploadMission", mission_dot_mission__pb2.UploadMissionRequest.SerializeToString, mission_dot_mission__pb2.UploadMissionResponse.FromString, options, @@ -364,23 +384,26 @@ def UploadMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeUploadMissionWithProgress(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeUploadMissionWithProgress( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission.MissionService/SubscribeUploadMissionWithProgress', + "/mavsdk.rpc.mission.MissionService/SubscribeUploadMissionWithProgress", mission_dot_mission__pb2.SubscribeUploadMissionWithProgressRequest.SerializeToString, mission_dot_mission__pb2.UploadMissionWithProgressResponse.FromString, options, @@ -391,23 +414,26 @@ def SubscribeUploadMissionWithProgress(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def CancelMissionUpload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def CancelMissionUpload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/CancelMissionUpload', + "/mavsdk.rpc.mission.MissionService/CancelMissionUpload", mission_dot_mission__pb2.CancelMissionUploadRequest.SerializeToString, mission_dot_mission__pb2.CancelMissionUploadResponse.FromString, options, @@ -418,23 +444,26 @@ def CancelMissionUpload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def DownloadMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def DownloadMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/DownloadMission', + "/mavsdk.rpc.mission.MissionService/DownloadMission", mission_dot_mission__pb2.DownloadMissionRequest.SerializeToString, mission_dot_mission__pb2.DownloadMissionResponse.FromString, options, @@ -445,23 +474,26 @@ def DownloadMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeDownloadMissionWithProgress(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeDownloadMissionWithProgress( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission.MissionService/SubscribeDownloadMissionWithProgress', + "/mavsdk.rpc.mission.MissionService/SubscribeDownloadMissionWithProgress", mission_dot_mission__pb2.SubscribeDownloadMissionWithProgressRequest.SerializeToString, mission_dot_mission__pb2.DownloadMissionWithProgressResponse.FromString, options, @@ -472,23 +504,26 @@ def SubscribeDownloadMissionWithProgress(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def CancelMissionDownload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def CancelMissionDownload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/CancelMissionDownload', + "/mavsdk.rpc.mission.MissionService/CancelMissionDownload", mission_dot_mission__pb2.CancelMissionDownloadRequest.SerializeToString, mission_dot_mission__pb2.CancelMissionDownloadResponse.FromString, options, @@ -499,23 +534,26 @@ def CancelMissionDownload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StartMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/StartMission', + "/mavsdk.rpc.mission.MissionService/StartMission", mission_dot_mission__pb2.StartMissionRequest.SerializeToString, mission_dot_mission__pb2.StartMissionResponse.FromString, options, @@ -526,23 +564,26 @@ def StartMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PauseMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PauseMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/PauseMission', + "/mavsdk.rpc.mission.MissionService/PauseMission", mission_dot_mission__pb2.PauseMissionRequest.SerializeToString, mission_dot_mission__pb2.PauseMissionResponse.FromString, options, @@ -553,23 +594,26 @@ def PauseMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ClearMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ClearMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/ClearMission', + "/mavsdk.rpc.mission.MissionService/ClearMission", mission_dot_mission__pb2.ClearMissionRequest.SerializeToString, mission_dot_mission__pb2.ClearMissionResponse.FromString, options, @@ -580,23 +624,26 @@ def ClearMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetCurrentMissionItem(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetCurrentMissionItem( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/SetCurrentMissionItem', + "/mavsdk.rpc.mission.MissionService/SetCurrentMissionItem", mission_dot_mission__pb2.SetCurrentMissionItemRequest.SerializeToString, mission_dot_mission__pb2.SetCurrentMissionItemResponse.FromString, options, @@ -607,23 +654,26 @@ def SetCurrentMissionItem(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def IsMissionFinished(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def IsMissionFinished( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/IsMissionFinished', + "/mavsdk.rpc.mission.MissionService/IsMissionFinished", mission_dot_mission__pb2.IsMissionFinishedRequest.SerializeToString, mission_dot_mission__pb2.IsMissionFinishedResponse.FromString, options, @@ -634,23 +684,26 @@ def IsMissionFinished(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeMissionProgress(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeMissionProgress( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission.MissionService/SubscribeMissionProgress', + "/mavsdk.rpc.mission.MissionService/SubscribeMissionProgress", mission_dot_mission__pb2.SubscribeMissionProgressRequest.SerializeToString, mission_dot_mission__pb2.MissionProgressResponse.FromString, options, @@ -661,23 +714,26 @@ def SubscribeMissionProgress(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetReturnToLaunchAfterMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetReturnToLaunchAfterMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/GetReturnToLaunchAfterMission', + "/mavsdk.rpc.mission.MissionService/GetReturnToLaunchAfterMission", mission_dot_mission__pb2.GetReturnToLaunchAfterMissionRequest.SerializeToString, mission_dot_mission__pb2.GetReturnToLaunchAfterMissionResponse.FromString, options, @@ -688,23 +744,26 @@ def GetReturnToLaunchAfterMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetReturnToLaunchAfterMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetReturnToLaunchAfterMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission.MissionService/SetReturnToLaunchAfterMission', + "/mavsdk.rpc.mission.MissionService/SetReturnToLaunchAfterMission", mission_dot_mission__pb2.SetReturnToLaunchAfterMissionRequest.SerializeToString, mission_dot_mission__pb2.SetReturnToLaunchAfterMissionResponse.FromString, options, @@ -715,4 +774,5 @@ def SetReturnToLaunchAfterMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/mission_raw.py b/mavsdk/mission_raw.py index ba270c22..8ba2da18 100644 --- a/mavsdk/mission_raw.py +++ b/mavsdk/mission_raw.py @@ -8,143 +8,120 @@ class MissionProgress: """ - Mission progress type. + Mission progress type. - Parameters - ---------- - current : int32_t - Current mission item index (0-based), if equal to total, the mission is finished + Parameters + ---------- + current : int32_t + Current mission item index (0-based), if equal to total, the mission is finished - total : int32_t - Total number of mission items + total : int32_t + Total number of mission items - """ - - + """ - def __init__( - self, - current, - total): - """ Initializes the MissionProgress object """ + def __init__(self, current, total): + """Initializes the MissionProgress object""" self.current = current self.total = total def __eq__(self, to_compare): - """ Checks if two MissionProgress are the same """ + """Checks if two MissionProgress are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionProgress object - return \ - (self.current == to_compare.current) and \ - (self.total == to_compare.total) + return (self.current == to_compare.current) and ( + self.total == to_compare.total + ) except AttributeError: return False def __str__(self): - """ MissionProgress in string representation """ - struct_repr = ", ".join([ - "current: " + str(self.current), - "total: " + str(self.total) - ]) + """MissionProgress in string representation""" + struct_repr = ", ".join( + ["current: " + str(self.current), "total: " + str(self.total)] + ) return f"MissionProgress: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionProgress): - """ Translates a gRPC struct to the SDK equivalent """ - return MissionProgress( - - rpcMissionProgress.current, - - - rpcMissionProgress.total - ) + """Translates a gRPC struct to the SDK equivalent""" + return MissionProgress(rpcMissionProgress.current, rpcMissionProgress.total) def translate_to_rpc(self, rpcMissionProgress): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionProgress.current = self.current - - - - - + rpcMissionProgress.total = self.total - - - class MissionItem: """ - Mission item exactly identical to MAVLink MISSION_ITEM_INT. + Mission item exactly identical to MAVLink MISSION_ITEM_INT. - Parameters - ---------- - seq : uint32_t - Sequence (uint16_t) + Parameters + ---------- + seq : uint32_t + Sequence (uint16_t) - frame : uint32_t - The coordinate system of the waypoint (actually uint8_t) + frame : uint32_t + The coordinate system of the waypoint (actually uint8_t) - command : uint32_t - The scheduled action for the waypoint (actually uint16_t) + command : uint32_t + The scheduled action for the waypoint (actually uint16_t) - current : uint32_t - false:0, true:1 (actually uint8_t) + current : uint32_t + false:0, true:1 (actually uint8_t) - autocontinue : uint32_t - Autocontinue to next waypoint (actually uint8_t) + autocontinue : uint32_t + Autocontinue to next waypoint (actually uint8_t) - param1 : float - PARAM1, see MAV_CMD enum + param1 : float + PARAM1, see MAV_CMD enum - param2 : float - PARAM2, see MAV_CMD enum + param2 : float + PARAM2, see MAV_CMD enum - param3 : float - PARAM3, see MAV_CMD enum + param3 : float + PARAM3, see MAV_CMD enum - param4 : float - PARAM4, see MAV_CMD enum + param4 : float + PARAM4, see MAV_CMD enum - x : int32_t - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + x : int32_t + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - y : int32_t - PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + y : int32_t + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - z : float - PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame) + z : float + PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame) - mission_type : uint32_t - Mission type (actually uint8_t) + mission_type : uint32_t + Mission type (actually uint8_t) - """ - - + """ def __init__( - self, - seq, - frame, - command, - current, - autocontinue, - param1, - param2, - param3, - param4, - x, - y, - z, - mission_type): - """ Initializes the MissionItem object """ + self, + seq, + frame, + command, + current, + autocontinue, + param1, + param2, + param3, + param4, + x, + y, + z, + mission_type, + ): + """Initializes the MissionItem object""" self.seq = seq self.frame = frame self.command = command @@ -160,31 +137,33 @@ def __init__( self.mission_type = mission_type def __eq__(self, to_compare): - """ Checks if two MissionItem are the same """ + """Checks if two MissionItem are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionItem object - return \ - (self.seq == to_compare.seq) and \ - (self.frame == to_compare.frame) and \ - (self.command == to_compare.command) and \ - (self.current == to_compare.current) and \ - (self.autocontinue == to_compare.autocontinue) and \ - (self.param1 == to_compare.param1) and \ - (self.param2 == to_compare.param2) and \ - (self.param3 == to_compare.param3) and \ - (self.param4 == to_compare.param4) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) and \ - (self.mission_type == to_compare.mission_type) + return ( + (self.seq == to_compare.seq) + and (self.frame == to_compare.frame) + and (self.command == to_compare.command) + and (self.current == to_compare.current) + and (self.autocontinue == to_compare.autocontinue) + and (self.param1 == to_compare.param1) + and (self.param2 == to_compare.param2) + and (self.param3 == to_compare.param3) + and (self.param4 == to_compare.param4) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + and (self.mission_type == to_compare.mission_type) + ) except AttributeError: return False def __str__(self): - """ MissionItem in string representation """ - struct_repr = ", ".join([ + """MissionItem in string representation""" + struct_repr = ", ".join( + [ "seq: " + str(self.seq), "frame: " + str(self.frame), "command: " + str(self.command), @@ -197,338 +176,247 @@ def __str__(self): "x: " + str(self.x), "y: " + str(self.y), "z: " + str(self.z), - "mission_type: " + str(self.mission_type) - ]) + "mission_type: " + str(self.mission_type), + ] + ) return f"MissionItem: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionItem): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionItem( - - rpcMissionItem.seq, - - - rpcMissionItem.frame, - - - rpcMissionItem.command, - - - rpcMissionItem.current, - - - rpcMissionItem.autocontinue, - - - rpcMissionItem.param1, - - - rpcMissionItem.param2, - - - rpcMissionItem.param3, - - - rpcMissionItem.param4, - - - rpcMissionItem.x, - - - rpcMissionItem.y, - - - rpcMissionItem.z, - - - rpcMissionItem.mission_type - ) + rpcMissionItem.seq, + rpcMissionItem.frame, + rpcMissionItem.command, + rpcMissionItem.current, + rpcMissionItem.autocontinue, + rpcMissionItem.param1, + rpcMissionItem.param2, + rpcMissionItem.param3, + rpcMissionItem.param4, + rpcMissionItem.x, + rpcMissionItem.y, + rpcMissionItem.z, + rpcMissionItem.mission_type, + ) def translate_to_rpc(self, rpcMissionItem): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionItem.seq = self.seq - - - - - + rpcMissionItem.frame = self.frame - - - - - + rpcMissionItem.command = self.command - - - - - + rpcMissionItem.current = self.current - - - - - + rpcMissionItem.autocontinue = self.autocontinue - - - - - + rpcMissionItem.param1 = self.param1 - - - - - + rpcMissionItem.param2 = self.param2 - - - - - + rpcMissionItem.param3 = self.param3 - - - - - + rpcMissionItem.param4 = self.param4 - - - - - + rpcMissionItem.x = self.x - - - - - + rpcMissionItem.y = self.y - - - - - + rpcMissionItem.z = self.z - - - - - + rpcMissionItem.mission_type = self.mission_type - - - class MissionImportData: """ - Mission import data + Mission import data - Parameters - ---------- - mission_items : [MissionItem] - Mission items + Parameters + ---------- + mission_items : [MissionItem] + Mission items - geofence_items : [MissionItem] - Geofence items + geofence_items : [MissionItem] + Geofence items - rally_items : [MissionItem] - Rally items + rally_items : [MissionItem] + Rally items - """ - - + """ - def __init__( - self, - mission_items, - geofence_items, - rally_items): - """ Initializes the MissionImportData object """ + def __init__(self, mission_items, geofence_items, rally_items): + """Initializes the MissionImportData object""" self.mission_items = mission_items self.geofence_items = geofence_items self.rally_items = rally_items def __eq__(self, to_compare): - """ Checks if two MissionImportData are the same """ + """Checks if two MissionImportData are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionImportData object - return \ - (self.mission_items == to_compare.mission_items) and \ - (self.geofence_items == to_compare.geofence_items) and \ - (self.rally_items == to_compare.rally_items) + return ( + (self.mission_items == to_compare.mission_items) + and (self.geofence_items == to_compare.geofence_items) + and (self.rally_items == to_compare.rally_items) + ) except AttributeError: return False def __str__(self): - """ MissionImportData in string representation """ - struct_repr = ", ".join([ + """MissionImportData in string representation""" + struct_repr = ", ".join( + [ "mission_items: " + str(self.mission_items), "geofence_items: " + str(self.geofence_items), - "rally_items: " + str(self.rally_items) - ]) + "rally_items: " + str(self.rally_items), + ] + ) return f"MissionImportData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionImportData): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionImportData( - - list(map(lambda elem: MissionItem.translate_from_rpc(elem), rpcMissionImportData.mission_items)), - - - list(map(lambda elem: MissionItem.translate_from_rpc(elem), rpcMissionImportData.geofence_items)), - - - list(map(lambda elem: MissionItem.translate_from_rpc(elem), rpcMissionImportData.rally_items)) + list( + map( + lambda elem: MissionItem.translate_from_rpc(elem), + rpcMissionImportData.mission_items, + ) + ), + list( + map( + lambda elem: MissionItem.translate_from_rpc(elem), + rpcMissionImportData.geofence_items, ) + ), + list( + map( + lambda elem: MissionItem.translate_from_rpc(elem), + rpcMissionImportData.rally_items, + ) + ), + ) def translate_to_rpc(self, rpcMissionImportData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.mission_items: - rpc_elem = mission_raw_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcMissionImportData.mission_items.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.geofence_items: - rpc_elem = mission_raw_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcMissionImportData.geofence_items.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.rally_items: - rpc_elem = mission_raw_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcMissionImportData.rally_items.extend(rpc_elems_list) - - - class MissionRawResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - ERROR - Error + ERROR + Error - TOO_MANY_MISSION_ITEMS - Too many mission items in the mission + TOO_MANY_MISSION_ITEMS + Too many mission items in the mission - BUSY - Vehicle is busy + BUSY + Vehicle is busy - TIMEOUT - Request timed out + TIMEOUT + Request timed out - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - UNSUPPORTED - Mission downloaded from the system is not supported + UNSUPPORTED + Mission downloaded from the system is not supported - NO_MISSION_AVAILABLE - No mission available on the system + NO_MISSION_AVAILABLE + No mission available on the system - TRANSFER_CANCELLED - Mission transfer (upload or download) has been cancelled + TRANSFER_CANCELLED + Mission transfer (upload or download) has been cancelled - FAILED_TO_OPEN_QGC_PLAN - Failed to open the QGroundControl plan + FAILED_TO_OPEN_QGC_PLAN + Failed to open the QGroundControl plan - FAILED_TO_PARSE_QGC_PLAN - Failed to parse the QGroundControl plan + FAILED_TO_PARSE_QGC_PLAN + Failed to parse the QGroundControl plan - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - DENIED - Request denied + DENIED + Request denied - MISSION_TYPE_NOT_CONSISTENT - Mission type is not consistent + MISSION_TYPE_NOT_CONSISTENT + Mission type is not consistent - INVALID_SEQUENCE - The mission item sequences are not increasing correctly + INVALID_SEQUENCE + The mission item sequences are not increasing correctly - CURRENT_INVALID - The current item is not set correctly + CURRENT_INVALID + The current item is not set correctly - PROTOCOL_ERROR - There was a protocol error + PROTOCOL_ERROR + There was a protocol error - INT_MESSAGES_NOT_SUPPORTED - The system does not support the MISSION_INT protocol + INT_MESSAGES_NOT_SUPPORTED + The system does not support the MISSION_INT protocol - FAILED_TO_OPEN_MISSION_PLANNER_PLAN - Failed to open the Mission Planner plan + FAILED_TO_OPEN_MISSION_PLANNER_PLAN + Failed to open the Mission Planner plan - FAILED_TO_PARSE_MISSION_PLANNER_PLAN - Failed to parse the Mission Planner plan + FAILED_TO_PARSE_MISSION_PLANNER_PLAN + Failed to parse the Mission Planner plan - """ + """ - UNKNOWN = 0 SUCCESS = 1 ERROR = 2 @@ -581,7 +469,9 @@ def translate_to_rpc(self): if self == MissionRawResult.Result.DENIED: return mission_raw_pb2.MissionRawResult.RESULT_DENIED if self == MissionRawResult.Result.MISSION_TYPE_NOT_CONSISTENT: - return mission_raw_pb2.MissionRawResult.RESULT_MISSION_TYPE_NOT_CONSISTENT + return ( + mission_raw_pb2.MissionRawResult.RESULT_MISSION_TYPE_NOT_CONSISTENT + ) if self == MissionRawResult.Result.INVALID_SEQUENCE: return mission_raw_pb2.MissionRawResult.RESULT_INVALID_SEQUENCE if self == MissionRawResult.Result.CURRENT_INVALID: @@ -589,7 +479,9 @@ def translate_to_rpc(self): if self == MissionRawResult.Result.PROTOCOL_ERROR: return mission_raw_pb2.MissionRawResult.RESULT_PROTOCOL_ERROR if self == MissionRawResult.Result.INT_MESSAGES_NOT_SUPPORTED: - return mission_raw_pb2.MissionRawResult.RESULT_INT_MESSAGES_NOT_SUPPORTED + return ( + mission_raw_pb2.MissionRawResult.RESULT_INT_MESSAGES_NOT_SUPPORTED + ) if self == MissionRawResult.Result.FAILED_TO_OPEN_MISSION_PLANNER_PLAN: return mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_OPEN_MISSION_PLANNER_PLAN if self == MissionRawResult.Result.FAILED_TO_PARSE_MISSION_PLANNER_PLAN: @@ -597,115 +489,132 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_UNKNOWN: return MissionRawResult.Result.UNKNOWN if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_SUCCESS: return MissionRawResult.Result.SUCCESS if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_ERROR: return MissionRawResult.Result.ERROR - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_TOO_MANY_MISSION_ITEMS: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_TOO_MANY_MISSION_ITEMS + ): return MissionRawResult.Result.TOO_MANY_MISSION_ITEMS if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_BUSY: return MissionRawResult.Result.BUSY if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_TIMEOUT: return MissionRawResult.Result.TIMEOUT - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_INVALID_ARGUMENT: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_INVALID_ARGUMENT + ): return MissionRawResult.Result.INVALID_ARGUMENT if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_UNSUPPORTED: return MissionRawResult.Result.UNSUPPORTED - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_NO_MISSION_AVAILABLE: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_NO_MISSION_AVAILABLE + ): return MissionRawResult.Result.NO_MISSION_AVAILABLE - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_TRANSFER_CANCELLED: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_TRANSFER_CANCELLED + ): return MissionRawResult.Result.TRANSFER_CANCELLED - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_OPEN_QGC_PLAN: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_OPEN_QGC_PLAN + ): return MissionRawResult.Result.FAILED_TO_OPEN_QGC_PLAN - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_PARSE_QGC_PLAN: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_PARSE_QGC_PLAN + ): return MissionRawResult.Result.FAILED_TO_PARSE_QGC_PLAN if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_NO_SYSTEM: return MissionRawResult.Result.NO_SYSTEM if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_DENIED: return MissionRawResult.Result.DENIED - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_MISSION_TYPE_NOT_CONSISTENT: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_MISSION_TYPE_NOT_CONSISTENT + ): return MissionRawResult.Result.MISSION_TYPE_NOT_CONSISTENT - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_INVALID_SEQUENCE: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_INVALID_SEQUENCE + ): return MissionRawResult.Result.INVALID_SEQUENCE - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_CURRENT_INVALID: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_CURRENT_INVALID + ): return MissionRawResult.Result.CURRENT_INVALID if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_PROTOCOL_ERROR: return MissionRawResult.Result.PROTOCOL_ERROR - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_INT_MESSAGES_NOT_SUPPORTED: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_INT_MESSAGES_NOT_SUPPORTED + ): return MissionRawResult.Result.INT_MESSAGES_NOT_SUPPORTED - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_OPEN_MISSION_PLANNER_PLAN: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_OPEN_MISSION_PLANNER_PLAN + ): return MissionRawResult.Result.FAILED_TO_OPEN_MISSION_PLANNER_PLAN - if rpc_enum_value == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_PARSE_MISSION_PLANNER_PLAN: + if ( + rpc_enum_value + == mission_raw_pb2.MissionRawResult.RESULT_FAILED_TO_PARSE_MISSION_PLANNER_PLAN + ): return MissionRawResult.Result.FAILED_TO_PARSE_MISSION_PLANNER_PLAN def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the MissionRawResult object """ + def __init__(self, result, result_str): + """Initializes the MissionRawResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two MissionRawResult are the same """ + """Checks if two MissionRawResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionRawResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ MissionRawResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """MissionRawResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"MissionRawResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionRawResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionRawResult( - - MissionRawResult.Result.translate_from_rpc(rpcMissionRawResult.result), - - - rpcMissionRawResult.result_str - ) + MissionRawResult.Result.translate_from_rpc(rpcMissionRawResult.result), + rpcMissionRawResult.result_str, + ) def translate_to_rpc(self, rpcMissionRawResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionRawResult.result = self.result.translate_to_rpc() - - - - - - rpcMissionRawResult.result_str = self.result_str - - - + rpcMissionRawResult.result_str = self.result_str class MissionRawError(Exception): - """ Raised when a MissionRawResult is a fail code """ + """Raised when a MissionRawResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -718,377 +627,344 @@ def __str__(self): class MissionRaw(AsyncBase): """ - Enable raw missions as exposed by MAVLink. + Enable raw missions as exposed by MAVLink. - Generated by dcsdkgen - MAVSDK MissionRaw API + Generated by dcsdkgen - MAVSDK MissionRaw API """ # Plugin name name = "MissionRaw" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = mission_raw_pb2_grpc.MissionRawServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return MissionRawResult.translate_from_rpc(response.mission_raw_result) - async def upload_mission(self, mission_items): """ - Upload a list of raw mission items to the system. + Upload a list of raw mission items to the system. - The raw mission items are uploaded to a drone. Once uploaded the mission - can be started and executed even if the connection is lost. + The raw mission items are uploaded to a drone. Once uploaded the mission + can be started and executed even if the connection is lost. - Parameters - ---------- - mission_items : [MissionItem] - The mission items + Parameters + ---------- + mission_items : [MissionItem] + The mission items - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.UploadMissionRequest() - + rpc_elems_list = [] for elem in mission_items: - rpc_elem = mission_raw_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + request.mission_items.extend(rpc_elems_list) - - + response = await self._stub.UploadMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "upload_mission()", mission_items) - async def upload_geofence(self, mission_items): """ - Upload a list of geofence items to the system. + Upload a list of geofence items to the system. - Parameters - ---------- - mission_items : [MissionItem] - The mission items + Parameters + ---------- + mission_items : [MissionItem] + The mission items - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.UploadGeofenceRequest() - + rpc_elems_list = [] for elem in mission_items: - rpc_elem = mission_raw_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + request.mission_items.extend(rpc_elems_list) - - + response = await self._stub.UploadGeofence(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "upload_geofence()", mission_items) - async def upload_rally_points(self, mission_items): """ - Upload a list of rally point items to the system. + Upload a list of rally point items to the system. - Parameters - ---------- - mission_items : [MissionItem] - The mission items + Parameters + ---------- + mission_items : [MissionItem] + The mission items - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.UploadRallyPointsRequest() - + rpc_elems_list = [] for elem in mission_items: - rpc_elem = mission_raw_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + request.mission_items.extend(rpc_elems_list) - - + response = await self._stub.UploadRallyPoints(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "upload_rally_points()", mission_items) - async def cancel_mission_upload(self): """ - Cancel an ongoing mission upload. + Cancel an ongoing mission upload. - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.CancelMissionUploadRequest() response = await self._stub.CancelMissionUpload(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "cancel_mission_upload()") - async def download_mission(self): """ - Download a list of raw mission items from the system (asynchronous). + Download a list of raw mission items from the system (asynchronous). - Returns - ------- - mission_items : [MissionItem] - The mission items + Returns + ------- + mission_items : [MissionItem] + The mission items - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.DownloadMissionRequest() response = await self._stub.DownloadMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "download_mission()") - mission_items = [] for mission_items_rpc in response.mission_items: mission_items.append(MissionItem.translate_from_rpc(mission_items_rpc)) return mission_items - async def download_geofence(self): """ - Download a list of raw geofence items from the system (asynchronous). + Download a list of raw geofence items from the system (asynchronous). - Returns - ------- - geofence_items : [MissionItem] - The geofence items + Returns + ------- + geofence_items : [MissionItem] + The geofence items - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.DownloadGeofenceRequest() response = await self._stub.DownloadGeofence(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "download_geofence()") - geofence_items = [] for geofence_items_rpc in response.geofence_items: geofence_items.append(MissionItem.translate_from_rpc(geofence_items_rpc)) return geofence_items - async def download_rallypoints(self): """ - Download a list of raw rallypoint items from the system (asynchronous). + Download a list of raw rallypoint items from the system (asynchronous). - Returns - ------- - rallypoint_items : [MissionItem] - The rallypoint items + Returns + ------- + rallypoint_items : [MissionItem] + The rallypoint items - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.DownloadRallypointsRequest() response = await self._stub.DownloadRallypoints(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "download_rallypoints()") - rallypoint_items = [] for rallypoint_items_rpc in response.rallypoint_items: - rallypoint_items.append(MissionItem.translate_from_rpc(rallypoint_items_rpc)) + rallypoint_items.append( + MissionItem.translate_from_rpc(rallypoint_items_rpc) + ) return rallypoint_items - async def cancel_mission_download(self): """ - Cancel an ongoing mission download. + Cancel an ongoing mission download. - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.CancelMissionDownloadRequest() response = await self._stub.CancelMissionDownload(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "cancel_mission_download()") - async def start_mission(self): """ - Start the mission. + Start the mission. - A mission must be uploaded to the vehicle before this can be called. + A mission must be uploaded to the vehicle before this can be called. - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.StartMissionRequest() response = await self._stub.StartMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "start_mission()") - async def pause_mission(self): """ - Pause the mission. + Pause the mission. - Pausing the mission puts the vehicle into - [HOLD mode](https://docs.px4.io/en/flight_modes/hold.html). - A multicopter should just hover at the spot while a fixedwing vehicle should loiter - around the location where it paused. + Pausing the mission puts the vehicle into + [HOLD mode](https://docs.px4.io/en/flight_modes/hold.html). + A multicopter should just hover at the spot while a fixedwing vehicle should loiter + around the location where it paused. - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.PauseMissionRequest() response = await self._stub.PauseMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "pause_mission()") - async def clear_mission(self): """ - Clear the mission saved on the vehicle. + Clear the mission saved on the vehicle. - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.ClearMissionRequest() response = await self._stub.ClearMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "clear_mission()") - async def set_current_mission_item(self, index): """ - Sets the raw mission item index to go to. + Sets the raw mission item index to go to. - By setting the current index to 0, the mission is restarted from the beginning. If it is set - to a specific index of a raw mission item, the mission will be set to this item. + By setting the current index to 0, the mission is restarted from the beginning. If it is set + to a specific index of a raw mission item, the mission will be set to this item. - Parameters - ---------- - index : int32_t - Index of the mission item to be set as the next one (0-based) + Parameters + ---------- + index : int32_t + Index of the mission item to be set as the next one (0-based) - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.SetCurrentMissionItemRequest() request.index = index response = await self._stub.SetCurrentMissionItem(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "set_current_mission_item()", index) - async def mission_progress(self): """ - Subscribe to mission progress updates. + Subscribe to mission progress updates. + + Yields + ------- + mission_progress : MissionProgress + Mission progress - Yields - ------- - mission_progress : MissionProgress - Mission progress - """ request = mission_raw_pb2.SubscribeMissionProgressRequest() @@ -1096,28 +972,25 @@ async def mission_progress(self): try: async for response in mission_progress_stream: - - - yield MissionProgress.translate_from_rpc(response.mission_progress) finally: mission_progress_stream.cancel() async def mission_changed(self): """ - Subscribes to mission changed. + Subscribes to mission changed. + + This notification can be used to be informed if a ground station has + been uploaded or changed by a ground station or companion computer. - This notification can be used to be informed if a ground station has - been uploaded or changed by a ground station or companion computer. + @param callback Callback to notify about change. - @param callback Callback to notify about change. + Yields + ------- + mission_changed : bool + Mission has changed - Yields - ------- - mission_changed : bool - Mission has changed - """ request = mission_raw_pb2.SubscribeMissionChangedRequest() @@ -1125,207 +998,195 @@ async def mission_changed(self): try: async for response in mission_changed_stream: - - - yield response.mission_changed finally: mission_changed_stream.cancel() async def import_qgroundcontrol_mission(self, qgc_plan_path): """ - Import a QGroundControl missions in JSON .plan format, from a file. - - Supported: - - Waypoints - - Survey - Not supported: - - Structure Scan - - Parameters - ---------- - qgc_plan_path : std::string - File path of the QGC plan - - Returns - ------- - mission_import_data : MissionImportData - The imported mission data - - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Import a QGroundControl missions in JSON .plan format, from a file. + + Supported: + - Waypoints + - Survey + Not supported: + - Structure Scan + + Parameters + ---------- + qgc_plan_path : std::string + File path of the QGC plan + + Returns + ------- + mission_import_data : MissionImportData + The imported mission data + + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.ImportQgroundcontrolMissionRequest() - - + request.qgc_plan_path = qgc_plan_path - + response = await self._stub.ImportQgroundcontrolMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: - raise MissionRawError(result, "import_qgroundcontrol_mission()", qgc_plan_path) - + raise MissionRawError( + result, "import_qgroundcontrol_mission()", qgc_plan_path + ) return MissionImportData.translate_from_rpc(response.mission_import_data) - async def import_qgroundcontrol_mission_from_string(self, qgc_plan): """ - Import a QGroundControl missions in JSON .plan format, from a string. - - Supported: - - Waypoints - - Survey - Not supported: - - Structure Scan - - Parameters - ---------- - qgc_plan : std::string - QGC plan as string - - Returns - ------- - mission_import_data : MissionImportData - The imported mission data - - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Import a QGroundControl missions in JSON .plan format, from a string. + + Supported: + - Waypoints + - Survey + Not supported: + - Structure Scan + + Parameters + ---------- + qgc_plan : std::string + QGC plan as string + + Returns + ------- + mission_import_data : MissionImportData + The imported mission data + + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.ImportQgroundcontrolMissionFromStringRequest() - - + request.qgc_plan = qgc_plan - + response = await self._stub.ImportQgroundcontrolMissionFromString(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: - raise MissionRawError(result, "import_qgroundcontrol_mission_from_string()", qgc_plan) - + raise MissionRawError( + result, "import_qgroundcontrol_mission_from_string()", qgc_plan + ) return MissionImportData.translate_from_rpc(response.mission_import_data) - async def import_mission_planner_mission(self, mission_planner_path): """ - Import a Mission Planner mission in QGC WPL 110 format, from a file. - - Supported: - - Waypoints - - ArduPilot home position handling - - Parameters - ---------- - mission_planner_path : std::string - File path of the Mission Planner mission file - - Returns - ------- - mission_import_data : MissionImportData - The imported mission data - - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Import a Mission Planner mission in QGC WPL 110 format, from a file. + + Supported: + - Waypoints + - ArduPilot home position handling + + Parameters + ---------- + mission_planner_path : std::string + File path of the Mission Planner mission file + + Returns + ------- + mission_import_data : MissionImportData + The imported mission data + + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.ImportMissionPlannerMissionRequest() - - + request.mission_planner_path = mission_planner_path - + response = await self._stub.ImportMissionPlannerMission(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: - raise MissionRawError(result, "import_mission_planner_mission()", mission_planner_path) - + raise MissionRawError( + result, "import_mission_planner_mission()", mission_planner_path + ) return MissionImportData.translate_from_rpc(response.mission_import_data) - async def import_mission_planner_mission_from_string(self, mission_planner_mission): """ - Import a Mission Planner mission in QGC WPL 110 format, from a string. - - Supported: - - Waypoints - - ArduPilot home position handling - - Parameters - ---------- - mission_planner_mission : std::string - Mission Planner mission as string - - Returns - ------- - mission_import_data : MissionImportData - The imported mission data - - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Import a Mission Planner mission in QGC WPL 110 format, from a string. + + Supported: + - Waypoints + - ArduPilot home position handling + + Parameters + ---------- + mission_planner_mission : std::string + Mission Planner mission as string + + Returns + ------- + mission_import_data : MissionImportData + The imported mission data + + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.ImportMissionPlannerMissionFromStringRequest() - - + request.mission_planner_mission = mission_planner_mission - + response = await self._stub.ImportMissionPlannerMissionFromString(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: - raise MissionRawError(result, "import_mission_planner_mission_from_string()", mission_planner_mission) - + raise MissionRawError( + result, + "import_mission_planner_mission_from_string()", + mission_planner_mission, + ) return MissionImportData.translate_from_rpc(response.mission_import_data) - async def is_mission_finished(self): """ - Check if the mission is finished. + Check if the mission is finished. - Returns true if the mission is finished, false otherwise. + Returns true if the mission is finished, false otherwise. - Returns - ------- - is_finished : bool - True if the mission is finished, false otherwise + Returns + ------- + is_finished : bool + True if the mission is finished, false otherwise - Raises - ------ - MissionRawError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_pb2.IsMissionFinishedRequest() response = await self._stub.IsMissionFinished(request) - result = self._extract_result(response) if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "is_mission_finished()") - return response.is_finished - \ No newline at end of file diff --git a/mavsdk/mission_raw_pb2.py b/mavsdk/mission_raw_pb2.py index d3364d4e..eb8ad3ad 100644 --- a/mavsdk/mission_raw_pb2.py +++ b/mavsdk/mission_raw_pb2.py @@ -4,18 +4,15 @@ # source: mission_raw/mission_raw.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'mission_raw/mission_raw.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "mission_raw/mission_raw.proto" ) # @@protoc_insertion_point(imports) @@ -25,116 +22,154 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x1dmission_raw/mission_raw.proto\x12\x16mavsdk.rpc.mission_raw\x1a\x14mavsdk_options.proto\"R\n\x14UploadMissionRequest\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"]\n\x15UploadMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"S\n\x15UploadGeofenceRequest\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"^\n\x16UploadGeofenceResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"V\n\x18UploadRallyPointsRequest\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"a\n\x19UploadRallyPointsResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"\x1c\n\x1a\x43\x61ncelMissionUploadRequest\"c\n\x1b\x43\x61ncelMissionUploadResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"\x18\n\x16\x44ownloadMissionRequest\"\x9b\x01\n\x17\x44ownloadMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12:\n\rmission_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"\x19\n\x17\x44ownloadGeofenceRequest\"\x9d\x01\n\x18\x44ownloadGeofenceResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12;\n\x0egeofence_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"\x1c\n\x1a\x44ownloadRallypointsRequest\"\xa2\x01\n\x1b\x44ownloadRallypointsResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12=\n\x10rallypoint_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"\x1e\n\x1c\x43\x61ncelMissionDownloadRequest\"e\n\x1d\x43\x61ncelMissionDownloadResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"\x15\n\x13StartMissionRequest\"\\\n\x14StartMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"\x15\n\x13PauseMissionRequest\"\\\n\x14PauseMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"\x15\n\x13\x43learMissionRequest\"\\\n\x14\x43learMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"-\n\x1cSetCurrentMissionItemRequest\x12\r\n\x05index\x18\x01 \x01(\x05\"e\n\x1dSetCurrentMissionItemResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\"!\n\x1fSubscribeMissionProgressRequest\"\\\n\x17MissionProgressResponse\x12\x41\n\x10mission_progress\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.mission_raw.MissionProgress\" \n\x1eSubscribeMissionChangedRequest\"1\n\x16MissionChangedResponse\x12\x17\n\x0fmission_changed\x18\x01 \x01(\x08\";\n\"ImportQgroundcontrolMissionRequest\x12\x15\n\rqgc_plan_path\x18\x01 \x01(\t\"\xb3\x01\n#ImportQgroundcontrolMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData\"@\n,ImportQgroundcontrolMissionFromStringRequest\x12\x10\n\x08qgc_plan\x18\x01 \x01(\t\"\xbd\x01\n-ImportQgroundcontrolMissionFromStringResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData\"B\n\"ImportMissionPlannerMissionRequest\x12\x1c\n\x14mission_planner_path\x18\x01 \x01(\t\"\xb3\x01\n#ImportMissionPlannerMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData\"O\n,ImportMissionPlannerMissionFromStringRequest\x12\x1f\n\x17mission_planner_mission\x18\x01 \x01(\t\"\xbd\x01\n-ImportMissionPlannerMissionFromStringResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData\"\x1a\n\x18IsMissionFinishedRequest\"v\n\x19IsMissionFinishedResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x13\n\x0bis_finished\x18\x02 \x01(\x08\"1\n\x0fMissionProgress\x12\x0f\n\x07\x63urrent\x18\x01 \x01(\x05\x12\r\n\x05total\x18\x02 \x01(\x05\"\xd8\x01\n\x0bMissionItem\x12\x0b\n\x03seq\x18\x01 \x01(\r\x12\r\n\x05\x66rame\x18\x02 \x01(\r\x12\x0f\n\x07\x63ommand\x18\x03 \x01(\r\x12\x0f\n\x07\x63urrent\x18\x04 \x01(\r\x12\x14\n\x0c\x61utocontinue\x18\x05 \x01(\r\x12\x0e\n\x06param1\x18\x06 \x01(\x02\x12\x0e\n\x06param2\x18\x07 \x01(\x02\x12\x0e\n\x06param3\x18\x08 \x01(\x02\x12\x0e\n\x06param4\x18\t \x01(\x02\x12\t\n\x01x\x18\n \x01(\x05\x12\t\n\x01y\x18\x0b \x01(\x05\x12\t\n\x01z\x18\x0c \x01(\x02\x12\x14\n\x0cmission_type\x18\r \x01(\r\"\xc6\x01\n\x11MissionImportData\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\x12;\n\x0egeofence_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\x12\x38\n\x0brally_items\x18\x03 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\"\xdf\x05\n\x10MissionRawResult\x12?\n\x06result\x18\x01 \x01(\x0e\x32/.mavsdk.rpc.mission_raw.MissionRawResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xf5\x04\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\x1dRESULT_TOO_MANY_MISSION_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\x16\n\x12RESULT_UNSUPPORTED\x10\x07\x12\x1f\n\x1bRESULT_NO_MISSION_AVAILABLE\x10\x08\x12\x1d\n\x19RESULT_TRANSFER_CANCELLED\x10\t\x12\"\n\x1eRESULT_FAILED_TO_OPEN_QGC_PLAN\x10\n\x12#\n\x1fRESULT_FAILED_TO_PARSE_QGC_PLAN\x10\x0b\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x0c\x12\x11\n\rRESULT_DENIED\x10\r\x12&\n\"RESULT_MISSION_TYPE_NOT_CONSISTENT\x10\x0e\x12\x1b\n\x17RESULT_INVALID_SEQUENCE\x10\x0f\x12\x1a\n\x16RESULT_CURRENT_INVALID\x10\x10\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x11\x12%\n!RESULT_INT_MESSAGES_NOT_SUPPORTED\x10\x12\x12.\n*RESULT_FAILED_TO_OPEN_MISSION_PLANNER_PLAN\x10\x13\x12/\n+RESULT_FAILED_TO_PARSE_MISSION_PLANNER_PLAN\x10\x14\x32\x97\x14\n\x11MissionRawService\x12n\n\rUploadMission\x12,.mavsdk.rpc.mission_raw.UploadMissionRequest\x1a-.mavsdk.rpc.mission_raw.UploadMissionResponse\"\x00\x12q\n\x0eUploadGeofence\x12-.mavsdk.rpc.mission_raw.UploadGeofenceRequest\x1a..mavsdk.rpc.mission_raw.UploadGeofenceResponse\"\x00\x12z\n\x11UploadRallyPoints\x12\x30.mavsdk.rpc.mission_raw.UploadRallyPointsRequest\x1a\x31.mavsdk.rpc.mission_raw.UploadRallyPointsResponse\"\x00\x12\x84\x01\n\x13\x43\x61ncelMissionUpload\x12\x32.mavsdk.rpc.mission_raw.CancelMissionUploadRequest\x1a\x33.mavsdk.rpc.mission_raw.CancelMissionUploadResponse\"\x04\x80\xb5\x18\x01\x12t\n\x0f\x44ownloadMission\x12..mavsdk.rpc.mission_raw.DownloadMissionRequest\x1a/.mavsdk.rpc.mission_raw.DownloadMissionResponse\"\x00\x12w\n\x10\x44ownloadGeofence\x12/.mavsdk.rpc.mission_raw.DownloadGeofenceRequest\x1a\x30.mavsdk.rpc.mission_raw.DownloadGeofenceResponse\"\x00\x12\x80\x01\n\x13\x44ownloadRallypoints\x12\x32.mavsdk.rpc.mission_raw.DownloadRallypointsRequest\x1a\x33.mavsdk.rpc.mission_raw.DownloadRallypointsResponse\"\x00\x12\x8a\x01\n\x15\x43\x61ncelMissionDownload\x12\x34.mavsdk.rpc.mission_raw.CancelMissionDownloadRequest\x1a\x35.mavsdk.rpc.mission_raw.CancelMissionDownloadResponse\"\x04\x80\xb5\x18\x01\x12k\n\x0cStartMission\x12+.mavsdk.rpc.mission_raw.StartMissionRequest\x1a,.mavsdk.rpc.mission_raw.StartMissionResponse\"\x00\x12k\n\x0cPauseMission\x12+.mavsdk.rpc.mission_raw.PauseMissionRequest\x1a,.mavsdk.rpc.mission_raw.PauseMissionResponse\"\x00\x12k\n\x0c\x43learMission\x12+.mavsdk.rpc.mission_raw.ClearMissionRequest\x1a,.mavsdk.rpc.mission_raw.ClearMissionResponse\"\x00\x12\x86\x01\n\x15SetCurrentMissionItem\x12\x34.mavsdk.rpc.mission_raw.SetCurrentMissionItemRequest\x1a\x35.mavsdk.rpc.mission_raw.SetCurrentMissionItemResponse\"\x00\x12\x88\x01\n\x18SubscribeMissionProgress\x12\x37.mavsdk.rpc.mission_raw.SubscribeMissionProgressRequest\x1a/.mavsdk.rpc.mission_raw.MissionProgressResponse\"\x00\x30\x01\x12\x89\x01\n\x17SubscribeMissionChanged\x12\x36.mavsdk.rpc.mission_raw.SubscribeMissionChangedRequest\x1a..mavsdk.rpc.mission_raw.MissionChangedResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9c\x01\n\x1bImportQgroundcontrolMission\x12:.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionRequest\x1a;.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionResponse\"\x04\x80\xb5\x18\x01\x12\xba\x01\n%ImportQgroundcontrolMissionFromString\x12\x44.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionFromStringRequest\x1a\x45.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionFromStringResponse\"\x04\x80\xb5\x18\x01\x12\x9c\x01\n\x1bImportMissionPlannerMission\x12:.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionRequest\x1a;.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionResponse\"\x04\x80\xb5\x18\x01\x12\xba\x01\n%ImportMissionPlannerMissionFromString\x12\x44.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionFromStringRequest\x1a\x45.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionFromStringResponse\"\x04\x80\xb5\x18\x01\x12~\n\x11IsMissionFinished\x12\x30.mavsdk.rpc.mission_raw.IsMissionFinishedRequest\x1a\x31.mavsdk.rpc.mission_raw.IsMissionFinishedResponse\"\x04\x80\xb5\x18\x01\x42(\n\x15io.mavsdk.mission_rawB\x0fMissionRawProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x1dmission_raw/mission_raw.proto\x12\x16mavsdk.rpc.mission_raw\x1a\x14mavsdk_options.proto"R\n\x14UploadMissionRequest\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"]\n\x15UploadMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"S\n\x15UploadGeofenceRequest\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"^\n\x16UploadGeofenceResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"V\n\x18UploadRallyPointsRequest\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"a\n\x19UploadRallyPointsResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"\x1c\n\x1a\x43\x61ncelMissionUploadRequest"c\n\x1b\x43\x61ncelMissionUploadResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"\x18\n\x16\x44ownloadMissionRequest"\x9b\x01\n\x17\x44ownloadMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12:\n\rmission_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"\x19\n\x17\x44ownloadGeofenceRequest"\x9d\x01\n\x18\x44ownloadGeofenceResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12;\n\x0egeofence_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"\x1c\n\x1a\x44ownloadRallypointsRequest"\xa2\x01\n\x1b\x44ownloadRallypointsResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12=\n\x10rallypoint_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"\x1e\n\x1c\x43\x61ncelMissionDownloadRequest"e\n\x1d\x43\x61ncelMissionDownloadResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"\x15\n\x13StartMissionRequest"\\\n\x14StartMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"\x15\n\x13PauseMissionRequest"\\\n\x14PauseMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"\x15\n\x13\x43learMissionRequest"\\\n\x14\x43learMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"-\n\x1cSetCurrentMissionItemRequest\x12\r\n\x05index\x18\x01 \x01(\x05"e\n\x1dSetCurrentMissionItemResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult"!\n\x1fSubscribeMissionProgressRequest"\\\n\x17MissionProgressResponse\x12\x41\n\x10mission_progress\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.mission_raw.MissionProgress" \n\x1eSubscribeMissionChangedRequest"1\n\x16MissionChangedResponse\x12\x17\n\x0fmission_changed\x18\x01 \x01(\x08";\n"ImportQgroundcontrolMissionRequest\x12\x15\n\rqgc_plan_path\x18\x01 \x01(\t"\xb3\x01\n#ImportQgroundcontrolMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData"@\n,ImportQgroundcontrolMissionFromStringRequest\x12\x10\n\x08qgc_plan\x18\x01 \x01(\t"\xbd\x01\n-ImportQgroundcontrolMissionFromStringResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData"B\n"ImportMissionPlannerMissionRequest\x12\x1c\n\x14mission_planner_path\x18\x01 \x01(\t"\xb3\x01\n#ImportMissionPlannerMissionResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData"O\n,ImportMissionPlannerMissionFromStringRequest\x12\x1f\n\x17mission_planner_mission\x18\x01 \x01(\t"\xbd\x01\n-ImportMissionPlannerMissionFromStringResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x46\n\x13mission_import_data\x18\x02 \x01(\x0b\x32).mavsdk.rpc.mission_raw.MissionImportData"\x1a\n\x18IsMissionFinishedRequest"v\n\x19IsMissionFinishedResponse\x12\x44\n\x12mission_raw_result\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mission_raw.MissionRawResult\x12\x13\n\x0bis_finished\x18\x02 \x01(\x08"1\n\x0fMissionProgress\x12\x0f\n\x07\x63urrent\x18\x01 \x01(\x05\x12\r\n\x05total\x18\x02 \x01(\x05"\xd8\x01\n\x0bMissionItem\x12\x0b\n\x03seq\x18\x01 \x01(\r\x12\r\n\x05\x66rame\x18\x02 \x01(\r\x12\x0f\n\x07\x63ommand\x18\x03 \x01(\r\x12\x0f\n\x07\x63urrent\x18\x04 \x01(\r\x12\x14\n\x0c\x61utocontinue\x18\x05 \x01(\r\x12\x0e\n\x06param1\x18\x06 \x01(\x02\x12\x0e\n\x06param2\x18\x07 \x01(\x02\x12\x0e\n\x06param3\x18\x08 \x01(\x02\x12\x0e\n\x06param4\x18\t \x01(\x02\x12\t\n\x01x\x18\n \x01(\x05\x12\t\n\x01y\x18\x0b \x01(\x05\x12\t\n\x01z\x18\x0c \x01(\x02\x12\x14\n\x0cmission_type\x18\r \x01(\r"\xc6\x01\n\x11MissionImportData\x12:\n\rmission_items\x18\x01 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\x12;\n\x0egeofence_items\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem\x12\x38\n\x0brally_items\x18\x03 \x03(\x0b\x32#.mavsdk.rpc.mission_raw.MissionItem"\xdf\x05\n\x10MissionRawResult\x12?\n\x06result\x18\x01 \x01(\x0e\x32/.mavsdk.rpc.mission_raw.MissionRawResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xf5\x04\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\x1dRESULT_TOO_MANY_MISSION_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\x16\n\x12RESULT_UNSUPPORTED\x10\x07\x12\x1f\n\x1bRESULT_NO_MISSION_AVAILABLE\x10\x08\x12\x1d\n\x19RESULT_TRANSFER_CANCELLED\x10\t\x12"\n\x1eRESULT_FAILED_TO_OPEN_QGC_PLAN\x10\n\x12#\n\x1fRESULT_FAILED_TO_PARSE_QGC_PLAN\x10\x0b\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x0c\x12\x11\n\rRESULT_DENIED\x10\r\x12&\n"RESULT_MISSION_TYPE_NOT_CONSISTENT\x10\x0e\x12\x1b\n\x17RESULT_INVALID_SEQUENCE\x10\x0f\x12\x1a\n\x16RESULT_CURRENT_INVALID\x10\x10\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x11\x12%\n!RESULT_INT_MESSAGES_NOT_SUPPORTED\x10\x12\x12.\n*RESULT_FAILED_TO_OPEN_MISSION_PLANNER_PLAN\x10\x13\x12/\n+RESULT_FAILED_TO_PARSE_MISSION_PLANNER_PLAN\x10\x14\x32\x97\x14\n\x11MissionRawService\x12n\n\rUploadMission\x12,.mavsdk.rpc.mission_raw.UploadMissionRequest\x1a-.mavsdk.rpc.mission_raw.UploadMissionResponse"\x00\x12q\n\x0eUploadGeofence\x12-.mavsdk.rpc.mission_raw.UploadGeofenceRequest\x1a..mavsdk.rpc.mission_raw.UploadGeofenceResponse"\x00\x12z\n\x11UploadRallyPoints\x12\x30.mavsdk.rpc.mission_raw.UploadRallyPointsRequest\x1a\x31.mavsdk.rpc.mission_raw.UploadRallyPointsResponse"\x00\x12\x84\x01\n\x13\x43\x61ncelMissionUpload\x12\x32.mavsdk.rpc.mission_raw.CancelMissionUploadRequest\x1a\x33.mavsdk.rpc.mission_raw.CancelMissionUploadResponse"\x04\x80\xb5\x18\x01\x12t\n\x0f\x44ownloadMission\x12..mavsdk.rpc.mission_raw.DownloadMissionRequest\x1a/.mavsdk.rpc.mission_raw.DownloadMissionResponse"\x00\x12w\n\x10\x44ownloadGeofence\x12/.mavsdk.rpc.mission_raw.DownloadGeofenceRequest\x1a\x30.mavsdk.rpc.mission_raw.DownloadGeofenceResponse"\x00\x12\x80\x01\n\x13\x44ownloadRallypoints\x12\x32.mavsdk.rpc.mission_raw.DownloadRallypointsRequest\x1a\x33.mavsdk.rpc.mission_raw.DownloadRallypointsResponse"\x00\x12\x8a\x01\n\x15\x43\x61ncelMissionDownload\x12\x34.mavsdk.rpc.mission_raw.CancelMissionDownloadRequest\x1a\x35.mavsdk.rpc.mission_raw.CancelMissionDownloadResponse"\x04\x80\xb5\x18\x01\x12k\n\x0cStartMission\x12+.mavsdk.rpc.mission_raw.StartMissionRequest\x1a,.mavsdk.rpc.mission_raw.StartMissionResponse"\x00\x12k\n\x0cPauseMission\x12+.mavsdk.rpc.mission_raw.PauseMissionRequest\x1a,.mavsdk.rpc.mission_raw.PauseMissionResponse"\x00\x12k\n\x0c\x43learMission\x12+.mavsdk.rpc.mission_raw.ClearMissionRequest\x1a,.mavsdk.rpc.mission_raw.ClearMissionResponse"\x00\x12\x86\x01\n\x15SetCurrentMissionItem\x12\x34.mavsdk.rpc.mission_raw.SetCurrentMissionItemRequest\x1a\x35.mavsdk.rpc.mission_raw.SetCurrentMissionItemResponse"\x00\x12\x88\x01\n\x18SubscribeMissionProgress\x12\x37.mavsdk.rpc.mission_raw.SubscribeMissionProgressRequest\x1a/.mavsdk.rpc.mission_raw.MissionProgressResponse"\x00\x30\x01\x12\x89\x01\n\x17SubscribeMissionChanged\x12\x36.mavsdk.rpc.mission_raw.SubscribeMissionChangedRequest\x1a..mavsdk.rpc.mission_raw.MissionChangedResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9c\x01\n\x1bImportQgroundcontrolMission\x12:.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionRequest\x1a;.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionResponse"\x04\x80\xb5\x18\x01\x12\xba\x01\n%ImportQgroundcontrolMissionFromString\x12\x44.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionFromStringRequest\x1a\x45.mavsdk.rpc.mission_raw.ImportQgroundcontrolMissionFromStringResponse"\x04\x80\xb5\x18\x01\x12\x9c\x01\n\x1bImportMissionPlannerMission\x12:.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionRequest\x1a;.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionResponse"\x04\x80\xb5\x18\x01\x12\xba\x01\n%ImportMissionPlannerMissionFromString\x12\x44.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionFromStringRequest\x1a\x45.mavsdk.rpc.mission_raw.ImportMissionPlannerMissionFromStringResponse"\x04\x80\xb5\x18\x01\x12~\n\x11IsMissionFinished\x12\x30.mavsdk.rpc.mission_raw.IsMissionFinishedRequest\x1a\x31.mavsdk.rpc.mission_raw.IsMissionFinishedResponse"\x04\x80\xb5\x18\x01\x42(\n\x15io.mavsdk.mission_rawB\x0fMissionRawProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mission_raw.mission_raw_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "mission_raw.mission_raw_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\025io.mavsdk.mission_rawB\017MissionRawProto' - _globals['_MISSIONRAWSERVICE'].methods_by_name['CancelMissionUpload']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['CancelMissionUpload']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVICE'].methods_by_name['CancelMissionDownload']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['CancelMissionDownload']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVICE'].methods_by_name['SubscribeMissionChanged']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['SubscribeMissionChanged']._serialized_options = b'\200\265\030\000' - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportQgroundcontrolMission']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportQgroundcontrolMission']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportQgroundcontrolMissionFromString']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportQgroundcontrolMissionFromString']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportMissionPlannerMission']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportMissionPlannerMission']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportMissionPlannerMissionFromString']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['ImportMissionPlannerMissionFromString']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVICE'].methods_by_name['IsMissionFinished']._loaded_options = None - _globals['_MISSIONRAWSERVICE'].methods_by_name['IsMissionFinished']._serialized_options = b'\200\265\030\001' - _globals['_UPLOADMISSIONREQUEST']._serialized_start=79 - _globals['_UPLOADMISSIONREQUEST']._serialized_end=161 - _globals['_UPLOADMISSIONRESPONSE']._serialized_start=163 - _globals['_UPLOADMISSIONRESPONSE']._serialized_end=256 - _globals['_UPLOADGEOFENCEREQUEST']._serialized_start=258 - _globals['_UPLOADGEOFENCEREQUEST']._serialized_end=341 - _globals['_UPLOADGEOFENCERESPONSE']._serialized_start=343 - _globals['_UPLOADGEOFENCERESPONSE']._serialized_end=437 - _globals['_UPLOADRALLYPOINTSREQUEST']._serialized_start=439 - _globals['_UPLOADRALLYPOINTSREQUEST']._serialized_end=525 - _globals['_UPLOADRALLYPOINTSRESPONSE']._serialized_start=527 - _globals['_UPLOADRALLYPOINTSRESPONSE']._serialized_end=624 - _globals['_CANCELMISSIONUPLOADREQUEST']._serialized_start=626 - _globals['_CANCELMISSIONUPLOADREQUEST']._serialized_end=654 - _globals['_CANCELMISSIONUPLOADRESPONSE']._serialized_start=656 - _globals['_CANCELMISSIONUPLOADRESPONSE']._serialized_end=755 - _globals['_DOWNLOADMISSIONREQUEST']._serialized_start=757 - _globals['_DOWNLOADMISSIONREQUEST']._serialized_end=781 - _globals['_DOWNLOADMISSIONRESPONSE']._serialized_start=784 - _globals['_DOWNLOADMISSIONRESPONSE']._serialized_end=939 - _globals['_DOWNLOADGEOFENCEREQUEST']._serialized_start=941 - _globals['_DOWNLOADGEOFENCEREQUEST']._serialized_end=966 - _globals['_DOWNLOADGEOFENCERESPONSE']._serialized_start=969 - _globals['_DOWNLOADGEOFENCERESPONSE']._serialized_end=1126 - _globals['_DOWNLOADRALLYPOINTSREQUEST']._serialized_start=1128 - _globals['_DOWNLOADRALLYPOINTSREQUEST']._serialized_end=1156 - _globals['_DOWNLOADRALLYPOINTSRESPONSE']._serialized_start=1159 - _globals['_DOWNLOADRALLYPOINTSRESPONSE']._serialized_end=1321 - _globals['_CANCELMISSIONDOWNLOADREQUEST']._serialized_start=1323 - _globals['_CANCELMISSIONDOWNLOADREQUEST']._serialized_end=1353 - _globals['_CANCELMISSIONDOWNLOADRESPONSE']._serialized_start=1355 - _globals['_CANCELMISSIONDOWNLOADRESPONSE']._serialized_end=1456 - _globals['_STARTMISSIONREQUEST']._serialized_start=1458 - _globals['_STARTMISSIONREQUEST']._serialized_end=1479 - _globals['_STARTMISSIONRESPONSE']._serialized_start=1481 - _globals['_STARTMISSIONRESPONSE']._serialized_end=1573 - _globals['_PAUSEMISSIONREQUEST']._serialized_start=1575 - _globals['_PAUSEMISSIONREQUEST']._serialized_end=1596 - _globals['_PAUSEMISSIONRESPONSE']._serialized_start=1598 - _globals['_PAUSEMISSIONRESPONSE']._serialized_end=1690 - _globals['_CLEARMISSIONREQUEST']._serialized_start=1692 - _globals['_CLEARMISSIONREQUEST']._serialized_end=1713 - _globals['_CLEARMISSIONRESPONSE']._serialized_start=1715 - _globals['_CLEARMISSIONRESPONSE']._serialized_end=1807 - _globals['_SETCURRENTMISSIONITEMREQUEST']._serialized_start=1809 - _globals['_SETCURRENTMISSIONITEMREQUEST']._serialized_end=1854 - _globals['_SETCURRENTMISSIONITEMRESPONSE']._serialized_start=1856 - _globals['_SETCURRENTMISSIONITEMRESPONSE']._serialized_end=1957 - _globals['_SUBSCRIBEMISSIONPROGRESSREQUEST']._serialized_start=1959 - _globals['_SUBSCRIBEMISSIONPROGRESSREQUEST']._serialized_end=1992 - _globals['_MISSIONPROGRESSRESPONSE']._serialized_start=1994 - _globals['_MISSIONPROGRESSRESPONSE']._serialized_end=2086 - _globals['_SUBSCRIBEMISSIONCHANGEDREQUEST']._serialized_start=2088 - _globals['_SUBSCRIBEMISSIONCHANGEDREQUEST']._serialized_end=2120 - _globals['_MISSIONCHANGEDRESPONSE']._serialized_start=2122 - _globals['_MISSIONCHANGEDRESPONSE']._serialized_end=2171 - _globals['_IMPORTQGROUNDCONTROLMISSIONREQUEST']._serialized_start=2173 - _globals['_IMPORTQGROUNDCONTROLMISSIONREQUEST']._serialized_end=2232 - _globals['_IMPORTQGROUNDCONTROLMISSIONRESPONSE']._serialized_start=2235 - _globals['_IMPORTQGROUNDCONTROLMISSIONRESPONSE']._serialized_end=2414 - _globals['_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGREQUEST']._serialized_start=2416 - _globals['_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGREQUEST']._serialized_end=2480 - _globals['_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGRESPONSE']._serialized_start=2483 - _globals['_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGRESPONSE']._serialized_end=2672 - _globals['_IMPORTMISSIONPLANNERMISSIONREQUEST']._serialized_start=2674 - _globals['_IMPORTMISSIONPLANNERMISSIONREQUEST']._serialized_end=2740 - _globals['_IMPORTMISSIONPLANNERMISSIONRESPONSE']._serialized_start=2743 - _globals['_IMPORTMISSIONPLANNERMISSIONRESPONSE']._serialized_end=2922 - _globals['_IMPORTMISSIONPLANNERMISSIONFROMSTRINGREQUEST']._serialized_start=2924 - _globals['_IMPORTMISSIONPLANNERMISSIONFROMSTRINGREQUEST']._serialized_end=3003 - _globals['_IMPORTMISSIONPLANNERMISSIONFROMSTRINGRESPONSE']._serialized_start=3006 - _globals['_IMPORTMISSIONPLANNERMISSIONFROMSTRINGRESPONSE']._serialized_end=3195 - _globals['_ISMISSIONFINISHEDREQUEST']._serialized_start=3197 - _globals['_ISMISSIONFINISHEDREQUEST']._serialized_end=3223 - _globals['_ISMISSIONFINISHEDRESPONSE']._serialized_start=3225 - _globals['_ISMISSIONFINISHEDRESPONSE']._serialized_end=3343 - _globals['_MISSIONPROGRESS']._serialized_start=3345 - _globals['_MISSIONPROGRESS']._serialized_end=3394 - _globals['_MISSIONITEM']._serialized_start=3397 - _globals['_MISSIONITEM']._serialized_end=3613 - _globals['_MISSIONIMPORTDATA']._serialized_start=3616 - _globals['_MISSIONIMPORTDATA']._serialized_end=3814 - _globals['_MISSIONRAWRESULT']._serialized_start=3817 - _globals['_MISSIONRAWRESULT']._serialized_end=4552 - _globals['_MISSIONRAWRESULT_RESULT']._serialized_start=3923 - _globals['_MISSIONRAWRESULT_RESULT']._serialized_end=4552 - _globals['_MISSIONRAWSERVICE']._serialized_start=4555 - _globals['_MISSIONRAWSERVICE']._serialized_end=7138 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\025io.mavsdk.mission_rawB\017MissionRawProto" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "CancelMissionUpload" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "CancelMissionUpload" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "CancelMissionDownload" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "CancelMissionDownload" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "SubscribeMissionChanged" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "SubscribeMissionChanged" + ]._serialized_options = b"\200\265\030\000" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportQgroundcontrolMission" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportQgroundcontrolMission" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportQgroundcontrolMissionFromString" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportQgroundcontrolMissionFromString" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportMissionPlannerMission" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportMissionPlannerMission" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportMissionPlannerMissionFromString" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "ImportMissionPlannerMissionFromString" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "IsMissionFinished" + ]._loaded_options = None + _globals["_MISSIONRAWSERVICE"].methods_by_name[ + "IsMissionFinished" + ]._serialized_options = b"\200\265\030\001" + _globals["_UPLOADMISSIONREQUEST"]._serialized_start = 79 + _globals["_UPLOADMISSIONREQUEST"]._serialized_end = 161 + _globals["_UPLOADMISSIONRESPONSE"]._serialized_start = 163 + _globals["_UPLOADMISSIONRESPONSE"]._serialized_end = 256 + _globals["_UPLOADGEOFENCEREQUEST"]._serialized_start = 258 + _globals["_UPLOADGEOFENCEREQUEST"]._serialized_end = 341 + _globals["_UPLOADGEOFENCERESPONSE"]._serialized_start = 343 + _globals["_UPLOADGEOFENCERESPONSE"]._serialized_end = 437 + _globals["_UPLOADRALLYPOINTSREQUEST"]._serialized_start = 439 + _globals["_UPLOADRALLYPOINTSREQUEST"]._serialized_end = 525 + _globals["_UPLOADRALLYPOINTSRESPONSE"]._serialized_start = 527 + _globals["_UPLOADRALLYPOINTSRESPONSE"]._serialized_end = 624 + _globals["_CANCELMISSIONUPLOADREQUEST"]._serialized_start = 626 + _globals["_CANCELMISSIONUPLOADREQUEST"]._serialized_end = 654 + _globals["_CANCELMISSIONUPLOADRESPONSE"]._serialized_start = 656 + _globals["_CANCELMISSIONUPLOADRESPONSE"]._serialized_end = 755 + _globals["_DOWNLOADMISSIONREQUEST"]._serialized_start = 757 + _globals["_DOWNLOADMISSIONREQUEST"]._serialized_end = 781 + _globals["_DOWNLOADMISSIONRESPONSE"]._serialized_start = 784 + _globals["_DOWNLOADMISSIONRESPONSE"]._serialized_end = 939 + _globals["_DOWNLOADGEOFENCEREQUEST"]._serialized_start = 941 + _globals["_DOWNLOADGEOFENCEREQUEST"]._serialized_end = 966 + _globals["_DOWNLOADGEOFENCERESPONSE"]._serialized_start = 969 + _globals["_DOWNLOADGEOFENCERESPONSE"]._serialized_end = 1126 + _globals["_DOWNLOADRALLYPOINTSREQUEST"]._serialized_start = 1128 + _globals["_DOWNLOADRALLYPOINTSREQUEST"]._serialized_end = 1156 + _globals["_DOWNLOADRALLYPOINTSRESPONSE"]._serialized_start = 1159 + _globals["_DOWNLOADRALLYPOINTSRESPONSE"]._serialized_end = 1321 + _globals["_CANCELMISSIONDOWNLOADREQUEST"]._serialized_start = 1323 + _globals["_CANCELMISSIONDOWNLOADREQUEST"]._serialized_end = 1353 + _globals["_CANCELMISSIONDOWNLOADRESPONSE"]._serialized_start = 1355 + _globals["_CANCELMISSIONDOWNLOADRESPONSE"]._serialized_end = 1456 + _globals["_STARTMISSIONREQUEST"]._serialized_start = 1458 + _globals["_STARTMISSIONREQUEST"]._serialized_end = 1479 + _globals["_STARTMISSIONRESPONSE"]._serialized_start = 1481 + _globals["_STARTMISSIONRESPONSE"]._serialized_end = 1573 + _globals["_PAUSEMISSIONREQUEST"]._serialized_start = 1575 + _globals["_PAUSEMISSIONREQUEST"]._serialized_end = 1596 + _globals["_PAUSEMISSIONRESPONSE"]._serialized_start = 1598 + _globals["_PAUSEMISSIONRESPONSE"]._serialized_end = 1690 + _globals["_CLEARMISSIONREQUEST"]._serialized_start = 1692 + _globals["_CLEARMISSIONREQUEST"]._serialized_end = 1713 + _globals["_CLEARMISSIONRESPONSE"]._serialized_start = 1715 + _globals["_CLEARMISSIONRESPONSE"]._serialized_end = 1807 + _globals["_SETCURRENTMISSIONITEMREQUEST"]._serialized_start = 1809 + _globals["_SETCURRENTMISSIONITEMREQUEST"]._serialized_end = 1854 + _globals["_SETCURRENTMISSIONITEMRESPONSE"]._serialized_start = 1856 + _globals["_SETCURRENTMISSIONITEMRESPONSE"]._serialized_end = 1957 + _globals["_SUBSCRIBEMISSIONPROGRESSREQUEST"]._serialized_start = 1959 + _globals["_SUBSCRIBEMISSIONPROGRESSREQUEST"]._serialized_end = 1992 + _globals["_MISSIONPROGRESSRESPONSE"]._serialized_start = 1994 + _globals["_MISSIONPROGRESSRESPONSE"]._serialized_end = 2086 + _globals["_SUBSCRIBEMISSIONCHANGEDREQUEST"]._serialized_start = 2088 + _globals["_SUBSCRIBEMISSIONCHANGEDREQUEST"]._serialized_end = 2120 + _globals["_MISSIONCHANGEDRESPONSE"]._serialized_start = 2122 + _globals["_MISSIONCHANGEDRESPONSE"]._serialized_end = 2171 + _globals["_IMPORTQGROUNDCONTROLMISSIONREQUEST"]._serialized_start = 2173 + _globals["_IMPORTQGROUNDCONTROLMISSIONREQUEST"]._serialized_end = 2232 + _globals["_IMPORTQGROUNDCONTROLMISSIONRESPONSE"]._serialized_start = 2235 + _globals["_IMPORTQGROUNDCONTROLMISSIONRESPONSE"]._serialized_end = 2414 + _globals["_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGREQUEST"]._serialized_start = 2416 + _globals["_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGREQUEST"]._serialized_end = 2480 + _globals["_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGRESPONSE"]._serialized_start = 2483 + _globals["_IMPORTQGROUNDCONTROLMISSIONFROMSTRINGRESPONSE"]._serialized_end = 2672 + _globals["_IMPORTMISSIONPLANNERMISSIONREQUEST"]._serialized_start = 2674 + _globals["_IMPORTMISSIONPLANNERMISSIONREQUEST"]._serialized_end = 2740 + _globals["_IMPORTMISSIONPLANNERMISSIONRESPONSE"]._serialized_start = 2743 + _globals["_IMPORTMISSIONPLANNERMISSIONRESPONSE"]._serialized_end = 2922 + _globals["_IMPORTMISSIONPLANNERMISSIONFROMSTRINGREQUEST"]._serialized_start = 2924 + _globals["_IMPORTMISSIONPLANNERMISSIONFROMSTRINGREQUEST"]._serialized_end = 3003 + _globals["_IMPORTMISSIONPLANNERMISSIONFROMSTRINGRESPONSE"]._serialized_start = 3006 + _globals["_IMPORTMISSIONPLANNERMISSIONFROMSTRINGRESPONSE"]._serialized_end = 3195 + _globals["_ISMISSIONFINISHEDREQUEST"]._serialized_start = 3197 + _globals["_ISMISSIONFINISHEDREQUEST"]._serialized_end = 3223 + _globals["_ISMISSIONFINISHEDRESPONSE"]._serialized_start = 3225 + _globals["_ISMISSIONFINISHEDRESPONSE"]._serialized_end = 3343 + _globals["_MISSIONPROGRESS"]._serialized_start = 3345 + _globals["_MISSIONPROGRESS"]._serialized_end = 3394 + _globals["_MISSIONITEM"]._serialized_start = 3397 + _globals["_MISSIONITEM"]._serialized_end = 3613 + _globals["_MISSIONIMPORTDATA"]._serialized_start = 3616 + _globals["_MISSIONIMPORTDATA"]._serialized_end = 3814 + _globals["_MISSIONRAWRESULT"]._serialized_start = 3817 + _globals["_MISSIONRAWRESULT"]._serialized_end = 4552 + _globals["_MISSIONRAWRESULT_RESULT"]._serialized_start = 3923 + _globals["_MISSIONRAWRESULT_RESULT"]._serialized_end = 4552 + _globals["_MISSIONRAWSERVICE"]._serialized_start = 4555 + _globals["_MISSIONRAWSERVICE"]._serialized_end = 7138 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/mission_raw_pb2_grpc.py b/mavsdk/mission_raw_pb2_grpc.py index 9582d773..0e069c81 100644 --- a/mavsdk/mission_raw_pb2_grpc.py +++ b/mavsdk/mission_raw_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import mission_raw_pb2 as mission__raw_dot_mission__raw__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in mission_raw/mission_raw_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in mission_raw/mission_raw_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class MissionRawServiceStub(object): - """Enable raw missions as exposed by MAVLink. - """ + """Enable raw missions as exposed by MAVLink.""" def __init__(self, channel): """Constructor. @@ -36,105 +39,123 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.UploadMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/UploadMission', - request_serializer=mission__raw_dot_mission__raw__pb2.UploadMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.UploadMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/UploadMission", + request_serializer=mission__raw_dot_mission__raw__pb2.UploadMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.UploadMissionResponse.FromString, + _registered_method=True, + ) self.UploadGeofence = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/UploadGeofence', - request_serializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/UploadGeofence", + request_serializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceResponse.FromString, + _registered_method=True, + ) self.UploadRallyPoints = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/UploadRallyPoints', - request_serializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/UploadRallyPoints", + request_serializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsResponse.FromString, + _registered_method=True, + ) self.CancelMissionUpload = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionUpload', - request_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionUpload", + request_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadResponse.FromString, + _registered_method=True, + ) self.DownloadMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/DownloadMission', - request_serializer=mission__raw_dot_mission__raw__pb2.DownloadMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.DownloadMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/DownloadMission", + request_serializer=mission__raw_dot_mission__raw__pb2.DownloadMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.DownloadMissionResponse.FromString, + _registered_method=True, + ) self.DownloadGeofence = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/DownloadGeofence', - request_serializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/DownloadGeofence", + request_serializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceResponse.FromString, + _registered_method=True, + ) self.DownloadRallypoints = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/DownloadRallypoints', - request_serializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/DownloadRallypoints", + request_serializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsResponse.FromString, + _registered_method=True, + ) self.CancelMissionDownload = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionDownload', - request_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionDownload", + request_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadResponse.FromString, + _registered_method=True, + ) self.StartMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/StartMission', - request_serializer=mission__raw_dot_mission__raw__pb2.StartMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.StartMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/StartMission", + request_serializer=mission__raw_dot_mission__raw__pb2.StartMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.StartMissionResponse.FromString, + _registered_method=True, + ) self.PauseMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/PauseMission', - request_serializer=mission__raw_dot_mission__raw__pb2.PauseMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.PauseMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/PauseMission", + request_serializer=mission__raw_dot_mission__raw__pb2.PauseMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.PauseMissionResponse.FromString, + _registered_method=True, + ) self.ClearMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/ClearMission', - request_serializer=mission__raw_dot_mission__raw__pb2.ClearMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.ClearMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/ClearMission", + request_serializer=mission__raw_dot_mission__raw__pb2.ClearMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.ClearMissionResponse.FromString, + _registered_method=True, + ) self.SetCurrentMissionItem = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/SetCurrentMissionItem', - request_serializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/SetCurrentMissionItem", + request_serializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemResponse.FromString, + _registered_method=True, + ) self.SubscribeMissionProgress = channel.unary_stream( - '/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionProgress', - request_serializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionProgressRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.MissionProgressResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionProgress", + request_serializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionProgressRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.MissionProgressResponse.FromString, + _registered_method=True, + ) self.SubscribeMissionChanged = channel.unary_stream( - '/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionChanged', - request_serializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionChangedRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.MissionChangedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionChanged", + request_serializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionChangedRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.MissionChangedResponse.FromString, + _registered_method=True, + ) self.ImportQgroundcontrolMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMission', - request_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMission", + request_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionResponse.FromString, + _registered_method=True, + ) self.ImportQgroundcontrolMissionFromString = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMissionFromString', - request_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMissionFromString", + request_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringResponse.FromString, + _registered_method=True, + ) self.ImportMissionPlannerMission = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMission', - request_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMission", + request_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionResponse.FromString, + _registered_method=True, + ) self.ImportMissionPlannerMissionFromString = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMissionFromString', - request_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMissionFromString", + request_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringResponse.FromString, + _registered_method=True, + ) self.IsMissionFinished = channel.unary_unary( - '/mavsdk.rpc.mission_raw.MissionRawService/IsMissionFinished', - request_serializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedRequest.SerializeToString, - response_deserializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw.MissionRawService/IsMissionFinished", + request_serializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedRequest.SerializeToString, + response_deserializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedResponse.FromString, + _registered_method=True, + ) class MissionRawServiceServicer(object): - """Enable raw missions as exposed by MAVLink. - """ + """Enable raw missions as exposed by MAVLink.""" def UploadMission(self, request, context): """ @@ -144,64 +165,64 @@ def UploadMission(self, request, context): can be started and executed even if the connection is lost. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def UploadGeofence(self, request, context): """ Upload a list of geofence items to the system. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def UploadRallyPoints(self, request, context): """ Upload a list of rally point items to the system. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def CancelMissionUpload(self, request, context): """ Cancel an ongoing mission upload. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def DownloadMission(self, request, context): """ Download a list of raw mission items from the system (asynchronous). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def DownloadGeofence(self, request, context): """ Download a list of raw geofence items from the system (asynchronous). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def DownloadRallypoints(self, request, context): """ Download a list of raw rallypoint items from the system (asynchronous). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def CancelMissionDownload(self, request, context): """ Cancel an ongoing mission download. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def StartMission(self, request, context): """ @@ -210,8 +231,8 @@ def StartMission(self, request, context): A mission must be uploaded to the vehicle before this can be called. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PauseMission(self, request, context): """ @@ -223,16 +244,16 @@ def PauseMission(self, request, context): around the location where it paused. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ClearMission(self, request, context): """ Clear the mission saved on the vehicle. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetCurrentMissionItem(self, request, context): """ @@ -242,16 +263,16 @@ def SetCurrentMissionItem(self, request, context): to a specific index of a raw mission item, the mission will be set to this item. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeMissionProgress(self, request, context): """ Subscribe to mission progress updates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeMissionChanged(self, request, context): """ @@ -263,8 +284,8 @@ def SubscribeMissionChanged(self, request, context): @param callback Callback to notify about change. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ImportQgroundcontrolMission(self, request, context): """ @@ -277,8 +298,8 @@ def ImportQgroundcontrolMission(self, request, context): - Structure Scan """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ImportQgroundcontrolMissionFromString(self, request, context): """ @@ -291,8 +312,8 @@ def ImportQgroundcontrolMissionFromString(self, request, context): - Structure Scan """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ImportMissionPlannerMission(self, request, context): """ @@ -303,8 +324,8 @@ def ImportMissionPlannerMission(self, request, context): - ArduPilot home position handling """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ImportMissionPlannerMissionFromString(self, request, context): """ @@ -315,8 +336,8 @@ def ImportMissionPlannerMissionFromString(self, request, context): - ArduPilot home position handling """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def IsMissionFinished(self, request, context): """ @@ -325,134 +346,138 @@ def IsMissionFinished(self, request, context): Returns true if the mission is finished, false otherwise. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_MissionRawServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'UploadMission': grpc.unary_unary_rpc_method_handler( - servicer.UploadMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.UploadMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.UploadMissionResponse.SerializeToString, - ), - 'UploadGeofence': grpc.unary_unary_rpc_method_handler( - servicer.UploadGeofence, - request_deserializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceResponse.SerializeToString, - ), - 'UploadRallyPoints': grpc.unary_unary_rpc_method_handler( - servicer.UploadRallyPoints, - request_deserializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsResponse.SerializeToString, - ), - 'CancelMissionUpload': grpc.unary_unary_rpc_method_handler( - servicer.CancelMissionUpload, - request_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadResponse.SerializeToString, - ), - 'DownloadMission': grpc.unary_unary_rpc_method_handler( - servicer.DownloadMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.DownloadMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.DownloadMissionResponse.SerializeToString, - ), - 'DownloadGeofence': grpc.unary_unary_rpc_method_handler( - servicer.DownloadGeofence, - request_deserializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceResponse.SerializeToString, - ), - 'DownloadRallypoints': grpc.unary_unary_rpc_method_handler( - servicer.DownloadRallypoints, - request_deserializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsResponse.SerializeToString, - ), - 'CancelMissionDownload': grpc.unary_unary_rpc_method_handler( - servicer.CancelMissionDownload, - request_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadResponse.SerializeToString, - ), - 'StartMission': grpc.unary_unary_rpc_method_handler( - servicer.StartMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.StartMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.StartMissionResponse.SerializeToString, - ), - 'PauseMission': grpc.unary_unary_rpc_method_handler( - servicer.PauseMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.PauseMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.PauseMissionResponse.SerializeToString, - ), - 'ClearMission': grpc.unary_unary_rpc_method_handler( - servicer.ClearMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.ClearMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.ClearMissionResponse.SerializeToString, - ), - 'SetCurrentMissionItem': grpc.unary_unary_rpc_method_handler( - servicer.SetCurrentMissionItem, - request_deserializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemResponse.SerializeToString, - ), - 'SubscribeMissionProgress': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeMissionProgress, - request_deserializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionProgressRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.MissionProgressResponse.SerializeToString, - ), - 'SubscribeMissionChanged': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeMissionChanged, - request_deserializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionChangedRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.MissionChangedResponse.SerializeToString, - ), - 'ImportQgroundcontrolMission': grpc.unary_unary_rpc_method_handler( - servicer.ImportQgroundcontrolMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionResponse.SerializeToString, - ), - 'ImportQgroundcontrolMissionFromString': grpc.unary_unary_rpc_method_handler( - servicer.ImportQgroundcontrolMissionFromString, - request_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringResponse.SerializeToString, - ), - 'ImportMissionPlannerMission': grpc.unary_unary_rpc_method_handler( - servicer.ImportMissionPlannerMission, - request_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionResponse.SerializeToString, - ), - 'ImportMissionPlannerMissionFromString': grpc.unary_unary_rpc_method_handler( - servicer.ImportMissionPlannerMissionFromString, - request_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringResponse.SerializeToString, - ), - 'IsMissionFinished': grpc.unary_unary_rpc_method_handler( - servicer.IsMissionFinished, - request_deserializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedRequest.FromString, - response_serializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedResponse.SerializeToString, - ), + "UploadMission": grpc.unary_unary_rpc_method_handler( + servicer.UploadMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.UploadMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.UploadMissionResponse.SerializeToString, + ), + "UploadGeofence": grpc.unary_unary_rpc_method_handler( + servicer.UploadGeofence, + request_deserializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.UploadGeofenceResponse.SerializeToString, + ), + "UploadRallyPoints": grpc.unary_unary_rpc_method_handler( + servicer.UploadRallyPoints, + request_deserializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.UploadRallyPointsResponse.SerializeToString, + ), + "CancelMissionUpload": grpc.unary_unary_rpc_method_handler( + servicer.CancelMissionUpload, + request_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionUploadResponse.SerializeToString, + ), + "DownloadMission": grpc.unary_unary_rpc_method_handler( + servicer.DownloadMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.DownloadMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.DownloadMissionResponse.SerializeToString, + ), + "DownloadGeofence": grpc.unary_unary_rpc_method_handler( + servicer.DownloadGeofence, + request_deserializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.DownloadGeofenceResponse.SerializeToString, + ), + "DownloadRallypoints": grpc.unary_unary_rpc_method_handler( + servicer.DownloadRallypoints, + request_deserializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.DownloadRallypointsResponse.SerializeToString, + ), + "CancelMissionDownload": grpc.unary_unary_rpc_method_handler( + servicer.CancelMissionDownload, + request_deserializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.CancelMissionDownloadResponse.SerializeToString, + ), + "StartMission": grpc.unary_unary_rpc_method_handler( + servicer.StartMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.StartMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.StartMissionResponse.SerializeToString, + ), + "PauseMission": grpc.unary_unary_rpc_method_handler( + servicer.PauseMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.PauseMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.PauseMissionResponse.SerializeToString, + ), + "ClearMission": grpc.unary_unary_rpc_method_handler( + servicer.ClearMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.ClearMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.ClearMissionResponse.SerializeToString, + ), + "SetCurrentMissionItem": grpc.unary_unary_rpc_method_handler( + servicer.SetCurrentMissionItem, + request_deserializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemResponse.SerializeToString, + ), + "SubscribeMissionProgress": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeMissionProgress, + request_deserializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionProgressRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.MissionProgressResponse.SerializeToString, + ), + "SubscribeMissionChanged": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeMissionChanged, + request_deserializer=mission__raw_dot_mission__raw__pb2.SubscribeMissionChangedRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.MissionChangedResponse.SerializeToString, + ), + "ImportQgroundcontrolMission": grpc.unary_unary_rpc_method_handler( + servicer.ImportQgroundcontrolMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionResponse.SerializeToString, + ), + "ImportQgroundcontrolMissionFromString": grpc.unary_unary_rpc_method_handler( + servicer.ImportQgroundcontrolMissionFromString, + request_deserializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringResponse.SerializeToString, + ), + "ImportMissionPlannerMission": grpc.unary_unary_rpc_method_handler( + servicer.ImportMissionPlannerMission, + request_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionResponse.SerializeToString, + ), + "ImportMissionPlannerMissionFromString": grpc.unary_unary_rpc_method_handler( + servicer.ImportMissionPlannerMissionFromString, + request_deserializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringResponse.SerializeToString, + ), + "IsMissionFinished": grpc.unary_unary_rpc_method_handler( + servicer.IsMissionFinished, + request_deserializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedRequest.FromString, + response_serializer=mission__raw_dot_mission__raw__pb2.IsMissionFinishedResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.mission_raw.MissionRawService', rpc_method_handlers) + "mavsdk.rpc.mission_raw.MissionRawService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.mission_raw.MissionRawService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.mission_raw.MissionRawService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class MissionRawService(object): - """Enable raw missions as exposed by MAVLink. - """ + """Enable raw missions as exposed by MAVLink.""" @staticmethod - def UploadMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def UploadMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/UploadMission', + "/mavsdk.rpc.mission_raw.MissionRawService/UploadMission", mission__raw_dot_mission__raw__pb2.UploadMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.UploadMissionResponse.FromString, options, @@ -463,23 +488,26 @@ def UploadMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def UploadGeofence(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def UploadGeofence( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/UploadGeofence', + "/mavsdk.rpc.mission_raw.MissionRawService/UploadGeofence", mission__raw_dot_mission__raw__pb2.UploadGeofenceRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.UploadGeofenceResponse.FromString, options, @@ -490,23 +518,26 @@ def UploadGeofence(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def UploadRallyPoints(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def UploadRallyPoints( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/UploadRallyPoints', + "/mavsdk.rpc.mission_raw.MissionRawService/UploadRallyPoints", mission__raw_dot_mission__raw__pb2.UploadRallyPointsRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.UploadRallyPointsResponse.FromString, options, @@ -517,23 +548,26 @@ def UploadRallyPoints(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def CancelMissionUpload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def CancelMissionUpload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionUpload', + "/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionUpload", mission__raw_dot_mission__raw__pb2.CancelMissionUploadRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.CancelMissionUploadResponse.FromString, options, @@ -544,23 +578,26 @@ def CancelMissionUpload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def DownloadMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def DownloadMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/DownloadMission', + "/mavsdk.rpc.mission_raw.MissionRawService/DownloadMission", mission__raw_dot_mission__raw__pb2.DownloadMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.DownloadMissionResponse.FromString, options, @@ -571,23 +608,26 @@ def DownloadMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def DownloadGeofence(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def DownloadGeofence( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/DownloadGeofence', + "/mavsdk.rpc.mission_raw.MissionRawService/DownloadGeofence", mission__raw_dot_mission__raw__pb2.DownloadGeofenceRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.DownloadGeofenceResponse.FromString, options, @@ -598,23 +638,26 @@ def DownloadGeofence(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def DownloadRallypoints(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def DownloadRallypoints( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/DownloadRallypoints', + "/mavsdk.rpc.mission_raw.MissionRawService/DownloadRallypoints", mission__raw_dot_mission__raw__pb2.DownloadRallypointsRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.DownloadRallypointsResponse.FromString, options, @@ -625,23 +668,26 @@ def DownloadRallypoints(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def CancelMissionDownload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def CancelMissionDownload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionDownload', + "/mavsdk.rpc.mission_raw.MissionRawService/CancelMissionDownload", mission__raw_dot_mission__raw__pb2.CancelMissionDownloadRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.CancelMissionDownloadResponse.FromString, options, @@ -652,23 +698,26 @@ def CancelMissionDownload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def StartMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def StartMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/StartMission', + "/mavsdk.rpc.mission_raw.MissionRawService/StartMission", mission__raw_dot_mission__raw__pb2.StartMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.StartMissionResponse.FromString, options, @@ -679,23 +728,26 @@ def StartMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PauseMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PauseMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/PauseMission', + "/mavsdk.rpc.mission_raw.MissionRawService/PauseMission", mission__raw_dot_mission__raw__pb2.PauseMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.PauseMissionResponse.FromString, options, @@ -706,23 +758,26 @@ def PauseMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ClearMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ClearMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/ClearMission', + "/mavsdk.rpc.mission_raw.MissionRawService/ClearMission", mission__raw_dot_mission__raw__pb2.ClearMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.ClearMissionResponse.FromString, options, @@ -733,23 +788,26 @@ def ClearMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetCurrentMissionItem(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetCurrentMissionItem( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/SetCurrentMissionItem', + "/mavsdk.rpc.mission_raw.MissionRawService/SetCurrentMissionItem", mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.SetCurrentMissionItemResponse.FromString, options, @@ -760,23 +818,26 @@ def SetCurrentMissionItem(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeMissionProgress(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeMissionProgress( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionProgress', + "/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionProgress", mission__raw_dot_mission__raw__pb2.SubscribeMissionProgressRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.MissionProgressResponse.FromString, options, @@ -787,23 +848,26 @@ def SubscribeMissionProgress(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeMissionChanged(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeMissionChanged( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionChanged', + "/mavsdk.rpc.mission_raw.MissionRawService/SubscribeMissionChanged", mission__raw_dot_mission__raw__pb2.SubscribeMissionChangedRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.MissionChangedResponse.FromString, options, @@ -814,23 +878,26 @@ def SubscribeMissionChanged(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ImportQgroundcontrolMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ImportQgroundcontrolMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMission', + "/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMission", mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionResponse.FromString, options, @@ -841,23 +908,26 @@ def ImportQgroundcontrolMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ImportQgroundcontrolMissionFromString(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ImportQgroundcontrolMissionFromString( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMissionFromString', + "/mavsdk.rpc.mission_raw.MissionRawService/ImportQgroundcontrolMissionFromString", mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.ImportQgroundcontrolMissionFromStringResponse.FromString, options, @@ -868,23 +938,26 @@ def ImportQgroundcontrolMissionFromString(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ImportMissionPlannerMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ImportMissionPlannerMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMission', + "/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMission", mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionResponse.FromString, options, @@ -895,23 +968,26 @@ def ImportMissionPlannerMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ImportMissionPlannerMissionFromString(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ImportMissionPlannerMissionFromString( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMissionFromString', + "/mavsdk.rpc.mission_raw.MissionRawService/ImportMissionPlannerMissionFromString", mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.ImportMissionPlannerMissionFromStringResponse.FromString, options, @@ -922,23 +998,26 @@ def ImportMissionPlannerMissionFromString(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def IsMissionFinished(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def IsMissionFinished( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw.MissionRawService/IsMissionFinished', + "/mavsdk.rpc.mission_raw.MissionRawService/IsMissionFinished", mission__raw_dot_mission__raw__pb2.IsMissionFinishedRequest.SerializeToString, mission__raw_dot_mission__raw__pb2.IsMissionFinishedResponse.FromString, options, @@ -949,4 +1028,5 @@ def IsMissionFinished(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/mission_raw_server.py b/mavsdk/mission_raw_server.py index 0de20d11..a066eb08 100644 --- a/mavsdk/mission_raw_server.py +++ b/mavsdk/mission_raw_server.py @@ -8,69 +8,68 @@ class MissionItem: """ - Mission item exactly identical to MAVLink MISSION_ITEM_INT. + Mission item exactly identical to MAVLink MISSION_ITEM_INT. - Parameters - ---------- - seq : uint32_t - Sequence (uint16_t) + Parameters + ---------- + seq : uint32_t + Sequence (uint16_t) - frame : uint32_t - The coordinate system of the waypoint (actually uint8_t) + frame : uint32_t + The coordinate system of the waypoint (actually uint8_t) - command : uint32_t - The scheduled action for the waypoint (actually uint16_t) + command : uint32_t + The scheduled action for the waypoint (actually uint16_t) - current : uint32_t - false:0, true:1 (actually uint8_t) + current : uint32_t + false:0, true:1 (actually uint8_t) - autocontinue : uint32_t - Autocontinue to next waypoint (actually uint8_t) + autocontinue : uint32_t + Autocontinue to next waypoint (actually uint8_t) - param1 : float - PARAM1, see MAV_CMD enum + param1 : float + PARAM1, see MAV_CMD enum - param2 : float - PARAM2, see MAV_CMD enum + param2 : float + PARAM2, see MAV_CMD enum - param3 : float - PARAM3, see MAV_CMD enum + param3 : float + PARAM3, see MAV_CMD enum - param4 : float - PARAM4, see MAV_CMD enum + param4 : float + PARAM4, see MAV_CMD enum - x : int32_t - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + x : int32_t + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - y : int32_t - PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + y : int32_t + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - z : float - PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame) + z : float + PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame) - mission_type : uint32_t - Mission type (actually uint8_t) + mission_type : uint32_t + Mission type (actually uint8_t) - """ - - + """ def __init__( - self, - seq, - frame, - command, - current, - autocontinue, - param1, - param2, - param3, - param4, - x, - y, - z, - mission_type): - """ Initializes the MissionItem object """ + self, + seq, + frame, + command, + current, + autocontinue, + param1, + param2, + param3, + param4, + x, + y, + z, + mission_type, + ): + """Initializes the MissionItem object""" self.seq = seq self.frame = frame self.command = command @@ -86,31 +85,33 @@ def __init__( self.mission_type = mission_type def __eq__(self, to_compare): - """ Checks if two MissionItem are the same """ + """Checks if two MissionItem are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionItem object - return \ - (self.seq == to_compare.seq) and \ - (self.frame == to_compare.frame) and \ - (self.command == to_compare.command) and \ - (self.current == to_compare.current) and \ - (self.autocontinue == to_compare.autocontinue) and \ - (self.param1 == to_compare.param1) and \ - (self.param2 == to_compare.param2) and \ - (self.param3 == to_compare.param3) and \ - (self.param4 == to_compare.param4) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) and \ - (self.mission_type == to_compare.mission_type) + return ( + (self.seq == to_compare.seq) + and (self.frame == to_compare.frame) + and (self.command == to_compare.command) + and (self.current == to_compare.current) + and (self.autocontinue == to_compare.autocontinue) + and (self.param1 == to_compare.param1) + and (self.param2 == to_compare.param2) + and (self.param3 == to_compare.param3) + and (self.param4 == to_compare.param4) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + and (self.mission_type == to_compare.mission_type) + ) except AttributeError: return False def __str__(self): - """ MissionItem in string representation """ - struct_repr = ", ".join([ + """MissionItem in string representation""" + struct_repr = ", ".join( + [ "seq: " + str(self.seq), "frame: " + str(self.frame), "command: " + str(self.command), @@ -123,342 +124,229 @@ def __str__(self): "x: " + str(self.x), "y: " + str(self.y), "z: " + str(self.z), - "mission_type: " + str(self.mission_type) - ]) + "mission_type: " + str(self.mission_type), + ] + ) return f"MissionItem: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionItem): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionItem( - - rpcMissionItem.seq, - - - rpcMissionItem.frame, - - - rpcMissionItem.command, - - - rpcMissionItem.current, - - - rpcMissionItem.autocontinue, - - - rpcMissionItem.param1, - - - rpcMissionItem.param2, - - - rpcMissionItem.param3, - - - rpcMissionItem.param4, - - - rpcMissionItem.x, - - - rpcMissionItem.y, - - - rpcMissionItem.z, - - - rpcMissionItem.mission_type - ) + rpcMissionItem.seq, + rpcMissionItem.frame, + rpcMissionItem.command, + rpcMissionItem.current, + rpcMissionItem.autocontinue, + rpcMissionItem.param1, + rpcMissionItem.param2, + rpcMissionItem.param3, + rpcMissionItem.param4, + rpcMissionItem.x, + rpcMissionItem.y, + rpcMissionItem.z, + rpcMissionItem.mission_type, + ) def translate_to_rpc(self, rpcMissionItem): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionItem.seq = self.seq - - - - - + rpcMissionItem.frame = self.frame - - - - - + rpcMissionItem.command = self.command - - - - - + rpcMissionItem.current = self.current - - - - - + rpcMissionItem.autocontinue = self.autocontinue - - - - - + rpcMissionItem.param1 = self.param1 - - - - - + rpcMissionItem.param2 = self.param2 - - - - - + rpcMissionItem.param3 = self.param3 - - - - - + rpcMissionItem.param4 = self.param4 - - - - - + rpcMissionItem.x = self.x - - - - - + rpcMissionItem.y = self.y - - - - - + rpcMissionItem.z = self.z - - - - - + rpcMissionItem.mission_type = self.mission_type - - - class MissionPlan: """ - Mission plan type + Mission plan type - Parameters - ---------- - mission_items : [MissionItem] - The mission items + Parameters + ---------- + mission_items : [MissionItem] + The mission items - """ - - + """ - def __init__( - self, - mission_items): - """ Initializes the MissionPlan object """ + def __init__(self, mission_items): + """Initializes the MissionPlan object""" self.mission_items = mission_items def __eq__(self, to_compare): - """ Checks if two MissionPlan are the same """ + """Checks if two MissionPlan are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionPlan object - return \ - (self.mission_items == to_compare.mission_items) + return self.mission_items == to_compare.mission_items except AttributeError: return False def __str__(self): - """ MissionPlan in string representation """ - struct_repr = ", ".join([ - "mission_items: " + str(self.mission_items) - ]) + """MissionPlan in string representation""" + struct_repr = ", ".join(["mission_items: " + str(self.mission_items)]) return f"MissionPlan: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionPlan): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionPlan( - - list(map(lambda elem: MissionItem.translate_from_rpc(elem), rpcMissionPlan.mission_items)) + list( + map( + lambda elem: MissionItem.translate_from_rpc(elem), + rpcMissionPlan.mission_items, ) + ) + ) def translate_to_rpc(self, rpcMissionPlan): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.mission_items: - rpc_elem = mission_raw_server_pb2.MissionItem() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcMissionPlan.mission_items.extend(rpc_elems_list) - - - class MissionProgress: """ - Mission progress type. - - Parameters - ---------- - current : int32_t - Current mission item index (0-based), if equal to total, the mission is finished + Mission progress type. - total : int32_t - Total number of mission items + Parameters + ---------- + current : int32_t + Current mission item index (0-based), if equal to total, the mission is finished - """ + total : int32_t + Total number of mission items - + """ - def __init__( - self, - current, - total): - """ Initializes the MissionProgress object """ + def __init__(self, current, total): + """Initializes the MissionProgress object""" self.current = current self.total = total def __eq__(self, to_compare): - """ Checks if two MissionProgress are the same """ + """Checks if two MissionProgress are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionProgress object - return \ - (self.current == to_compare.current) and \ - (self.total == to_compare.total) + return (self.current == to_compare.current) and ( + self.total == to_compare.total + ) except AttributeError: return False def __str__(self): - """ MissionProgress in string representation """ - struct_repr = ", ".join([ - "current: " + str(self.current), - "total: " + str(self.total) - ]) + """MissionProgress in string representation""" + struct_repr = ", ".join( + ["current: " + str(self.current), "total: " + str(self.total)] + ) return f"MissionProgress: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionProgress): - """ Translates a gRPC struct to the SDK equivalent """ - return MissionProgress( - - rpcMissionProgress.current, - - - rpcMissionProgress.total - ) + """Translates a gRPC struct to the SDK equivalent""" + return MissionProgress(rpcMissionProgress.current, rpcMissionProgress.total) def translate_to_rpc(self, rpcMissionProgress): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionProgress.current = self.current - - - - - + rpcMissionProgress.total = self.total - - - class MissionRawServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for action requests. + Possible results returned for action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - ERROR - Error + ERROR + Error - TOO_MANY_MISSION_ITEMS - Too many mission items in the mission + TOO_MANY_MISSION_ITEMS + Too many mission items in the mission - BUSY - Vehicle is busy + BUSY + Vehicle is busy - TIMEOUT - Request timed out + TIMEOUT + Request timed out - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - UNSUPPORTED - Mission downloaded from the system is not supported + UNSUPPORTED + Mission downloaded from the system is not supported - NO_MISSION_AVAILABLE - No mission available on the system + NO_MISSION_AVAILABLE + No mission available on the system - UNSUPPORTED_MISSION_CMD - Unsupported mission command + UNSUPPORTED_MISSION_CMD + Unsupported mission command - TRANSFER_CANCELLED - Mission transfer (upload or download) has been cancelled + TRANSFER_CANCELLED + Mission transfer (upload or download) has been cancelled - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - NEXT - Intermediate message showing progress or instructions on the next steps + NEXT + Intermediate message showing progress or instructions on the next steps - """ + """ - UNKNOWN = 0 SUCCESS = 1 ERROR = 2 @@ -503,99 +391,121 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_UNKNOWN + ): return MissionRawServerResult.Result.UNKNOWN - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_SUCCESS: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_SUCCESS + ): return MissionRawServerResult.Result.SUCCESS - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_ERROR: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_ERROR + ): return MissionRawServerResult.Result.ERROR - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_TOO_MANY_MISSION_ITEMS: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_TOO_MANY_MISSION_ITEMS + ): return MissionRawServerResult.Result.TOO_MANY_MISSION_ITEMS - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_BUSY: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_BUSY + ): return MissionRawServerResult.Result.BUSY - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_TIMEOUT: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_TIMEOUT + ): return MissionRawServerResult.Result.TIMEOUT - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_INVALID_ARGUMENT: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_INVALID_ARGUMENT + ): return MissionRawServerResult.Result.INVALID_ARGUMENT - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_UNSUPPORTED: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_UNSUPPORTED + ): return MissionRawServerResult.Result.UNSUPPORTED - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_NO_MISSION_AVAILABLE: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_NO_MISSION_AVAILABLE + ): return MissionRawServerResult.Result.NO_MISSION_AVAILABLE - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_UNSUPPORTED_MISSION_CMD: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_UNSUPPORTED_MISSION_CMD + ): return MissionRawServerResult.Result.UNSUPPORTED_MISSION_CMD - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_TRANSFER_CANCELLED: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_TRANSFER_CANCELLED + ): return MissionRawServerResult.Result.TRANSFER_CANCELLED - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_NO_SYSTEM + ): return MissionRawServerResult.Result.NO_SYSTEM - if rpc_enum_value == mission_raw_server_pb2.MissionRawServerResult.RESULT_NEXT: + if ( + rpc_enum_value + == mission_raw_server_pb2.MissionRawServerResult.RESULT_NEXT + ): return MissionRawServerResult.Result.NEXT def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the MissionRawServerResult object """ + def __init__(self, result, result_str): + """Initializes the MissionRawServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two MissionRawServerResult are the same """ + """Checks if two MissionRawServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # MissionRawServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ MissionRawServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """MissionRawServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"MissionRawServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMissionRawServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MissionRawServerResult( - - MissionRawServerResult.Result.translate_from_rpc(rpcMissionRawServerResult.result), - - - rpcMissionRawServerResult.result_str - ) + MissionRawServerResult.Result.translate_from_rpc( + rpcMissionRawServerResult.result + ), + rpcMissionRawServerResult.result_str, + ) def translate_to_rpc(self, rpcMissionRawServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMissionRawServerResult.result = self.result.translate_to_rpc() - - - - - - rpcMissionRawServerResult.result_str = self.result_str - - - + rpcMissionRawServerResult.result_str = self.result_str class MissionRawServerError(Exception): - """ Raised when a MissionRawServerResult is a fail code """ + """Raised when a MissionRawServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -608,38 +518,38 @@ def __str__(self): class MissionRawServer(AsyncBase): """ - Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). - Provides current mission item state, so the server can progress through missions. + Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). + Provides current mission item state, so the server can progress through missions. - Generated by dcsdkgen - MAVSDK MissionRawServer API + Generated by dcsdkgen - MAVSDK MissionRawServer API """ # Plugin name name = "MissionRawServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = mission_raw_server_pb2_grpc.MissionRawServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ - return MissionRawServerResult.translate_from_rpc(response.mission_raw_server_result) - + """Returns the response status and description""" + return MissionRawServerResult.translate_from_rpc( + response.mission_raw_server_result + ) async def incoming_mission(self): """ - Subscribe to when a new mission is uploaded (asynchronous). + Subscribe to when a new mission is uploaded (asynchronous). - Yields - ------- - mission_plan : MissionPlan - The mission plan + Yields + ------- + mission_plan : MissionPlan + The mission plan - Raises - ------ - MissionRawServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MissionRawServerError + If the request fails. The error contains the reason for the failure. """ request = mission_raw_server_pb2.SubscribeIncomingMissionRequest() @@ -647,35 +557,34 @@ async def incoming_mission(self): try: async for response in incoming_mission_stream: - result = self._extract_result(response) success_codes = [MissionRawServerResult.Result.SUCCESS] - if 'NEXT' in [return_code.name for return_code in MissionRawServerResult.Result]: + if "NEXT" in [ + return_code.name for return_code in MissionRawServerResult.Result + ]: success_codes.append(MissionRawServerResult.Result.NEXT) if result.result not in success_codes: raise MissionRawServerError(result, "incoming_mission()") if result.result == MissionRawServerResult.Result.SUCCESS: - incoming_mission_stream.cancel(); + incoming_mission_stream.cancel() return - - yield MissionPlan.translate_from_rpc(response.mission_plan) finally: incoming_mission_stream.cancel() async def current_item_changed(self): """ - Subscribe to when a new current item is set + Subscribe to when a new current item is set + + Yields + ------- + mission_item : MissionItem + - Yields - ------- - mission_item : MissionItem - - """ request = mission_raw_server_pb2.SubscribeCurrentItemChangedRequest() @@ -683,34 +592,29 @@ async def current_item_changed(self): try: async for response in current_item_changed_stream: - - - yield MissionItem.translate_from_rpc(response.mission_item) finally: current_item_changed_stream.cancel() async def set_current_item_complete(self): """ - Set Current item as completed + Set Current item as completed + - """ request = mission_raw_server_pb2.SetCurrentItemCompleteRequest() response = await self._stub.SetCurrentItemComplete(request) - - async def clear_all(self): """ - Subscribe when a MISSION_CLEAR_ALL is received + Subscribe when a MISSION_CLEAR_ALL is received + + Yields + ------- + clear_type : uint32_t + - Yields - ------- - clear_type : uint32_t - - """ request = mission_raw_server_pb2.SubscribeClearAllRequest() @@ -718,9 +622,6 @@ async def clear_all(self): try: async for response in clear_all_stream: - - - yield response.clear_type finally: - clear_all_stream.cancel() \ No newline at end of file + clear_all_stream.cancel() diff --git a/mavsdk/mission_raw_server_pb2.py b/mavsdk/mission_raw_server_pb2.py index eb04fe32..09432626 100644 --- a/mavsdk/mission_raw_server_pb2.py +++ b/mavsdk/mission_raw_server_pb2.py @@ -4,18 +4,20 @@ # source: mission_raw_server/mission_raw_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( _runtime_version.Domain.PUBLIC, 5, 29, 0, - '', - 'mission_raw_server/mission_raw_server.proto' + "", + "mission_raw_server/mission_raw_server.proto", ) # @@protoc_insertion_point(imports) @@ -25,48 +27,72 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n+mission_raw_server/mission_raw_server.proto\x12\x1dmavsdk.rpc.mission_raw_server\x1a\x14mavsdk_options.proto\"!\n\x1fSubscribeIncomingMissionRequest\"\xb5\x01\n\x17IncomingMissionResponse\x12X\n\x19mission_raw_server_result\x18\x01 \x01(\x0b\x32\x35.mavsdk.rpc.mission_raw_server.MissionRawServerResult\x12@\n\x0cmission_plan\x18\x02 \x01(\x0b\x32*.mavsdk.rpc.mission_raw_server.MissionPlan\"$\n\"SubscribeCurrentItemChangedRequest\"^\n\x1a\x43urrentItemChangedResponse\x12@\n\x0cmission_item\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.mission_raw_server.MissionItem\"\x1a\n\x18SubscribeClearAllRequest\"&\n\x10\x43learAllResponse\x12\x12\n\nclear_type\x18\x01 \x01(\r\"\x1f\n\x1dSetCurrentItemCompleteRequest\" \n\x1eSetCurrentItemCompleteResponse\"\xd8\x01\n\x0bMissionItem\x12\x0b\n\x03seq\x18\x01 \x01(\r\x12\r\n\x05\x66rame\x18\x02 \x01(\r\x12\x0f\n\x07\x63ommand\x18\x03 \x01(\r\x12\x0f\n\x07\x63urrent\x18\x04 \x01(\r\x12\x14\n\x0c\x61utocontinue\x18\x05 \x01(\r\x12\x0e\n\x06param1\x18\x06 \x01(\x02\x12\x0e\n\x06param2\x18\x07 \x01(\x02\x12\x0e\n\x06param3\x18\x08 \x01(\x02\x12\x0e\n\x06param4\x18\t \x01(\x02\x12\t\n\x01x\x18\n \x01(\x05\x12\t\n\x01y\x18\x0b \x01(\x05\x12\t\n\x01z\x18\x0c \x01(\x02\x12\x14\n\x0cmission_type\x18\r \x01(\r\"P\n\x0bMissionPlan\x12\x41\n\rmission_items\x18\x01 \x03(\x0b\x32*.mavsdk.rpc.mission_raw_server.MissionItem\"1\n\x0fMissionProgress\x12\x0f\n\x07\x63urrent\x18\x01 \x01(\x05\x12\r\n\x05total\x18\x02 \x01(\x05\"\xc7\x03\n\x16MissionRawServerResult\x12L\n\x06result\x18\x01 \x01(\x0e\x32<.mavsdk.rpc.mission_raw_server.MissionRawServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xca\x02\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\x1dRESULT_TOO_MANY_MISSION_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\x16\n\x12RESULT_UNSUPPORTED\x10\x07\x12\x1f\n\x1bRESULT_NO_MISSION_AVAILABLE\x10\x08\x12\"\n\x1eRESULT_UNSUPPORTED_MISSION_CMD\x10\x0b\x12\x1d\n\x19RESULT_TRANSFER_CANCELLED\x10\x0c\x12\x14\n\x10RESULT_NO_SYSTEM\x10\r\x12\x0f\n\x0bRESULT_NEXT\x10\x0e\x32\x82\x05\n\x17MissionRawServerService\x12\x9a\x01\n\x18SubscribeIncomingMission\x12>.mavsdk.rpc.mission_raw_server.SubscribeIncomingMissionRequest\x1a\x36.mavsdk.rpc.mission_raw_server.IncomingMissionResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\xa3\x01\n\x1bSubscribeCurrentItemChanged\x12\x41.mavsdk.rpc.mission_raw_server.SubscribeCurrentItemChangedRequest\x1a\x39.mavsdk.rpc.mission_raw_server.CurrentItemChangedResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9b\x01\n\x16SetCurrentItemComplete\x12<.mavsdk.rpc.mission_raw_server.SetCurrentItemCompleteRequest\x1a=.mavsdk.rpc.mission_raw_server.SetCurrentItemCompleteResponse\"\x04\x80\xb5\x18\x01\x12\x85\x01\n\x11SubscribeClearAll\x12\x37.mavsdk.rpc.mission_raw_server.SubscribeClearAllRequest\x1a/.mavsdk.rpc.mission_raw_server.ClearAllResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42\x35\n\x1cio.mavsdk.mission_raw_serverB\x15MissionRawServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n+mission_raw_server/mission_raw_server.proto\x12\x1dmavsdk.rpc.mission_raw_server\x1a\x14mavsdk_options.proto"!\n\x1fSubscribeIncomingMissionRequest"\xb5\x01\n\x17IncomingMissionResponse\x12X\n\x19mission_raw_server_result\x18\x01 \x01(\x0b\x32\x35.mavsdk.rpc.mission_raw_server.MissionRawServerResult\x12@\n\x0cmission_plan\x18\x02 \x01(\x0b\x32*.mavsdk.rpc.mission_raw_server.MissionPlan"$\n"SubscribeCurrentItemChangedRequest"^\n\x1a\x43urrentItemChangedResponse\x12@\n\x0cmission_item\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.mission_raw_server.MissionItem"\x1a\n\x18SubscribeClearAllRequest"&\n\x10\x43learAllResponse\x12\x12\n\nclear_type\x18\x01 \x01(\r"\x1f\n\x1dSetCurrentItemCompleteRequest" \n\x1eSetCurrentItemCompleteResponse"\xd8\x01\n\x0bMissionItem\x12\x0b\n\x03seq\x18\x01 \x01(\r\x12\r\n\x05\x66rame\x18\x02 \x01(\r\x12\x0f\n\x07\x63ommand\x18\x03 \x01(\r\x12\x0f\n\x07\x63urrent\x18\x04 \x01(\r\x12\x14\n\x0c\x61utocontinue\x18\x05 \x01(\r\x12\x0e\n\x06param1\x18\x06 \x01(\x02\x12\x0e\n\x06param2\x18\x07 \x01(\x02\x12\x0e\n\x06param3\x18\x08 \x01(\x02\x12\x0e\n\x06param4\x18\t \x01(\x02\x12\t\n\x01x\x18\n \x01(\x05\x12\t\n\x01y\x18\x0b \x01(\x05\x12\t\n\x01z\x18\x0c \x01(\x02\x12\x14\n\x0cmission_type\x18\r \x01(\r"P\n\x0bMissionPlan\x12\x41\n\rmission_items\x18\x01 \x03(\x0b\x32*.mavsdk.rpc.mission_raw_server.MissionItem"1\n\x0fMissionProgress\x12\x0f\n\x07\x63urrent\x18\x01 \x01(\x05\x12\r\n\x05total\x18\x02 \x01(\x05"\xc7\x03\n\x16MissionRawServerResult\x12L\n\x06result\x18\x01 \x01(\x0e\x32<.mavsdk.rpc.mission_raw_server.MissionRawServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xca\x02\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\x1dRESULT_TOO_MANY_MISSION_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\x16\n\x12RESULT_UNSUPPORTED\x10\x07\x12\x1f\n\x1bRESULT_NO_MISSION_AVAILABLE\x10\x08\x12"\n\x1eRESULT_UNSUPPORTED_MISSION_CMD\x10\x0b\x12\x1d\n\x19RESULT_TRANSFER_CANCELLED\x10\x0c\x12\x14\n\x10RESULT_NO_SYSTEM\x10\r\x12\x0f\n\x0bRESULT_NEXT\x10\x0e\x32\x82\x05\n\x17MissionRawServerService\x12\x9a\x01\n\x18SubscribeIncomingMission\x12>.mavsdk.rpc.mission_raw_server.SubscribeIncomingMissionRequest\x1a\x36.mavsdk.rpc.mission_raw_server.IncomingMissionResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\xa3\x01\n\x1bSubscribeCurrentItemChanged\x12\x41.mavsdk.rpc.mission_raw_server.SubscribeCurrentItemChangedRequest\x1a\x39.mavsdk.rpc.mission_raw_server.CurrentItemChangedResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9b\x01\n\x16SetCurrentItemComplete\x12<.mavsdk.rpc.mission_raw_server.SetCurrentItemCompleteRequest\x1a=.mavsdk.rpc.mission_raw_server.SetCurrentItemCompleteResponse"\x04\x80\xb5\x18\x01\x12\x85\x01\n\x11SubscribeClearAll\x12\x37.mavsdk.rpc.mission_raw_server.SubscribeClearAllRequest\x1a/.mavsdk.rpc.mission_raw_server.ClearAllResponse"\x04\x80\xb5\x18\x00\x30\x01\x42\x35\n\x1cio.mavsdk.mission_raw_serverB\x15MissionRawServerProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mission_raw_server.mission_raw_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "mission_raw_server.mission_raw_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\034io.mavsdk.mission_raw_serverB\025MissionRawServerProto' - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SubscribeIncomingMission']._loaded_options = None - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SubscribeIncomingMission']._serialized_options = b'\200\265\030\000' - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SubscribeCurrentItemChanged']._loaded_options = None - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SubscribeCurrentItemChanged']._serialized_options = b'\200\265\030\000' - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SetCurrentItemComplete']._loaded_options = None - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SetCurrentItemComplete']._serialized_options = b'\200\265\030\001' - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SubscribeClearAll']._loaded_options = None - _globals['_MISSIONRAWSERVERSERVICE'].methods_by_name['SubscribeClearAll']._serialized_options = b'\200\265\030\000' - _globals['_SUBSCRIBEINCOMINGMISSIONREQUEST']._serialized_start=100 - _globals['_SUBSCRIBEINCOMINGMISSIONREQUEST']._serialized_end=133 - _globals['_INCOMINGMISSIONRESPONSE']._serialized_start=136 - _globals['_INCOMINGMISSIONRESPONSE']._serialized_end=317 - _globals['_SUBSCRIBECURRENTITEMCHANGEDREQUEST']._serialized_start=319 - _globals['_SUBSCRIBECURRENTITEMCHANGEDREQUEST']._serialized_end=355 - _globals['_CURRENTITEMCHANGEDRESPONSE']._serialized_start=357 - _globals['_CURRENTITEMCHANGEDRESPONSE']._serialized_end=451 - _globals['_SUBSCRIBECLEARALLREQUEST']._serialized_start=453 - _globals['_SUBSCRIBECLEARALLREQUEST']._serialized_end=479 - _globals['_CLEARALLRESPONSE']._serialized_start=481 - _globals['_CLEARALLRESPONSE']._serialized_end=519 - _globals['_SETCURRENTITEMCOMPLETEREQUEST']._serialized_start=521 - _globals['_SETCURRENTITEMCOMPLETEREQUEST']._serialized_end=552 - _globals['_SETCURRENTITEMCOMPLETERESPONSE']._serialized_start=554 - _globals['_SETCURRENTITEMCOMPLETERESPONSE']._serialized_end=586 - _globals['_MISSIONITEM']._serialized_start=589 - _globals['_MISSIONITEM']._serialized_end=805 - _globals['_MISSIONPLAN']._serialized_start=807 - _globals['_MISSIONPLAN']._serialized_end=887 - _globals['_MISSIONPROGRESS']._serialized_start=889 - _globals['_MISSIONPROGRESS']._serialized_end=938 - _globals['_MISSIONRAWSERVERRESULT']._serialized_start=941 - _globals['_MISSIONRAWSERVERRESULT']._serialized_end=1396 - _globals['_MISSIONRAWSERVERRESULT_RESULT']._serialized_start=1066 - _globals['_MISSIONRAWSERVERRESULT_RESULT']._serialized_end=1396 - _globals['_MISSIONRAWSERVERSERVICE']._serialized_start=1399 - _globals['_MISSIONRAWSERVERSERVICE']._serialized_end=2041 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = ( + b"\n\034io.mavsdk.mission_raw_serverB\025MissionRawServerProto" + ) + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SubscribeIncomingMission" + ]._loaded_options = None + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SubscribeIncomingMission" + ]._serialized_options = b"\200\265\030\000" + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SubscribeCurrentItemChanged" + ]._loaded_options = None + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SubscribeCurrentItemChanged" + ]._serialized_options = b"\200\265\030\000" + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SetCurrentItemComplete" + ]._loaded_options = None + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SetCurrentItemComplete" + ]._serialized_options = b"\200\265\030\001" + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SubscribeClearAll" + ]._loaded_options = None + _globals["_MISSIONRAWSERVERSERVICE"].methods_by_name[ + "SubscribeClearAll" + ]._serialized_options = b"\200\265\030\000" + _globals["_SUBSCRIBEINCOMINGMISSIONREQUEST"]._serialized_start = 100 + _globals["_SUBSCRIBEINCOMINGMISSIONREQUEST"]._serialized_end = 133 + _globals["_INCOMINGMISSIONRESPONSE"]._serialized_start = 136 + _globals["_INCOMINGMISSIONRESPONSE"]._serialized_end = 317 + _globals["_SUBSCRIBECURRENTITEMCHANGEDREQUEST"]._serialized_start = 319 + _globals["_SUBSCRIBECURRENTITEMCHANGEDREQUEST"]._serialized_end = 355 + _globals["_CURRENTITEMCHANGEDRESPONSE"]._serialized_start = 357 + _globals["_CURRENTITEMCHANGEDRESPONSE"]._serialized_end = 451 + _globals["_SUBSCRIBECLEARALLREQUEST"]._serialized_start = 453 + _globals["_SUBSCRIBECLEARALLREQUEST"]._serialized_end = 479 + _globals["_CLEARALLRESPONSE"]._serialized_start = 481 + _globals["_CLEARALLRESPONSE"]._serialized_end = 519 + _globals["_SETCURRENTITEMCOMPLETEREQUEST"]._serialized_start = 521 + _globals["_SETCURRENTITEMCOMPLETEREQUEST"]._serialized_end = 552 + _globals["_SETCURRENTITEMCOMPLETERESPONSE"]._serialized_start = 554 + _globals["_SETCURRENTITEMCOMPLETERESPONSE"]._serialized_end = 586 + _globals["_MISSIONITEM"]._serialized_start = 589 + _globals["_MISSIONITEM"]._serialized_end = 805 + _globals["_MISSIONPLAN"]._serialized_start = 807 + _globals["_MISSIONPLAN"]._serialized_end = 887 + _globals["_MISSIONPROGRESS"]._serialized_start = 889 + _globals["_MISSIONPROGRESS"]._serialized_end = 938 + _globals["_MISSIONRAWSERVERRESULT"]._serialized_start = 941 + _globals["_MISSIONRAWSERVERRESULT"]._serialized_end = 1396 + _globals["_MISSIONRAWSERVERRESULT_RESULT"]._serialized_start = 1066 + _globals["_MISSIONRAWSERVERRESULT_RESULT"]._serialized_end = 1396 + _globals["_MISSIONRAWSERVERSERVICE"]._serialized_start = 1399 + _globals["_MISSIONRAWSERVERSERVICE"]._serialized_end = 2041 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/mission_raw_server_pb2_grpc.py b/mavsdk/mission_raw_server_pb2_grpc.py index d1256e08..9c0c0026 100644 --- a/mavsdk/mission_raw_server_pb2_grpc.py +++ b/mavsdk/mission_raw_server_pb2_grpc.py @@ -1,32 +1,38 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings -from . import mission_raw_server_pb2 as mission__raw__server_dot_mission__raw__server__pb2 +from . import ( + mission_raw_server_pb2 as mission__raw__server_dot_mission__raw__server__pb2, +) -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in mission_raw_server/mission_raw_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in mission_raw_server/mission_raw_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class MissionRawServerServiceStub(object): - """Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). + """Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). Provides current mission item state, so the server can progress through missions. """ @@ -37,29 +43,33 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeIncomingMission = channel.unary_stream( - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeIncomingMission', - request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeIncomingMissionRequest.SerializeToString, - response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.IncomingMissionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeIncomingMission", + request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeIncomingMissionRequest.SerializeToString, + response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.IncomingMissionResponse.FromString, + _registered_method=True, + ) self.SubscribeCurrentItemChanged = channel.unary_stream( - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeCurrentItemChanged', - request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeCurrentItemChangedRequest.SerializeToString, - response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.CurrentItemChangedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeCurrentItemChanged", + request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeCurrentItemChangedRequest.SerializeToString, + response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.CurrentItemChangedResponse.FromString, + _registered_method=True, + ) self.SetCurrentItemComplete = channel.unary_unary( - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SetCurrentItemComplete', - request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteRequest.SerializeToString, - response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SetCurrentItemComplete", + request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteRequest.SerializeToString, + response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteResponse.FromString, + _registered_method=True, + ) self.SubscribeClearAll = channel.unary_stream( - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeClearAll', - request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeClearAllRequest.SerializeToString, - response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.ClearAllResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeClearAll", + request_serializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeClearAllRequest.SerializeToString, + response_deserializer=mission__raw__server_dot_mission__raw__server__pb2.ClearAllResponse.FromString, + _registered_method=True, + ) class MissionRawServerServiceServicer(object): - """Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). + """Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). Provides current mission item state, so the server can progress through missions. """ @@ -68,84 +78,89 @@ def SubscribeIncomingMission(self, request, context): Subscribe to when a new mission is uploaded (asynchronous). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeCurrentItemChanged(self, request, context): """ Subscribe to when a new current item is set """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetCurrentItemComplete(self, request, context): """ Set Current item as completed """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeClearAll(self, request, context): """ Subscribe when a MISSION_CLEAR_ALL is received """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_MissionRawServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeIncomingMission': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeIncomingMission, - request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeIncomingMissionRequest.FromString, - response_serializer=mission__raw__server_dot_mission__raw__server__pb2.IncomingMissionResponse.SerializeToString, - ), - 'SubscribeCurrentItemChanged': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeCurrentItemChanged, - request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeCurrentItemChangedRequest.FromString, - response_serializer=mission__raw__server_dot_mission__raw__server__pb2.CurrentItemChangedResponse.SerializeToString, - ), - 'SetCurrentItemComplete': grpc.unary_unary_rpc_method_handler( - servicer.SetCurrentItemComplete, - request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteRequest.FromString, - response_serializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteResponse.SerializeToString, - ), - 'SubscribeClearAll': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeClearAll, - request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeClearAllRequest.FromString, - response_serializer=mission__raw__server_dot_mission__raw__server__pb2.ClearAllResponse.SerializeToString, - ), + "SubscribeIncomingMission": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeIncomingMission, + request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeIncomingMissionRequest.FromString, + response_serializer=mission__raw__server_dot_mission__raw__server__pb2.IncomingMissionResponse.SerializeToString, + ), + "SubscribeCurrentItemChanged": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCurrentItemChanged, + request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeCurrentItemChangedRequest.FromString, + response_serializer=mission__raw__server_dot_mission__raw__server__pb2.CurrentItemChangedResponse.SerializeToString, + ), + "SetCurrentItemComplete": grpc.unary_unary_rpc_method_handler( + servicer.SetCurrentItemComplete, + request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteRequest.FromString, + response_serializer=mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteResponse.SerializeToString, + ), + "SubscribeClearAll": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeClearAll, + request_deserializer=mission__raw__server_dot_mission__raw__server__pb2.SubscribeClearAllRequest.FromString, + response_serializer=mission__raw__server_dot_mission__raw__server__pb2.ClearAllResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.mission_raw_server.MissionRawServerService', rpc_method_handlers) + "mavsdk.rpc.mission_raw_server.MissionRawServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.mission_raw_server.MissionRawServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.mission_raw_server.MissionRawServerService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class MissionRawServerService(object): - """Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). + """Acts as a vehicle and receives incoming missions from GCS (in raw MAVLINK format). Provides current mission item state, so the server can progress through missions. """ @staticmethod - def SubscribeIncomingMission(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeIncomingMission( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeIncomingMission', + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeIncomingMission", mission__raw__server_dot_mission__raw__server__pb2.SubscribeIncomingMissionRequest.SerializeToString, mission__raw__server_dot_mission__raw__server__pb2.IncomingMissionResponse.FromString, options, @@ -156,23 +171,26 @@ def SubscribeIncomingMission(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeCurrentItemChanged(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeCurrentItemChanged( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeCurrentItemChanged', + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeCurrentItemChanged", mission__raw__server_dot_mission__raw__server__pb2.SubscribeCurrentItemChangedRequest.SerializeToString, mission__raw__server_dot_mission__raw__server__pb2.CurrentItemChangedResponse.FromString, options, @@ -183,23 +201,26 @@ def SubscribeCurrentItemChanged(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetCurrentItemComplete(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetCurrentItemComplete( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SetCurrentItemComplete', + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SetCurrentItemComplete", mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteRequest.SerializeToString, mission__raw__server_dot_mission__raw__server__pb2.SetCurrentItemCompleteResponse.FromString, options, @@ -210,23 +231,26 @@ def SetCurrentItemComplete(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeClearAll(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeClearAll( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeClearAll', + "/mavsdk.rpc.mission_raw_server.MissionRawServerService/SubscribeClearAll", mission__raw__server_dot_mission__raw__server__pb2.SubscribeClearAllRequest.SerializeToString, mission__raw__server_dot_mission__raw__server__pb2.ClearAllResponse.FromString, options, @@ -237,4 +261,5 @@ def SubscribeClearAll(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/mocap.py b/mavsdk/mocap.py index c0f98e31..4ea44b07 100644 --- a/mavsdk/mocap.py +++ b/mavsdk/mocap.py @@ -8,980 +8,725 @@ class PositionBody: """ - Body position type + Body position type - Parameters - ---------- - x_m : float - X position in metres. + Parameters + ---------- + x_m : float + X position in metres. - y_m : float - Y position in metres. + y_m : float + Y position in metres. - z_m : float - Z position in metres. + z_m : float + Z position in metres. - """ - - + """ - def __init__( - self, - x_m, - y_m, - z_m): - """ Initializes the PositionBody object """ + def __init__(self, x_m, y_m, z_m): + """Initializes the PositionBody object""" self.x_m = x_m self.y_m = y_m self.z_m = z_m def __eq__(self, to_compare): - """ Checks if two PositionBody are the same """ + """Checks if two PositionBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionBody object - return \ - (self.x_m == to_compare.x_m) and \ - (self.y_m == to_compare.y_m) and \ - (self.z_m == to_compare.z_m) + return ( + (self.x_m == to_compare.x_m) + and (self.y_m == to_compare.y_m) + and (self.z_m == to_compare.z_m) + ) except AttributeError: return False def __str__(self): - """ PositionBody in string representation """ - struct_repr = ", ".join([ - "x_m: " + str(self.x_m), - "y_m: " + str(self.y_m), - "z_m: " + str(self.z_m) - ]) + """PositionBody in string representation""" + struct_repr = ", ".join( + ["x_m: " + str(self.x_m), "y_m: " + str(self.y_m), "z_m: " + str(self.z_m)] + ) return f"PositionBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionBody( - - rpcPositionBody.x_m, - - - rpcPositionBody.y_m, - - - rpcPositionBody.z_m - ) + rpcPositionBody.x_m, rpcPositionBody.y_m, rpcPositionBody.z_m + ) def translate_to_rpc(self, rpcPositionBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionBody.x_m = self.x_m - - - - - + rpcPositionBody.y_m = self.y_m - - - - - + rpcPositionBody.z_m = self.z_m - - - class AngleBody: """ - Body angle type + Body angle type - Parameters - ---------- - roll_rad : float - Roll angle in radians. + Parameters + ---------- + roll_rad : float + Roll angle in radians. - pitch_rad : float - Pitch angle in radians. + pitch_rad : float + Pitch angle in radians. - yaw_rad : float - Yaw angle in radians. + yaw_rad : float + Yaw angle in radians. - """ - - + """ - def __init__( - self, - roll_rad, - pitch_rad, - yaw_rad): - """ Initializes the AngleBody object """ + def __init__(self, roll_rad, pitch_rad, yaw_rad): + """Initializes the AngleBody object""" self.roll_rad = roll_rad self.pitch_rad = pitch_rad self.yaw_rad = yaw_rad def __eq__(self, to_compare): - """ Checks if two AngleBody are the same """ + """Checks if two AngleBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngleBody object - return \ - (self.roll_rad == to_compare.roll_rad) and \ - (self.pitch_rad == to_compare.pitch_rad) and \ - (self.yaw_rad == to_compare.yaw_rad) + return ( + (self.roll_rad == to_compare.roll_rad) + and (self.pitch_rad == to_compare.pitch_rad) + and (self.yaw_rad == to_compare.yaw_rad) + ) except AttributeError: return False def __str__(self): - """ AngleBody in string representation """ - struct_repr = ", ".join([ + """AngleBody in string representation""" + struct_repr = ", ".join( + [ "roll_rad: " + str(self.roll_rad), "pitch_rad: " + str(self.pitch_rad), - "yaw_rad: " + str(self.yaw_rad) - ]) + "yaw_rad: " + str(self.yaw_rad), + ] + ) return f"AngleBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngleBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngleBody( - - rpcAngleBody.roll_rad, - - - rpcAngleBody.pitch_rad, - - - rpcAngleBody.yaw_rad - ) + rpcAngleBody.roll_rad, rpcAngleBody.pitch_rad, rpcAngleBody.yaw_rad + ) def translate_to_rpc(self, rpcAngleBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngleBody.roll_rad = self.roll_rad - - - - - + rpcAngleBody.pitch_rad = self.pitch_rad - - - - - + rpcAngleBody.yaw_rad = self.yaw_rad - - - class SpeedBody: """ - Speed type, represented in the Body (X Y Z) frame and in metres/second. + Speed type, represented in the Body (X Y Z) frame and in metres/second. - Parameters - ---------- - x_m_s : float - Velocity in X in metres/second. + Parameters + ---------- + x_m_s : float + Velocity in X in metres/second. - y_m_s : float - Velocity in Y in metres/second. + y_m_s : float + Velocity in Y in metres/second. - z_m_s : float - Velocity in Z in metres/second. + z_m_s : float + Velocity in Z in metres/second. - """ - - + """ - def __init__( - self, - x_m_s, - y_m_s, - z_m_s): - """ Initializes the SpeedBody object """ + def __init__(self, x_m_s, y_m_s, z_m_s): + """Initializes the SpeedBody object""" self.x_m_s = x_m_s self.y_m_s = y_m_s self.z_m_s = z_m_s def __eq__(self, to_compare): - """ Checks if two SpeedBody are the same """ + """Checks if two SpeedBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # SpeedBody object - return \ - (self.x_m_s == to_compare.x_m_s) and \ - (self.y_m_s == to_compare.y_m_s) and \ - (self.z_m_s == to_compare.z_m_s) + return ( + (self.x_m_s == to_compare.x_m_s) + and (self.y_m_s == to_compare.y_m_s) + and (self.z_m_s == to_compare.z_m_s) + ) except AttributeError: return False def __str__(self): - """ SpeedBody in string representation """ - struct_repr = ", ".join([ + """SpeedBody in string representation""" + struct_repr = ", ".join( + [ "x_m_s: " + str(self.x_m_s), "y_m_s: " + str(self.y_m_s), - "z_m_s: " + str(self.z_m_s) - ]) + "z_m_s: " + str(self.z_m_s), + ] + ) return f"SpeedBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcSpeedBody): - """ Translates a gRPC struct to the SDK equivalent """ - return SpeedBody( - - rpcSpeedBody.x_m_s, - - - rpcSpeedBody.y_m_s, - - - rpcSpeedBody.z_m_s - ) + """Translates a gRPC struct to the SDK equivalent""" + return SpeedBody(rpcSpeedBody.x_m_s, rpcSpeedBody.y_m_s, rpcSpeedBody.z_m_s) def translate_to_rpc(self, rpcSpeedBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcSpeedBody.x_m_s = self.x_m_s - - - - - + rpcSpeedBody.y_m_s = self.y_m_s - - - - - + rpcSpeedBody.z_m_s = self.z_m_s - - - class SpeedNed: """ - Speed type, represented in NED (North East Down) coordinates. + Speed type, represented in NED (North East Down) coordinates. - Parameters - ---------- - north_m_s : float - Velocity North in metres/second. + Parameters + ---------- + north_m_s : float + Velocity North in metres/second. - east_m_s : float - Velocity East in metres/second. + east_m_s : float + Velocity East in metres/second. - down_m_s : float - Velocity Down in metres/second. + down_m_s : float + Velocity Down in metres/second. - """ - - + """ - def __init__( - self, - north_m_s, - east_m_s, - down_m_s): - """ Initializes the SpeedNed object """ + def __init__(self, north_m_s, east_m_s, down_m_s): + """Initializes the SpeedNed object""" self.north_m_s = north_m_s self.east_m_s = east_m_s self.down_m_s = down_m_s def __eq__(self, to_compare): - """ Checks if two SpeedNed are the same """ + """Checks if two SpeedNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # SpeedNed object - return \ - (self.north_m_s == to_compare.north_m_s) and \ - (self.east_m_s == to_compare.east_m_s) and \ - (self.down_m_s == to_compare.down_m_s) + return ( + (self.north_m_s == to_compare.north_m_s) + and (self.east_m_s == to_compare.east_m_s) + and (self.down_m_s == to_compare.down_m_s) + ) except AttributeError: return False def __str__(self): - """ SpeedNed in string representation """ - struct_repr = ", ".join([ + """SpeedNed in string representation""" + struct_repr = ", ".join( + [ "north_m_s: " + str(self.north_m_s), "east_m_s: " + str(self.east_m_s), - "down_m_s: " + str(self.down_m_s) - ]) + "down_m_s: " + str(self.down_m_s), + ] + ) return f"SpeedNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcSpeedNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return SpeedNed( - - rpcSpeedNed.north_m_s, - - - rpcSpeedNed.east_m_s, - - - rpcSpeedNed.down_m_s - ) + rpcSpeedNed.north_m_s, rpcSpeedNed.east_m_s, rpcSpeedNed.down_m_s + ) def translate_to_rpc(self, rpcSpeedNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcSpeedNed.north_m_s = self.north_m_s - - - - - + rpcSpeedNed.east_m_s = self.east_m_s - - - - - + rpcSpeedNed.down_m_s = self.down_m_s - - - class AngularVelocityBody: """ - Angular velocity type - - Parameters - ---------- - roll_rad_s : float - Roll angular velocity in radians/second. + Angular velocity type - pitch_rad_s : float - Pitch angular velocity in radians/second. + Parameters + ---------- + roll_rad_s : float + Roll angular velocity in radians/second. - yaw_rad_s : float - Yaw angular velocity in radians/second. + pitch_rad_s : float + Pitch angular velocity in radians/second. - """ + yaw_rad_s : float + Yaw angular velocity in radians/second. - + """ - def __init__( - self, - roll_rad_s, - pitch_rad_s, - yaw_rad_s): - """ Initializes the AngularVelocityBody object """ + def __init__(self, roll_rad_s, pitch_rad_s, yaw_rad_s): + """Initializes the AngularVelocityBody object""" self.roll_rad_s = roll_rad_s self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s def __eq__(self, to_compare): - """ Checks if two AngularVelocityBody are the same """ + """Checks if two AngularVelocityBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngularVelocityBody object - return \ - (self.roll_rad_s == to_compare.roll_rad_s) and \ - (self.pitch_rad_s == to_compare.pitch_rad_s) and \ - (self.yaw_rad_s == to_compare.yaw_rad_s) + return ( + (self.roll_rad_s == to_compare.roll_rad_s) + and (self.pitch_rad_s == to_compare.pitch_rad_s) + and (self.yaw_rad_s == to_compare.yaw_rad_s) + ) except AttributeError: return False def __str__(self): - """ AngularVelocityBody in string representation """ - struct_repr = ", ".join([ + """AngularVelocityBody in string representation""" + struct_repr = ", ".join( + [ "roll_rad_s: " + str(self.roll_rad_s), "pitch_rad_s: " + str(self.pitch_rad_s), - "yaw_rad_s: " + str(self.yaw_rad_s) - ]) + "yaw_rad_s: " + str(self.yaw_rad_s), + ] + ) return f"AngularVelocityBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngularVelocityBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngularVelocityBody( - - rpcAngularVelocityBody.roll_rad_s, - - - rpcAngularVelocityBody.pitch_rad_s, - - - rpcAngularVelocityBody.yaw_rad_s - ) + rpcAngularVelocityBody.roll_rad_s, + rpcAngularVelocityBody.pitch_rad_s, + rpcAngularVelocityBody.yaw_rad_s, + ) def translate_to_rpc(self, rpcAngularVelocityBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngularVelocityBody.roll_rad_s = self.roll_rad_s - - - - - + rpcAngularVelocityBody.pitch_rad_s = self.pitch_rad_s - - - - - + rpcAngularVelocityBody.yaw_rad_s = self.yaw_rad_s - - - class Covariance: """ - Covariance type. - Row-major representation of a 6x6 cross-covariance matrix upper - right triangle. - Needs to be 21 entries or 1 entry with NaN if unknown. - - Parameters - ---------- - covariance_matrix : [float] - The covariance matrix + Covariance type. + Row-major representation of a 6x6 cross-covariance matrix upper + right triangle. + Needs to be 21 entries or 1 entry with NaN if unknown. - """ + Parameters + ---------- + covariance_matrix : [float] + The covariance matrix - + """ - def __init__( - self, - covariance_matrix): - """ Initializes the Covariance object """ + def __init__(self, covariance_matrix): + """Initializes the Covariance object""" self.covariance_matrix = covariance_matrix def __eq__(self, to_compare): - """ Checks if two Covariance are the same """ + """Checks if two Covariance are the same""" try: # Try to compare - this likely fails when it is compared to a non # Covariance object - return \ - (self.covariance_matrix == to_compare.covariance_matrix) + return self.covariance_matrix == to_compare.covariance_matrix except AttributeError: return False def __str__(self): - """ Covariance in string representation """ - struct_repr = ", ".join([ - "covariance_matrix: " + str(self.covariance_matrix) - ]) + """Covariance in string representation""" + struct_repr = ", ".join(["covariance_matrix: " + str(self.covariance_matrix)]) return f"Covariance: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCovariance): - """ Translates a gRPC struct to the SDK equivalent """ - return Covariance( - - rpcCovariance.covariance_matrix - ) + """Translates a gRPC struct to the SDK equivalent""" + return Covariance(rpcCovariance.covariance_matrix) def translate_to_rpc(self, rpcCovariance): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - for elem in self.covariance_matrix: - rpcCovariance.covariance_matrix.append(elem) - - - + rpcCovariance.covariance_matrix.append(elem) class Quaternion: """ - Quaternion type. - - All rotations and axis systems follow the right-hand rule. - The Hamilton quaternion product definition is used. - A zero-rotation quaternion is represented by (1,0,0,0). - The quaternion could also be written as w + xi + yj + zk. + Quaternion type. - For more info see: https://en.wikipedia.org/wiki/Quaternion + All rotations and axis systems follow the right-hand rule. + The Hamilton quaternion product definition is used. + A zero-rotation quaternion is represented by (1,0,0,0). + The quaternion could also be written as w + xi + yj + zk. - Parameters - ---------- - w : float - Quaternion entry 0, also denoted as a + For more info see: https://en.wikipedia.org/wiki/Quaternion - x : float - Quaternion entry 1, also denoted as b + Parameters + ---------- + w : float + Quaternion entry 0, also denoted as a - y : float - Quaternion entry 2, also denoted as c + x : float + Quaternion entry 1, also denoted as b - z : float - Quaternion entry 3, also denoted as d + y : float + Quaternion entry 2, also denoted as c - """ + z : float + Quaternion entry 3, also denoted as d - + """ - def __init__( - self, - w, - x, - y, - z): - """ Initializes the Quaternion object """ + def __init__(self, w, x, y, z): + """Initializes the Quaternion object""" self.w = w self.x = x self.y = y self.z = z def __eq__(self, to_compare): - """ Checks if two Quaternion are the same """ + """Checks if two Quaternion are the same""" try: # Try to compare - this likely fails when it is compared to a non # Quaternion object - return \ - (self.w == to_compare.w) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) + return ( + (self.w == to_compare.w) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + ) except AttributeError: return False def __str__(self): - """ Quaternion in string representation """ - struct_repr = ", ".join([ + """Quaternion in string representation""" + struct_repr = ", ".join( + [ "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), - "z: " + str(self.z) - ]) + "z: " + str(self.z), + ] + ) return f"Quaternion: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcQuaternion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Quaternion( - - rpcQuaternion.w, - - - rpcQuaternion.x, - - - rpcQuaternion.y, - - - rpcQuaternion.z - ) + rpcQuaternion.w, rpcQuaternion.x, rpcQuaternion.y, rpcQuaternion.z + ) def translate_to_rpc(self, rpcQuaternion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcQuaternion.w = self.w - - - - - + rpcQuaternion.x = self.x - - - - - + rpcQuaternion.y = self.y - - - - - + rpcQuaternion.z = self.z - - - class VisionPositionEstimate: """ - Global position/attitude estimate from a vision source. + Global position/attitude estimate from a vision source. - Parameters - ---------- - time_usec : uint64_t - PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp) + Parameters + ---------- + time_usec : uint64_t + PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp) - position_body : PositionBody - Global position (m) + position_body : PositionBody + Global position (m) - angle_body : AngleBody - Body angle (rad). + angle_body : AngleBody + Body angle (rad). - pose_covariance : Covariance - Pose cross-covariance matrix. + pose_covariance : Covariance + Pose cross-covariance matrix. - """ - - + """ - def __init__( - self, - time_usec, - position_body, - angle_body, - pose_covariance): - """ Initializes the VisionPositionEstimate object """ + def __init__(self, time_usec, position_body, angle_body, pose_covariance): + """Initializes the VisionPositionEstimate object""" self.time_usec = time_usec self.position_body = position_body self.angle_body = angle_body self.pose_covariance = pose_covariance def __eq__(self, to_compare): - """ Checks if two VisionPositionEstimate are the same """ + """Checks if two VisionPositionEstimate are the same""" try: # Try to compare - this likely fails when it is compared to a non # VisionPositionEstimate object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.position_body == to_compare.position_body) and \ - (self.angle_body == to_compare.angle_body) and \ - (self.pose_covariance == to_compare.pose_covariance) + return ( + (self.time_usec == to_compare.time_usec) + and (self.position_body == to_compare.position_body) + and (self.angle_body == to_compare.angle_body) + and (self.pose_covariance == to_compare.pose_covariance) + ) except AttributeError: return False def __str__(self): - """ VisionPositionEstimate in string representation """ - struct_repr = ", ".join([ + """VisionPositionEstimate in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "position_body: " + str(self.position_body), "angle_body: " + str(self.angle_body), - "pose_covariance: " + str(self.pose_covariance) - ]) + "pose_covariance: " + str(self.pose_covariance), + ] + ) return f"VisionPositionEstimate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVisionPositionEstimate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VisionPositionEstimate( - - rpcVisionPositionEstimate.time_usec, - - - PositionBody.translate_from_rpc(rpcVisionPositionEstimate.position_body), - - - AngleBody.translate_from_rpc(rpcVisionPositionEstimate.angle_body), - - - Covariance.translate_from_rpc(rpcVisionPositionEstimate.pose_covariance) - ) + rpcVisionPositionEstimate.time_usec, + PositionBody.translate_from_rpc(rpcVisionPositionEstimate.position_body), + AngleBody.translate_from_rpc(rpcVisionPositionEstimate.angle_body), + Covariance.translate_from_rpc(rpcVisionPositionEstimate.pose_covariance), + ) def translate_to_rpc(self, rpcVisionPositionEstimate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVisionPositionEstimate.time_usec = self.time_usec - - - - - + self.position_body.translate_to_rpc(rpcVisionPositionEstimate.position_body) - - - - - + self.angle_body.translate_to_rpc(rpcVisionPositionEstimate.angle_body) - - - - - + self.pose_covariance.translate_to_rpc(rpcVisionPositionEstimate.pose_covariance) - - - class VisionSpeedEstimate: """ - Global speed estimate from a vision source. + Global speed estimate from a vision source. - Parameters - ---------- - time_usec : uint64_t - Timestamp UNIX Epoch time (0 to use Backend timestamp) + Parameters + ---------- + time_usec : uint64_t + Timestamp UNIX Epoch time (0 to use Backend timestamp) - speed_ned : SpeedNed - Global speed (m/s) + speed_ned : SpeedNed + Global speed (m/s) - speed_covariance : Covariance - Linear velocity cross-covariance matrix. + speed_covariance : Covariance + Linear velocity cross-covariance matrix. - """ - - + """ - def __init__( - self, - time_usec, - speed_ned, - speed_covariance): - """ Initializes the VisionSpeedEstimate object """ + def __init__(self, time_usec, speed_ned, speed_covariance): + """Initializes the VisionSpeedEstimate object""" self.time_usec = time_usec self.speed_ned = speed_ned self.speed_covariance = speed_covariance def __eq__(self, to_compare): - """ Checks if two VisionSpeedEstimate are the same """ + """Checks if two VisionSpeedEstimate are the same""" try: # Try to compare - this likely fails when it is compared to a non # VisionSpeedEstimate object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.speed_ned == to_compare.speed_ned) and \ - (self.speed_covariance == to_compare.speed_covariance) + return ( + (self.time_usec == to_compare.time_usec) + and (self.speed_ned == to_compare.speed_ned) + and (self.speed_covariance == to_compare.speed_covariance) + ) except AttributeError: return False def __str__(self): - """ VisionSpeedEstimate in string representation """ - struct_repr = ", ".join([ + """VisionSpeedEstimate in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "speed_ned: " + str(self.speed_ned), - "speed_covariance: " + str(self.speed_covariance) - ]) + "speed_covariance: " + str(self.speed_covariance), + ] + ) return f"VisionSpeedEstimate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVisionSpeedEstimate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VisionSpeedEstimate( - - rpcVisionSpeedEstimate.time_usec, - - - SpeedNed.translate_from_rpc(rpcVisionSpeedEstimate.speed_ned), - - - Covariance.translate_from_rpc(rpcVisionSpeedEstimate.speed_covariance) - ) + rpcVisionSpeedEstimate.time_usec, + SpeedNed.translate_from_rpc(rpcVisionSpeedEstimate.speed_ned), + Covariance.translate_from_rpc(rpcVisionSpeedEstimate.speed_covariance), + ) def translate_to_rpc(self, rpcVisionSpeedEstimate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVisionSpeedEstimate.time_usec = self.time_usec - - - - - + self.speed_ned.translate_to_rpc(rpcVisionSpeedEstimate.speed_ned) - - - - - + self.speed_covariance.translate_to_rpc(rpcVisionSpeedEstimate.speed_covariance) - - - class AttitudePositionMocap: """ - Motion capture attitude and position + Motion capture attitude and position - Parameters - ---------- - time_usec : uint64_t - PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp) + Parameters + ---------- + time_usec : uint64_t + PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp) - q : Quaternion - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + q : Quaternion + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - position_body : PositionBody - Body Position (NED) + position_body : PositionBody + Body Position (NED) - pose_covariance : Covariance - Pose cross-covariance matrix. + pose_covariance : Covariance + Pose cross-covariance matrix. - """ - - + """ - def __init__( - self, - time_usec, - q, - position_body, - pose_covariance): - """ Initializes the AttitudePositionMocap object """ + def __init__(self, time_usec, q, position_body, pose_covariance): + """Initializes the AttitudePositionMocap object""" self.time_usec = time_usec self.q = q self.position_body = position_body self.pose_covariance = pose_covariance def __eq__(self, to_compare): - """ Checks if two AttitudePositionMocap are the same """ + """Checks if two AttitudePositionMocap are the same""" try: # Try to compare - this likely fails when it is compared to a non # AttitudePositionMocap object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.q == to_compare.q) and \ - (self.position_body == to_compare.position_body) and \ - (self.pose_covariance == to_compare.pose_covariance) + return ( + (self.time_usec == to_compare.time_usec) + and (self.q == to_compare.q) + and (self.position_body == to_compare.position_body) + and (self.pose_covariance == to_compare.pose_covariance) + ) except AttributeError: return False def __str__(self): - """ AttitudePositionMocap in string representation """ - struct_repr = ", ".join([ + """AttitudePositionMocap in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "q: " + str(self.q), "position_body: " + str(self.position_body), - "pose_covariance: " + str(self.pose_covariance) - ]) + "pose_covariance: " + str(self.pose_covariance), + ] + ) return f"AttitudePositionMocap: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAttitudePositionMocap): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AttitudePositionMocap( - - rpcAttitudePositionMocap.time_usec, - - - Quaternion.translate_from_rpc(rpcAttitudePositionMocap.q), - - - PositionBody.translate_from_rpc(rpcAttitudePositionMocap.position_body), - - - Covariance.translate_from_rpc(rpcAttitudePositionMocap.pose_covariance) - ) + rpcAttitudePositionMocap.time_usec, + Quaternion.translate_from_rpc(rpcAttitudePositionMocap.q), + PositionBody.translate_from_rpc(rpcAttitudePositionMocap.position_body), + Covariance.translate_from_rpc(rpcAttitudePositionMocap.pose_covariance), + ) def translate_to_rpc(self, rpcAttitudePositionMocap): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAttitudePositionMocap.time_usec = self.time_usec - - - - - + self.q.translate_to_rpc(rpcAttitudePositionMocap.q) - - - - - + self.position_body.translate_to_rpc(rpcAttitudePositionMocap.position_body) - - - - - + self.pose_covariance.translate_to_rpc(rpcAttitudePositionMocap.pose_covariance) - - - class Odometry: """ - Odometry message to communicate odometry information with an external interface. + Odometry message to communicate odometry information with an external interface. - Parameters - ---------- - time_usec : uint64_t - Timestamp (0 to use Backend timestamp). + Parameters + ---------- + time_usec : uint64_t + Timestamp (0 to use Backend timestamp). - frame_id : MavFrame - Coordinate frame of reference for the pose data. + frame_id : MavFrame + Coordinate frame of reference for the pose data. - position_body : PositionBody - Body Position. + position_body : PositionBody + Body Position. - q : Quaternion - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). + q : Quaternion + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). - speed_body : SpeedBody - Linear speed (m/s). + speed_body : SpeedBody + Linear speed (m/s). - angular_velocity_body : AngularVelocityBody - Angular speed (rad/s). + angular_velocity_body : AngularVelocityBody + Angular speed (rad/s). - pose_covariance : Covariance - Pose cross-covariance matrix. + pose_covariance : Covariance + Pose cross-covariance matrix. - velocity_covariance : Covariance - Velocity cross-covariance matrix. + velocity_covariance : Covariance + Velocity cross-covariance matrix. - """ + """ - - class MavFrame(Enum): """ - Mavlink frame id + Mavlink frame id - Values - ------ - MOCAP_NED - MAVLink number: 14. Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down). + Values + ------ + MOCAP_NED + MAVLink number: 14. Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down). - LOCAL_FRD - MAVLink number: 20. Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). Replacement for MAV_FRAME_MOCAP_NED, MAV_FRAME_VISION_NED, MAV_FRAME_ESTIM_NED. + LOCAL_FRD + MAVLink number: 20. Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). Replacement for MAV_FRAME_MOCAP_NED, MAV_FRAME_VISION_NED, MAV_FRAME_ESTIM_NED. - """ + """ - MOCAP_NED = 0 LOCAL_FRD = 1 @@ -993,7 +738,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mocap_pb2.Odometry.MAV_FRAME_MOCAP_NED: return Odometry.MavFrame.MOCAP_NED if rpc_enum_value == mocap_pb2.Odometry.MAV_FRAME_LOCAL_FRD: @@ -1001,19 +746,19 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - def __init__( - self, - time_usec, - frame_id, - position_body, - q, - speed_body, - angular_velocity_body, - pose_covariance, - velocity_covariance): - """ Initializes the Odometry object """ + self, + time_usec, + frame_id, + position_body, + q, + speed_body, + angular_velocity_body, + pose_covariance, + velocity_covariance, + ): + """Initializes the Odometry object""" self.time_usec = time_usec self.frame_id = frame_id self.position_body = position_body @@ -1024,26 +769,28 @@ def __init__( self.velocity_covariance = velocity_covariance def __eq__(self, to_compare): - """ Checks if two Odometry are the same """ + """Checks if two Odometry are the same""" try: # Try to compare - this likely fails when it is compared to a non # Odometry object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.frame_id == to_compare.frame_id) and \ - (self.position_body == to_compare.position_body) and \ - (self.q == to_compare.q) and \ - (self.speed_body == to_compare.speed_body) and \ - (self.angular_velocity_body == to_compare.angular_velocity_body) and \ - (self.pose_covariance == to_compare.pose_covariance) and \ - (self.velocity_covariance == to_compare.velocity_covariance) + return ( + (self.time_usec == to_compare.time_usec) + and (self.frame_id == to_compare.frame_id) + and (self.position_body == to_compare.position_body) + and (self.q == to_compare.q) + and (self.speed_body == to_compare.speed_body) + and (self.angular_velocity_body == to_compare.angular_velocity_body) + and (self.pose_covariance == to_compare.pose_covariance) + and (self.velocity_covariance == to_compare.velocity_covariance) + ) except AttributeError: return False def __str__(self): - """ Odometry in string representation """ - struct_repr = ", ".join([ + """Odometry in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "frame_id: " + str(self.frame_id), "position_body: " + str(self.position_body), @@ -1051,137 +798,86 @@ def __str__(self): "speed_body: " + str(self.speed_body), "angular_velocity_body: " + str(self.angular_velocity_body), "pose_covariance: " + str(self.pose_covariance), - "velocity_covariance: " + str(self.velocity_covariance) - ]) + "velocity_covariance: " + str(self.velocity_covariance), + ] + ) return f"Odometry: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcOdometry): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Odometry( - - rpcOdometry.time_usec, - - - Odometry.MavFrame.translate_from_rpc(rpcOdometry.frame_id), - - - PositionBody.translate_from_rpc(rpcOdometry.position_body), - - - Quaternion.translate_from_rpc(rpcOdometry.q), - - - SpeedBody.translate_from_rpc(rpcOdometry.speed_body), - - - AngularVelocityBody.translate_from_rpc(rpcOdometry.angular_velocity_body), - - - Covariance.translate_from_rpc(rpcOdometry.pose_covariance), - - - Covariance.translate_from_rpc(rpcOdometry.velocity_covariance) - ) + rpcOdometry.time_usec, + Odometry.MavFrame.translate_from_rpc(rpcOdometry.frame_id), + PositionBody.translate_from_rpc(rpcOdometry.position_body), + Quaternion.translate_from_rpc(rpcOdometry.q), + SpeedBody.translate_from_rpc(rpcOdometry.speed_body), + AngularVelocityBody.translate_from_rpc(rpcOdometry.angular_velocity_body), + Covariance.translate_from_rpc(rpcOdometry.pose_covariance), + Covariance.translate_from_rpc(rpcOdometry.velocity_covariance), + ) def translate_to_rpc(self, rpcOdometry): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcOdometry.time_usec = self.time_usec - - - - - + rpcOdometry.frame_id = self.frame_id.translate_to_rpc() - - - - - + self.position_body.translate_to_rpc(rpcOdometry.position_body) - - - - - + self.q.translate_to_rpc(rpcOdometry.q) - - - - - + self.speed_body.translate_to_rpc(rpcOdometry.speed_body) - - - - - + self.angular_velocity_body.translate_to_rpc(rpcOdometry.angular_velocity_body) - - - - - + self.pose_covariance.translate_to_rpc(rpcOdometry.pose_covariance) - - - - - + self.velocity_covariance.translate_to_rpc(rpcOdometry.velocity_covariance) - - - class MocapResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for mocap requests + Possible results returned for mocap requests - Values - ------ - UNKNOWN - Unknown error + Values + ------ + UNKNOWN + Unknown error - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - INVALID_REQUEST_DATA - Invalid request data + INVALID_REQUEST_DATA + Invalid request data - UNSUPPORTED - Function unsupported + UNSUPPORTED + Function unsupported - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -1205,7 +901,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == mocap_pb2.MocapResult.RESULT_UNKNOWN: return MocapResult.Result.UNKNOWN if rpc_enum_value == mocap_pb2.MocapResult.RESULT_SUCCESS: @@ -1221,69 +917,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the MocapResult object """ + def __init__(self, result, result_str): + """Initializes the MocapResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two MocapResult are the same """ + """Checks if two MocapResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # MocapResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ MocapResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """MocapResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"MocapResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMocapResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MocapResult( - - MocapResult.Result.translate_from_rpc(rpcMocapResult.result), - - - rpcMocapResult.result_str - ) + MocapResult.Result.translate_from_rpc(rpcMocapResult.result), + rpcMocapResult.result_str, + ) def translate_to_rpc(self, rpcMocapResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMocapResult.result = self.result.translate_to_rpc() - - - - - - rpcMocapResult.result_str = self.result_str - - - + rpcMocapResult.result_str = self.result_str class MocapError(Exception): - """ Raised when a MocapResult is a fail code """ + """Raised when a MocapResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -1296,138 +973,130 @@ def __str__(self): class Mocap(AsyncBase): """ - Allows interfacing a vehicle with a motion capture system in - order to allow navigation without global positioning sources available - (e.g. indoors, or when flying under a bridge. etc.). + Allows interfacing a vehicle with a motion capture system in + order to allow navigation without global positioning sources available + (e.g. indoors, or when flying under a bridge. etc.). - Generated by dcsdkgen - MAVSDK Mocap API + Generated by dcsdkgen - MAVSDK Mocap API """ # Plugin name name = "Mocap" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = mocap_pb2_grpc.MocapServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return MocapResult.translate_from_rpc(response.mocap_result) - async def set_vision_position_estimate(self, vision_position_estimate): """ - Send Global position/attitude estimate from a vision source. + Send Global position/attitude estimate from a vision source. - Parameters - ---------- - vision_position_estimate : VisionPositionEstimate - The vision position estimate + Parameters + ---------- + vision_position_estimate : VisionPositionEstimate + The vision position estimate - Raises - ------ - MocapError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MocapError + If the request fails. The error contains the reason for the failure. """ request = mocap_pb2.SetVisionPositionEstimateRequest() - + vision_position_estimate.translate_to_rpc(request.vision_position_estimate) - - + response = await self._stub.SetVisionPositionEstimate(request) - result = self._extract_result(response) if result.result != MocapResult.Result.SUCCESS: - raise MocapError(result, "set_vision_position_estimate()", vision_position_estimate) - + raise MocapError( + result, "set_vision_position_estimate()", vision_position_estimate + ) async def set_vision_speed_estimate(self, vision_speed_estimate): """ - Send Global speed estimate from a vision source. + Send Global speed estimate from a vision source. - Parameters - ---------- - vision_speed_estimate : VisionSpeedEstimate - The vision speed estimate + Parameters + ---------- + vision_speed_estimate : VisionSpeedEstimate + The vision speed estimate - Raises - ------ - MocapError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MocapError + If the request fails. The error contains the reason for the failure. """ request = mocap_pb2.SetVisionSpeedEstimateRequest() - + vision_speed_estimate.translate_to_rpc(request.vision_speed_estimate) - - + response = await self._stub.SetVisionSpeedEstimate(request) - result = self._extract_result(response) if result.result != MocapResult.Result.SUCCESS: - raise MocapError(result, "set_vision_speed_estimate()", vision_speed_estimate) - + raise MocapError( + result, "set_vision_speed_estimate()", vision_speed_estimate + ) async def set_attitude_position_mocap(self, attitude_position_mocap): """ - Send motion capture attitude and position. + Send motion capture attitude and position. - Parameters - ---------- - attitude_position_mocap : AttitudePositionMocap - The attitude and position data + Parameters + ---------- + attitude_position_mocap : AttitudePositionMocap + The attitude and position data - Raises - ------ - MocapError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MocapError + If the request fails. The error contains the reason for the failure. """ request = mocap_pb2.SetAttitudePositionMocapRequest() - + attitude_position_mocap.translate_to_rpc(request.attitude_position_mocap) - - + response = await self._stub.SetAttitudePositionMocap(request) - result = self._extract_result(response) if result.result != MocapResult.Result.SUCCESS: - raise MocapError(result, "set_attitude_position_mocap()", attitude_position_mocap) - + raise MocapError( + result, "set_attitude_position_mocap()", attitude_position_mocap + ) async def set_odometry(self, odometry): """ - Send odometry information with an external interface. + Send odometry information with an external interface. - Parameters - ---------- - odometry : Odometry - The odometry data + Parameters + ---------- + odometry : Odometry + The odometry data - Raises - ------ - MocapError - If the request fails. The error contains the reason for the failure. + Raises + ------ + MocapError + If the request fails. The error contains the reason for the failure. """ request = mocap_pb2.SetOdometryRequest() - + odometry.translate_to_rpc(request.odometry) - - + response = await self._stub.SetOdometry(request) - result = self._extract_result(response) if result.result != MocapResult.Result.SUCCESS: raise MocapError(result, "set_odometry()", odometry) - \ No newline at end of file diff --git a/mavsdk/mocap_pb2.py b/mavsdk/mocap_pb2.py index c55745de..27d8aac4 100644 --- a/mavsdk/mocap_pb2.py +++ b/mavsdk/mocap_pb2.py @@ -4,18 +4,15 @@ # source: mocap/mocap.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'mocap/mocap.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "mocap/mocap.proto" ) # @@protoc_insertion_point(imports) @@ -25,66 +22,82 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x11mocap/mocap.proto\x12\x10mavsdk.rpc.mocap\x1a\x14mavsdk_options.proto\"n\n SetVisionPositionEstimateRequest\x12J\n\x18vision_position_estimate\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mocap.VisionPositionEstimate\"X\n!SetVisionPositionEstimateResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult\"e\n\x1dSetVisionSpeedEstimateRequest\x12\x44\n\x15vision_speed_estimate\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.mocap.VisionSpeedEstimate\"U\n\x1eSetVisionSpeedEstimateResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult\"k\n\x1fSetAttitudePositionMocapRequest\x12H\n\x17\x61ttitude_position_mocap\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.mocap.AttitudePositionMocap\"W\n SetAttitudePositionMocapResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult\"B\n\x12SetOdometryRequest\x12,\n\x08odometry\x18\x01 \x01(\x0b\x32\x1a.mavsdk.rpc.mocap.Odometry\"J\n\x13SetOdometryResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult\"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02\"A\n\tAngleBody\x12\x10\n\x08roll_rad\x18\x01 \x01(\x02\x12\x11\n\tpitch_rad\x18\x02 \x01(\x02\x12\x0f\n\x07yaw_rad\x18\x03 \x01(\x02\"8\n\tSpeedBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02\"A\n\x08SpeedNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\"Q\n\x13\x41ngularVelocityBody\x12\x12\n\nroll_rad_s\x18\x01 \x01(\x02\x12\x13\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x12\x11\n\tyaw_rad_s\x18\x03 \x01(\x02\"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02\"8\n\nQuaternion\x12\t\n\x01w\x18\x01 \x01(\x02\x12\t\n\x01x\x18\x02 \x01(\x02\x12\t\n\x01y\x18\x03 \x01(\x02\x12\t\n\x01z\x18\x04 \x01(\x02\"\xca\x01\n\x16VisionPositionEstimate\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x35\n\rposition_body\x18\x02 \x01(\x0b\x32\x1e.mavsdk.rpc.mocap.PositionBody\x12/\n\nangle_body\x18\x03 \x01(\x0b\x32\x1b.mavsdk.rpc.mocap.AngleBody\x12\x35\n\x0fpose_covariance\x18\x04 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance\"\x8f\x01\n\x13VisionSpeedEstimate\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12-\n\tspeed_ned\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.mocap.SpeedNed\x12\x36\n\x10speed_covariance\x18\x03 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance\"\xc1\x01\n\x15\x41ttitudePositionMocap\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\'\n\x01q\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Quaternion\x12\x35\n\rposition_body\x18\x03 \x01(\x0b\x32\x1e.mavsdk.rpc.mocap.PositionBody\x12\x35\n\x0fpose_covariance\x18\x04 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance\"\xdb\x03\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x35\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32#.mavsdk.rpc.mocap.Odometry.MavFrame\x12\x35\n\rposition_body\x18\x03 \x01(\x0b\x32\x1e.mavsdk.rpc.mocap.PositionBody\x12\'\n\x01q\x18\x04 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Quaternion\x12/\n\nspeed_body\x18\x05 \x01(\x0b\x32\x1b.mavsdk.rpc.mocap.SpeedBody\x12\x44\n\x15\x61ngular_velocity_body\x18\x06 \x01(\x0b\x32%.mavsdk.rpc.mocap.AngularVelocityBody\x12\x35\n\x0fpose_covariance\x18\x07 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance\x12\x39\n\x13velocity_covariance\x18\x08 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance\"<\n\x08MavFrame\x12\x17\n\x13MAV_FRAME_MOCAP_NED\x10\x00\x12\x17\n\x13MAV_FRAME_LOCAL_FRD\x10\x01\"\xf6\x01\n\x0bMocapResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.mocap.MocapResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\x9c\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\x1f\n\x1bRESULT_INVALID_REQUEST_DATA\x10\x04\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x05\x32\x8b\x04\n\x0cMocapService\x12\x8a\x01\n\x19SetVisionPositionEstimate\x12\x32.mavsdk.rpc.mocap.SetVisionPositionEstimateRequest\x1a\x33.mavsdk.rpc.mocap.SetVisionPositionEstimateResponse\"\x04\x80\xb5\x18\x01\x12\x81\x01\n\x16SetVisionSpeedEstimate\x12/.mavsdk.rpc.mocap.SetVisionSpeedEstimateRequest\x1a\x30.mavsdk.rpc.mocap.SetVisionSpeedEstimateResponse\"\x04\x80\xb5\x18\x01\x12\x87\x01\n\x18SetAttitudePositionMocap\x12\x31.mavsdk.rpc.mocap.SetAttitudePositionMocapRequest\x1a\x32.mavsdk.rpc.mocap.SetAttitudePositionMocapResponse\"\x04\x80\xb5\x18\x01\x12`\n\x0bSetOdometry\x12$.mavsdk.rpc.mocap.SetOdometryRequest\x1a%.mavsdk.rpc.mocap.SetOdometryResponse\"\x04\x80\xb5\x18\x01\x42\x1d\n\x0fio.mavsdk.mocapB\nMocapProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x11mocap/mocap.proto\x12\x10mavsdk.rpc.mocap\x1a\x14mavsdk_options.proto"n\n SetVisionPositionEstimateRequest\x12J\n\x18vision_position_estimate\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.mocap.VisionPositionEstimate"X\n!SetVisionPositionEstimateResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult"e\n\x1dSetVisionSpeedEstimateRequest\x12\x44\n\x15vision_speed_estimate\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.mocap.VisionSpeedEstimate"U\n\x1eSetVisionSpeedEstimateResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult"k\n\x1fSetAttitudePositionMocapRequest\x12H\n\x17\x61ttitude_position_mocap\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.mocap.AttitudePositionMocap"W\n SetAttitudePositionMocapResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult"B\n\x12SetOdometryRequest\x12,\n\x08odometry\x18\x01 \x01(\x0b\x32\x1a.mavsdk.rpc.mocap.Odometry"J\n\x13SetOdometryResponse\x12\x33\n\x0cmocap_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.mocap.MocapResult"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02"A\n\tAngleBody\x12\x10\n\x08roll_rad\x18\x01 \x01(\x02\x12\x11\n\tpitch_rad\x18\x02 \x01(\x02\x12\x0f\n\x07yaw_rad\x18\x03 \x01(\x02"8\n\tSpeedBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02"A\n\x08SpeedNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02"Q\n\x13\x41ngularVelocityBody\x12\x12\n\nroll_rad_s\x18\x01 \x01(\x02\x12\x13\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x12\x11\n\tyaw_rad_s\x18\x03 \x01(\x02"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02"8\n\nQuaternion\x12\t\n\x01w\x18\x01 \x01(\x02\x12\t\n\x01x\x18\x02 \x01(\x02\x12\t\n\x01y\x18\x03 \x01(\x02\x12\t\n\x01z\x18\x04 \x01(\x02"\xca\x01\n\x16VisionPositionEstimate\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x35\n\rposition_body\x18\x02 \x01(\x0b\x32\x1e.mavsdk.rpc.mocap.PositionBody\x12/\n\nangle_body\x18\x03 \x01(\x0b\x32\x1b.mavsdk.rpc.mocap.AngleBody\x12\x35\n\x0fpose_covariance\x18\x04 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance"\x8f\x01\n\x13VisionSpeedEstimate\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12-\n\tspeed_ned\x18\x02 \x01(\x0b\x32\x1a.mavsdk.rpc.mocap.SpeedNed\x12\x36\n\x10speed_covariance\x18\x03 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance"\xc1\x01\n\x15\x41ttitudePositionMocap\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\'\n\x01q\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Quaternion\x12\x35\n\rposition_body\x18\x03 \x01(\x0b\x32\x1e.mavsdk.rpc.mocap.PositionBody\x12\x35\n\x0fpose_covariance\x18\x04 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance"\xdb\x03\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x35\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32#.mavsdk.rpc.mocap.Odometry.MavFrame\x12\x35\n\rposition_body\x18\x03 \x01(\x0b\x32\x1e.mavsdk.rpc.mocap.PositionBody\x12\'\n\x01q\x18\x04 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Quaternion\x12/\n\nspeed_body\x18\x05 \x01(\x0b\x32\x1b.mavsdk.rpc.mocap.SpeedBody\x12\x44\n\x15\x61ngular_velocity_body\x18\x06 \x01(\x0b\x32%.mavsdk.rpc.mocap.AngularVelocityBody\x12\x35\n\x0fpose_covariance\x18\x07 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance\x12\x39\n\x13velocity_covariance\x18\x08 \x01(\x0b\x32\x1c.mavsdk.rpc.mocap.Covariance"<\n\x08MavFrame\x12\x17\n\x13MAV_FRAME_MOCAP_NED\x10\x00\x12\x17\n\x13MAV_FRAME_LOCAL_FRD\x10\x01"\xf6\x01\n\x0bMocapResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.mocap.MocapResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\x9c\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\x1f\n\x1bRESULT_INVALID_REQUEST_DATA\x10\x04\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x05\x32\x8b\x04\n\x0cMocapService\x12\x8a\x01\n\x19SetVisionPositionEstimate\x12\x32.mavsdk.rpc.mocap.SetVisionPositionEstimateRequest\x1a\x33.mavsdk.rpc.mocap.SetVisionPositionEstimateResponse"\x04\x80\xb5\x18\x01\x12\x81\x01\n\x16SetVisionSpeedEstimate\x12/.mavsdk.rpc.mocap.SetVisionSpeedEstimateRequest\x1a\x30.mavsdk.rpc.mocap.SetVisionSpeedEstimateResponse"\x04\x80\xb5\x18\x01\x12\x87\x01\n\x18SetAttitudePositionMocap\x12\x31.mavsdk.rpc.mocap.SetAttitudePositionMocapRequest\x1a\x32.mavsdk.rpc.mocap.SetAttitudePositionMocapResponse"\x04\x80\xb5\x18\x01\x12`\n\x0bSetOdometry\x12$.mavsdk.rpc.mocap.SetOdometryRequest\x1a%.mavsdk.rpc.mocap.SetOdometryResponse"\x04\x80\xb5\x18\x01\x42\x1d\n\x0fio.mavsdk.mocapB\nMocapProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'mocap.mocap_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "mocap.mocap_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\017io.mavsdk.mocapB\nMocapProto' - _globals['_MOCAPSERVICE'].methods_by_name['SetVisionPositionEstimate']._loaded_options = None - _globals['_MOCAPSERVICE'].methods_by_name['SetVisionPositionEstimate']._serialized_options = b'\200\265\030\001' - _globals['_MOCAPSERVICE'].methods_by_name['SetVisionSpeedEstimate']._loaded_options = None - _globals['_MOCAPSERVICE'].methods_by_name['SetVisionSpeedEstimate']._serialized_options = b'\200\265\030\001' - _globals['_MOCAPSERVICE'].methods_by_name['SetAttitudePositionMocap']._loaded_options = None - _globals['_MOCAPSERVICE'].methods_by_name['SetAttitudePositionMocap']._serialized_options = b'\200\265\030\001' - _globals['_MOCAPSERVICE'].methods_by_name['SetOdometry']._loaded_options = None - _globals['_MOCAPSERVICE'].methods_by_name['SetOdometry']._serialized_options = b'\200\265\030\001' - _globals['_SETVISIONPOSITIONESTIMATEREQUEST']._serialized_start=61 - _globals['_SETVISIONPOSITIONESTIMATEREQUEST']._serialized_end=171 - _globals['_SETVISIONPOSITIONESTIMATERESPONSE']._serialized_start=173 - _globals['_SETVISIONPOSITIONESTIMATERESPONSE']._serialized_end=261 - _globals['_SETVISIONSPEEDESTIMATEREQUEST']._serialized_start=263 - _globals['_SETVISIONSPEEDESTIMATEREQUEST']._serialized_end=364 - _globals['_SETVISIONSPEEDESTIMATERESPONSE']._serialized_start=366 - _globals['_SETVISIONSPEEDESTIMATERESPONSE']._serialized_end=451 - _globals['_SETATTITUDEPOSITIONMOCAPREQUEST']._serialized_start=453 - _globals['_SETATTITUDEPOSITIONMOCAPREQUEST']._serialized_end=560 - _globals['_SETATTITUDEPOSITIONMOCAPRESPONSE']._serialized_start=562 - _globals['_SETATTITUDEPOSITIONMOCAPRESPONSE']._serialized_end=649 - _globals['_SETODOMETRYREQUEST']._serialized_start=651 - _globals['_SETODOMETRYREQUEST']._serialized_end=717 - _globals['_SETODOMETRYRESPONSE']._serialized_start=719 - _globals['_SETODOMETRYRESPONSE']._serialized_end=793 - _globals['_POSITIONBODY']._serialized_start=795 - _globals['_POSITIONBODY']._serialized_end=848 - _globals['_ANGLEBODY']._serialized_start=850 - _globals['_ANGLEBODY']._serialized_end=915 - _globals['_SPEEDBODY']._serialized_start=917 - _globals['_SPEEDBODY']._serialized_end=973 - _globals['_SPEEDNED']._serialized_start=975 - _globals['_SPEEDNED']._serialized_end=1040 - _globals['_ANGULARVELOCITYBODY']._serialized_start=1042 - _globals['_ANGULARVELOCITYBODY']._serialized_end=1123 - _globals['_COVARIANCE']._serialized_start=1125 - _globals['_COVARIANCE']._serialized_end=1164 - _globals['_QUATERNION']._serialized_start=1166 - _globals['_QUATERNION']._serialized_end=1222 - _globals['_VISIONPOSITIONESTIMATE']._serialized_start=1225 - _globals['_VISIONPOSITIONESTIMATE']._serialized_end=1427 - _globals['_VISIONSPEEDESTIMATE']._serialized_start=1430 - _globals['_VISIONSPEEDESTIMATE']._serialized_end=1573 - _globals['_ATTITUDEPOSITIONMOCAP']._serialized_start=1576 - _globals['_ATTITUDEPOSITIONMOCAP']._serialized_end=1769 - _globals['_ODOMETRY']._serialized_start=1772 - _globals['_ODOMETRY']._serialized_end=2247 - _globals['_ODOMETRY_MAVFRAME']._serialized_start=2187 - _globals['_ODOMETRY_MAVFRAME']._serialized_end=2247 - _globals['_MOCAPRESULT']._serialized_start=2250 - _globals['_MOCAPRESULT']._serialized_end=2496 - _globals['_MOCAPRESULT_RESULT']._serialized_start=2340 - _globals['_MOCAPRESULT_RESULT']._serialized_end=2496 - _globals['_MOCAPSERVICE']._serialized_start=2499 - _globals['_MOCAPSERVICE']._serialized_end=3022 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\017io.mavsdk.mocapB\nMocapProto" + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetVisionPositionEstimate" + ]._loaded_options = None + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetVisionPositionEstimate" + ]._serialized_options = b"\200\265\030\001" + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetVisionSpeedEstimate" + ]._loaded_options = None + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetVisionSpeedEstimate" + ]._serialized_options = b"\200\265\030\001" + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetAttitudePositionMocap" + ]._loaded_options = None + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetAttitudePositionMocap" + ]._serialized_options = b"\200\265\030\001" + _globals["_MOCAPSERVICE"].methods_by_name["SetOdometry"]._loaded_options = None + _globals["_MOCAPSERVICE"].methods_by_name[ + "SetOdometry" + ]._serialized_options = b"\200\265\030\001" + _globals["_SETVISIONPOSITIONESTIMATEREQUEST"]._serialized_start = 61 + _globals["_SETVISIONPOSITIONESTIMATEREQUEST"]._serialized_end = 171 + _globals["_SETVISIONPOSITIONESTIMATERESPONSE"]._serialized_start = 173 + _globals["_SETVISIONPOSITIONESTIMATERESPONSE"]._serialized_end = 261 + _globals["_SETVISIONSPEEDESTIMATEREQUEST"]._serialized_start = 263 + _globals["_SETVISIONSPEEDESTIMATEREQUEST"]._serialized_end = 364 + _globals["_SETVISIONSPEEDESTIMATERESPONSE"]._serialized_start = 366 + _globals["_SETVISIONSPEEDESTIMATERESPONSE"]._serialized_end = 451 + _globals["_SETATTITUDEPOSITIONMOCAPREQUEST"]._serialized_start = 453 + _globals["_SETATTITUDEPOSITIONMOCAPREQUEST"]._serialized_end = 560 + _globals["_SETATTITUDEPOSITIONMOCAPRESPONSE"]._serialized_start = 562 + _globals["_SETATTITUDEPOSITIONMOCAPRESPONSE"]._serialized_end = 649 + _globals["_SETODOMETRYREQUEST"]._serialized_start = 651 + _globals["_SETODOMETRYREQUEST"]._serialized_end = 717 + _globals["_SETODOMETRYRESPONSE"]._serialized_start = 719 + _globals["_SETODOMETRYRESPONSE"]._serialized_end = 793 + _globals["_POSITIONBODY"]._serialized_start = 795 + _globals["_POSITIONBODY"]._serialized_end = 848 + _globals["_ANGLEBODY"]._serialized_start = 850 + _globals["_ANGLEBODY"]._serialized_end = 915 + _globals["_SPEEDBODY"]._serialized_start = 917 + _globals["_SPEEDBODY"]._serialized_end = 973 + _globals["_SPEEDNED"]._serialized_start = 975 + _globals["_SPEEDNED"]._serialized_end = 1040 + _globals["_ANGULARVELOCITYBODY"]._serialized_start = 1042 + _globals["_ANGULARVELOCITYBODY"]._serialized_end = 1123 + _globals["_COVARIANCE"]._serialized_start = 1125 + _globals["_COVARIANCE"]._serialized_end = 1164 + _globals["_QUATERNION"]._serialized_start = 1166 + _globals["_QUATERNION"]._serialized_end = 1222 + _globals["_VISIONPOSITIONESTIMATE"]._serialized_start = 1225 + _globals["_VISIONPOSITIONESTIMATE"]._serialized_end = 1427 + _globals["_VISIONSPEEDESTIMATE"]._serialized_start = 1430 + _globals["_VISIONSPEEDESTIMATE"]._serialized_end = 1573 + _globals["_ATTITUDEPOSITIONMOCAP"]._serialized_start = 1576 + _globals["_ATTITUDEPOSITIONMOCAP"]._serialized_end = 1769 + _globals["_ODOMETRY"]._serialized_start = 1772 + _globals["_ODOMETRY"]._serialized_end = 2247 + _globals["_ODOMETRY_MAVFRAME"]._serialized_start = 2187 + _globals["_ODOMETRY_MAVFRAME"]._serialized_end = 2247 + _globals["_MOCAPRESULT"]._serialized_start = 2250 + _globals["_MOCAPRESULT"]._serialized_end = 2496 + _globals["_MOCAPRESULT_RESULT"]._serialized_start = 2340 + _globals["_MOCAPRESULT_RESULT"]._serialized_end = 2496 + _globals["_MOCAPSERVICE"]._serialized_start = 2499 + _globals["_MOCAPSERVICE"]._serialized_end = 3022 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/mocap_pb2_grpc.py b/mavsdk/mocap_pb2_grpc.py index 70684a9e..a9b60cef 100644 --- a/mavsdk/mocap_pb2_grpc.py +++ b/mavsdk/mocap_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import mocap_pb2 as mocap_dot_mocap__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in mocap/mocap_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in mocap/mocap_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -39,25 +43,29 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetVisionPositionEstimate = channel.unary_unary( - '/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate', - request_serializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateRequest.SerializeToString, - response_deserializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate", + request_serializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateRequest.SerializeToString, + response_deserializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateResponse.FromString, + _registered_method=True, + ) self.SetVisionSpeedEstimate = channel.unary_unary( - '/mavsdk.rpc.mocap.MocapService/SetVisionSpeedEstimate', - request_serializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateRequest.SerializeToString, - response_deserializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mocap.MocapService/SetVisionSpeedEstimate", + request_serializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateRequest.SerializeToString, + response_deserializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateResponse.FromString, + _registered_method=True, + ) self.SetAttitudePositionMocap = channel.unary_unary( - '/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap', - request_serializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapRequest.SerializeToString, - response_deserializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap", + request_serializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapRequest.SerializeToString, + response_deserializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapResponse.FromString, + _registered_method=True, + ) self.SetOdometry = channel.unary_unary( - '/mavsdk.rpc.mocap.MocapService/SetOdometry', - request_serializer=mocap_dot_mocap__pb2.SetOdometryRequest.SerializeToString, - response_deserializer=mocap_dot_mocap__pb2.SetOdometryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.mocap.MocapService/SetOdometry", + request_serializer=mocap_dot_mocap__pb2.SetOdometryRequest.SerializeToString, + response_deserializer=mocap_dot_mocap__pb2.SetOdometryResponse.FromString, + _registered_method=True, + ) class MocapServiceServicer(object): @@ -68,64 +76,63 @@ class MocapServiceServicer(object): """ def SetVisionPositionEstimate(self, request, context): - """Send Global position/attitude estimate from a vision source. - """ + """Send Global position/attitude estimate from a vision source.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetVisionSpeedEstimate(self, request, context): - """Send Global speed estimate from a vision source. - """ + """Send Global speed estimate from a vision source.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAttitudePositionMocap(self, request, context): - """Send motion capture attitude and position. - """ + """Send motion capture attitude and position.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetOdometry(self, request, context): - """Send odometry information with an external interface. - """ + """Send odometry information with an external interface.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_MocapServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetVisionPositionEstimate': grpc.unary_unary_rpc_method_handler( - servicer.SetVisionPositionEstimate, - request_deserializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateRequest.FromString, - response_serializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateResponse.SerializeToString, - ), - 'SetVisionSpeedEstimate': grpc.unary_unary_rpc_method_handler( - servicer.SetVisionSpeedEstimate, - request_deserializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateRequest.FromString, - response_serializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateResponse.SerializeToString, - ), - 'SetAttitudePositionMocap': grpc.unary_unary_rpc_method_handler( - servicer.SetAttitudePositionMocap, - request_deserializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapRequest.FromString, - response_serializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapResponse.SerializeToString, - ), - 'SetOdometry': grpc.unary_unary_rpc_method_handler( - servicer.SetOdometry, - request_deserializer=mocap_dot_mocap__pb2.SetOdometryRequest.FromString, - response_serializer=mocap_dot_mocap__pb2.SetOdometryResponse.SerializeToString, - ), + "SetVisionPositionEstimate": grpc.unary_unary_rpc_method_handler( + servicer.SetVisionPositionEstimate, + request_deserializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateRequest.FromString, + response_serializer=mocap_dot_mocap__pb2.SetVisionPositionEstimateResponse.SerializeToString, + ), + "SetVisionSpeedEstimate": grpc.unary_unary_rpc_method_handler( + servicer.SetVisionSpeedEstimate, + request_deserializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateRequest.FromString, + response_serializer=mocap_dot_mocap__pb2.SetVisionSpeedEstimateResponse.SerializeToString, + ), + "SetAttitudePositionMocap": grpc.unary_unary_rpc_method_handler( + servicer.SetAttitudePositionMocap, + request_deserializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapRequest.FromString, + response_serializer=mocap_dot_mocap__pb2.SetAttitudePositionMocapResponse.SerializeToString, + ), + "SetOdometry": grpc.unary_unary_rpc_method_handler( + servicer.SetOdometry, + request_deserializer=mocap_dot_mocap__pb2.SetOdometryRequest.FromString, + response_serializer=mocap_dot_mocap__pb2.SetOdometryResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.mocap.MocapService', rpc_method_handlers) + "mavsdk.rpc.mocap.MocapService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.mocap.MocapService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.mocap.MocapService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class MocapService(object): """ Allows interfacing a vehicle with a motion capture system in @@ -134,20 +141,22 @@ class MocapService(object): """ @staticmethod - def SetVisionPositionEstimate(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetVisionPositionEstimate( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate', + "/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate", mocap_dot_mocap__pb2.SetVisionPositionEstimateRequest.SerializeToString, mocap_dot_mocap__pb2.SetVisionPositionEstimateResponse.FromString, options, @@ -158,23 +167,26 @@ def SetVisionPositionEstimate(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetVisionSpeedEstimate(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetVisionSpeedEstimate( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mocap.MocapService/SetVisionSpeedEstimate', + "/mavsdk.rpc.mocap.MocapService/SetVisionSpeedEstimate", mocap_dot_mocap__pb2.SetVisionSpeedEstimateRequest.SerializeToString, mocap_dot_mocap__pb2.SetVisionSpeedEstimateResponse.FromString, options, @@ -185,23 +197,26 @@ def SetVisionSpeedEstimate(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAttitudePositionMocap(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAttitudePositionMocap( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap', + "/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap", mocap_dot_mocap__pb2.SetAttitudePositionMocapRequest.SerializeToString, mocap_dot_mocap__pb2.SetAttitudePositionMocapResponse.FromString, options, @@ -212,23 +227,26 @@ def SetAttitudePositionMocap(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetOdometry(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetOdometry( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.mocap.MocapService/SetOdometry', + "/mavsdk.rpc.mocap.MocapService/SetOdometry", mocap_dot_mocap__pb2.SetOdometryRequest.SerializeToString, mocap_dot_mocap__pb2.SetOdometryResponse.FromString, options, @@ -239,4 +257,5 @@ def SetOdometry(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/offboard.py b/mavsdk/offboard.py index d6c374a8..d6c9a67a 100644 --- a/mavsdk/offboard.py +++ b/mavsdk/offboard.py @@ -8,504 +8,388 @@ class Attitude: """ - Type for attitude body angles in NED reference frame (roll, pitch, yaw and thrust) + Type for attitude body angles in NED reference frame (roll, pitch, yaw and thrust) - Parameters - ---------- - roll_deg : float - Roll angle (in degrees, positive is right side down) + Parameters + ---------- + roll_deg : float + Roll angle (in degrees, positive is right side down) - pitch_deg : float - Pitch angle (in degrees, positive is nose up) + pitch_deg : float + Pitch angle (in degrees, positive is nose up) - yaw_deg : float - Yaw angle (in degrees, positive is move nose to the right) + yaw_deg : float + Yaw angle (in degrees, positive is move nose to the right) - thrust_value : float - Thrust (range: 0 to 1) + thrust_value : float + Thrust (range: 0 to 1) - """ - - + """ - def __init__( - self, - roll_deg, - pitch_deg, - yaw_deg, - thrust_value): - """ Initializes the Attitude object """ + def __init__(self, roll_deg, pitch_deg, yaw_deg, thrust_value): + """Initializes the Attitude object""" self.roll_deg = roll_deg self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg self.thrust_value = thrust_value def __eq__(self, to_compare): - """ Checks if two Attitude are the same """ + """Checks if two Attitude are the same""" try: # Try to compare - this likely fails when it is compared to a non # Attitude object - return \ - (self.roll_deg == to_compare.roll_deg) and \ - (self.pitch_deg == to_compare.pitch_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) and \ - (self.thrust_value == to_compare.thrust_value) + return ( + (self.roll_deg == to_compare.roll_deg) + and (self.pitch_deg == to_compare.pitch_deg) + and (self.yaw_deg == to_compare.yaw_deg) + and (self.thrust_value == to_compare.thrust_value) + ) except AttributeError: return False def __str__(self): - """ Attitude in string representation """ - struct_repr = ", ".join([ + """Attitude in string representation""" + struct_repr = ", ".join( + [ "roll_deg: " + str(self.roll_deg), "pitch_deg: " + str(self.pitch_deg), "yaw_deg: " + str(self.yaw_deg), - "thrust_value: " + str(self.thrust_value) - ]) + "thrust_value: " + str(self.thrust_value), + ] + ) return f"Attitude: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAttitude): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Attitude( - - rpcAttitude.roll_deg, - - - rpcAttitude.pitch_deg, - - - rpcAttitude.yaw_deg, - - - rpcAttitude.thrust_value - ) + rpcAttitude.roll_deg, + rpcAttitude.pitch_deg, + rpcAttitude.yaw_deg, + rpcAttitude.thrust_value, + ) def translate_to_rpc(self, rpcAttitude): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAttitude.roll_deg = self.roll_deg - - - - - + rpcAttitude.pitch_deg = self.pitch_deg - - - - - + rpcAttitude.yaw_deg = self.yaw_deg - - - - - + rpcAttitude.thrust_value = self.thrust_value - - - class ActuatorControlGroup: """ - Eight controls that will be given to the group. Each control is a normalized - (-1..+1) command value, which will be mapped and scaled through the mixer. + Eight controls that will be given to the group. Each control is a normalized + (-1..+1) command value, which will be mapped and scaled through the mixer. - Parameters - ---------- - controls : [float] - Controls in the group + Parameters + ---------- + controls : [float] + Controls in the group - """ - - + """ - def __init__( - self, - controls): - """ Initializes the ActuatorControlGroup object """ + def __init__(self, controls): + """Initializes the ActuatorControlGroup object""" self.controls = controls def __eq__(self, to_compare): - """ Checks if two ActuatorControlGroup are the same """ + """Checks if two ActuatorControlGroup are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActuatorControlGroup object - return \ - (self.controls == to_compare.controls) + return self.controls == to_compare.controls except AttributeError: return False def __str__(self): - """ ActuatorControlGroup in string representation """ - struct_repr = ", ".join([ - "controls: " + str(self.controls) - ]) + """ActuatorControlGroup in string representation""" + struct_repr = ", ".join(["controls: " + str(self.controls)]) return f"ActuatorControlGroup: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActuatorControlGroup): - """ Translates a gRPC struct to the SDK equivalent """ - return ActuatorControlGroup( - - rpcActuatorControlGroup.controls - ) + """Translates a gRPC struct to the SDK equivalent""" + return ActuatorControlGroup(rpcActuatorControlGroup.controls) def translate_to_rpc(self, rpcActuatorControlGroup): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - for elem in self.controls: - rpcActuatorControlGroup.controls.append(elem) - - - + rpcActuatorControlGroup.controls.append(elem) class ActuatorControl: """ - Type for actuator control. + Type for actuator control. - Control members should be normed to -1..+1 where 0 is neutral position. - Throttle for single rotation direction motors is 0..1, negative range for reverse direction. + Control members should be normed to -1..+1 where 0 is neutral position. + Throttle for single rotation direction motors is 0..1, negative range for reverse direction. - One group support eight controls. + One group support eight controls. - Up to 16 actuator controls can be set. To ignore an output group, set all it controls to NaN. - If one or more controls in group is not NaN, then all NaN controls will sent as zero. - The first 8 actuator controls internally map to control group 0, the latter 8 actuator - controls map to control group 1. Depending on what controls are set (instead of NaN) 1 or 2 - MAVLink messages are actually sent. + Up to 16 actuator controls can be set. To ignore an output group, set all it controls to NaN. + If one or more controls in group is not NaN, then all NaN controls will sent as zero. + The first 8 actuator controls internally map to control group 0, the latter 8 actuator + controls map to control group 1. Depending on what controls are set (instead of NaN) 1 or 2 + MAVLink messages are actually sent. - In PX4 v1.9.0 Only first four Control Groups are supported - (https://github.com/PX4/Firmware/blob/v1.9.0/src/modules/mavlink/mavlink_receiver.cpp#L980). + In PX4 v1.9.0 Only first four Control Groups are supported + (https://github.com/PX4/Firmware/blob/v1.9.0/src/modules/mavlink/mavlink_receiver.cpp#L980). - Parameters - ---------- - groups : [ActuatorControlGroup] - Control groups. + Parameters + ---------- + groups : [ActuatorControlGroup] + Control groups. - """ - - + """ - def __init__( - self, - groups): - """ Initializes the ActuatorControl object """ + def __init__(self, groups): + """Initializes the ActuatorControl object""" self.groups = groups def __eq__(self, to_compare): - """ Checks if two ActuatorControl are the same """ + """Checks if two ActuatorControl are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActuatorControl object - return \ - (self.groups == to_compare.groups) + return self.groups == to_compare.groups except AttributeError: return False def __str__(self): - """ ActuatorControl in string representation """ - struct_repr = ", ".join([ - "groups: " + str(self.groups) - ]) + """ActuatorControl in string representation""" + struct_repr = ", ".join(["groups: " + str(self.groups)]) return f"ActuatorControl: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActuatorControl): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActuatorControl( - - list(map(lambda elem: ActuatorControlGroup.translate_from_rpc(elem), rpcActuatorControl.groups)) + list( + map( + lambda elem: ActuatorControlGroup.translate_from_rpc(elem), + rpcActuatorControl.groups, ) + ) + ) def translate_to_rpc(self, rpcActuatorControl): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.groups: - rpc_elem = offboard_pb2.ActuatorControlGroup() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcActuatorControl.groups.extend(rpc_elems_list) - - - class AttitudeRate: """ - Type for attitude rate commands in body coordinates (roll, pitch, yaw angular rate and thrust) - - Parameters - ---------- - roll_deg_s : float - Roll angular rate (in degrees/second, positive for clock-wise looking from front) + Type for attitude rate commands in body coordinates (roll, pitch, yaw angular rate and thrust) - pitch_deg_s : float - Pitch angular rate (in degrees/second, positive for head/front moving up) + Parameters + ---------- + roll_deg_s : float + Roll angular rate (in degrees/second, positive for clock-wise looking from front) - yaw_deg_s : float - Yaw angular rate (in degrees/second, positive for clock-wise looking from above) + pitch_deg_s : float + Pitch angular rate (in degrees/second, positive for head/front moving up) - thrust_value : float - Thrust (range: 0 to 1) + yaw_deg_s : float + Yaw angular rate (in degrees/second, positive for clock-wise looking from above) - """ + thrust_value : float + Thrust (range: 0 to 1) - + """ - def __init__( - self, - roll_deg_s, - pitch_deg_s, - yaw_deg_s, - thrust_value): - """ Initializes the AttitudeRate object """ + def __init__(self, roll_deg_s, pitch_deg_s, yaw_deg_s, thrust_value): + """Initializes the AttitudeRate object""" self.roll_deg_s = roll_deg_s self.pitch_deg_s = pitch_deg_s self.yaw_deg_s = yaw_deg_s self.thrust_value = thrust_value def __eq__(self, to_compare): - """ Checks if two AttitudeRate are the same """ + """Checks if two AttitudeRate are the same""" try: # Try to compare - this likely fails when it is compared to a non # AttitudeRate object - return \ - (self.roll_deg_s == to_compare.roll_deg_s) and \ - (self.pitch_deg_s == to_compare.pitch_deg_s) and \ - (self.yaw_deg_s == to_compare.yaw_deg_s) and \ - (self.thrust_value == to_compare.thrust_value) + return ( + (self.roll_deg_s == to_compare.roll_deg_s) + and (self.pitch_deg_s == to_compare.pitch_deg_s) + and (self.yaw_deg_s == to_compare.yaw_deg_s) + and (self.thrust_value == to_compare.thrust_value) + ) except AttributeError: return False def __str__(self): - """ AttitudeRate in string representation """ - struct_repr = ", ".join([ + """AttitudeRate in string representation""" + struct_repr = ", ".join( + [ "roll_deg_s: " + str(self.roll_deg_s), "pitch_deg_s: " + str(self.pitch_deg_s), "yaw_deg_s: " + str(self.yaw_deg_s), - "thrust_value: " + str(self.thrust_value) - ]) + "thrust_value: " + str(self.thrust_value), + ] + ) return f"AttitudeRate: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAttitudeRate): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AttitudeRate( - - rpcAttitudeRate.roll_deg_s, - - - rpcAttitudeRate.pitch_deg_s, - - - rpcAttitudeRate.yaw_deg_s, - - - rpcAttitudeRate.thrust_value - ) + rpcAttitudeRate.roll_deg_s, + rpcAttitudeRate.pitch_deg_s, + rpcAttitudeRate.yaw_deg_s, + rpcAttitudeRate.thrust_value, + ) def translate_to_rpc(self, rpcAttitudeRate): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAttitudeRate.roll_deg_s = self.roll_deg_s - - - - - + rpcAttitudeRate.pitch_deg_s = self.pitch_deg_s - - - - - + rpcAttitudeRate.yaw_deg_s = self.yaw_deg_s - - - - - + rpcAttitudeRate.thrust_value = self.thrust_value - - - class PositionNedYaw: """ - Type for position commands in NED (North East Down) coordinates and yaw. - - Parameters - ---------- - north_m : float - Position North (in metres) + Type for position commands in NED (North East Down) coordinates and yaw. - east_m : float - Position East (in metres) + Parameters + ---------- + north_m : float + Position North (in metres) - down_m : float - Position Down (in metres) + east_m : float + Position East (in metres) - yaw_deg : float - Yaw in degrees (0 North, positive is clock-wise looking from above) + down_m : float + Position Down (in metres) - """ + yaw_deg : float + Yaw in degrees (0 North, positive is clock-wise looking from above) - + """ - def __init__( - self, - north_m, - east_m, - down_m, - yaw_deg): - """ Initializes the PositionNedYaw object """ + def __init__(self, north_m, east_m, down_m, yaw_deg): + """Initializes the PositionNedYaw object""" self.north_m = north_m self.east_m = east_m self.down_m = down_m self.yaw_deg = yaw_deg def __eq__(self, to_compare): - """ Checks if two PositionNedYaw are the same """ + """Checks if two PositionNedYaw are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionNedYaw object - return \ - (self.north_m == to_compare.north_m) and \ - (self.east_m == to_compare.east_m) and \ - (self.down_m == to_compare.down_m) and \ - (self.yaw_deg == to_compare.yaw_deg) + return ( + (self.north_m == to_compare.north_m) + and (self.east_m == to_compare.east_m) + and (self.down_m == to_compare.down_m) + and (self.yaw_deg == to_compare.yaw_deg) + ) except AttributeError: return False def __str__(self): - """ PositionNedYaw in string representation """ - struct_repr = ", ".join([ + """PositionNedYaw in string representation""" + struct_repr = ", ".join( + [ "north_m: " + str(self.north_m), "east_m: " + str(self.east_m), "down_m: " + str(self.down_m), - "yaw_deg: " + str(self.yaw_deg) - ]) + "yaw_deg: " + str(self.yaw_deg), + ] + ) return f"PositionNedYaw: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionNedYaw): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionNedYaw( - - rpcPositionNedYaw.north_m, - - - rpcPositionNedYaw.east_m, - - - rpcPositionNedYaw.down_m, - - - rpcPositionNedYaw.yaw_deg - ) + rpcPositionNedYaw.north_m, + rpcPositionNedYaw.east_m, + rpcPositionNedYaw.down_m, + rpcPositionNedYaw.yaw_deg, + ) def translate_to_rpc(self, rpcPositionNedYaw): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionNedYaw.north_m = self.north_m - - - - - + rpcPositionNedYaw.east_m = self.east_m - - - - - + rpcPositionNedYaw.down_m = self.down_m - - - - - + rpcPositionNedYaw.yaw_deg = self.yaw_deg - - - class PositionGlobalYaw: """ - Type for position commands in Global (Latitude, Longitude, Altitude) coordinates and yaw. + Type for position commands in Global (Latitude, Longitude, Altitude) coordinates and yaw. - Parameters - ---------- - lat_deg : double - Latitude (in degrees) + Parameters + ---------- + lat_deg : double + Latitude (in degrees) - lon_deg : double - Longitude (in degrees) + lon_deg : double + Longitude (in degrees) - alt_m : float - altitude (in metres) + alt_m : float + altitude (in metres) - yaw_deg : float - Yaw in degrees (0 North, positive is clock-wise looking from above) + yaw_deg : float + Yaw in degrees (0 North, positive is clock-wise looking from above) - altitude_type : AltitudeType - altitude type for this position + altitude_type : AltitudeType + altitude type for this position - """ + """ - - class AltitudeType(Enum): """ - Possible altitude options + Possible altitude options - Values - ------ - REL_HOME - Altitude relative to the Home position + Values + ------ + REL_HOME + Altitude relative to the Home position - AMSL - Altitude above mean sea level (AMSL) + AMSL + Altitude above mean sea level (AMSL) - AGL - Altitude above ground level (AGL) + AGL + Altitude above ground level (AGL) - """ + """ - REL_HOME = 0 AMSL = 1 AGL = 2 @@ -520,7 +404,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == offboard_pb2.PositionGlobalYaw.ALTITUDE_TYPE_REL_HOME: return PositionGlobalYaw.AltitudeType.REL_HOME if rpc_enum_value == offboard_pb2.PositionGlobalYaw.ALTITUDE_TYPE_AMSL: @@ -530,16 +414,9 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - - def __init__( - self, - lat_deg, - lon_deg, - alt_m, - yaw_deg, - altitude_type): - """ Initializes the PositionGlobalYaw object """ + + def __init__(self, lat_deg, lon_deg, alt_m, yaw_deg, altitude_type): + """Initializes the PositionGlobalYaw object""" self.lat_deg = lat_deg self.lon_deg = lon_deg self.alt_m = alt_m @@ -547,442 +424,333 @@ def __init__( self.altitude_type = altitude_type def __eq__(self, to_compare): - """ Checks if two PositionGlobalYaw are the same """ + """Checks if two PositionGlobalYaw are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionGlobalYaw object - return \ - (self.lat_deg == to_compare.lat_deg) and \ - (self.lon_deg == to_compare.lon_deg) and \ - (self.alt_m == to_compare.alt_m) and \ - (self.yaw_deg == to_compare.yaw_deg) and \ - (self.altitude_type == to_compare.altitude_type) + return ( + (self.lat_deg == to_compare.lat_deg) + and (self.lon_deg == to_compare.lon_deg) + and (self.alt_m == to_compare.alt_m) + and (self.yaw_deg == to_compare.yaw_deg) + and (self.altitude_type == to_compare.altitude_type) + ) except AttributeError: return False def __str__(self): - """ PositionGlobalYaw in string representation """ - struct_repr = ", ".join([ + """PositionGlobalYaw in string representation""" + struct_repr = ", ".join( + [ "lat_deg: " + str(self.lat_deg), "lon_deg: " + str(self.lon_deg), "alt_m: " + str(self.alt_m), "yaw_deg: " + str(self.yaw_deg), - "altitude_type: " + str(self.altitude_type) - ]) + "altitude_type: " + str(self.altitude_type), + ] + ) return f"PositionGlobalYaw: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionGlobalYaw): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionGlobalYaw( - - rpcPositionGlobalYaw.lat_deg, - - - rpcPositionGlobalYaw.lon_deg, - - - rpcPositionGlobalYaw.alt_m, - - - rpcPositionGlobalYaw.yaw_deg, - - - PositionGlobalYaw.AltitudeType.translate_from_rpc(rpcPositionGlobalYaw.altitude_type) - ) + rpcPositionGlobalYaw.lat_deg, + rpcPositionGlobalYaw.lon_deg, + rpcPositionGlobalYaw.alt_m, + rpcPositionGlobalYaw.yaw_deg, + PositionGlobalYaw.AltitudeType.translate_from_rpc( + rpcPositionGlobalYaw.altitude_type + ), + ) def translate_to_rpc(self, rpcPositionGlobalYaw): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionGlobalYaw.lat_deg = self.lat_deg - - - - - + rpcPositionGlobalYaw.lon_deg = self.lon_deg - - - - - + rpcPositionGlobalYaw.alt_m = self.alt_m - - - - - + rpcPositionGlobalYaw.yaw_deg = self.yaw_deg - - - - - + rpcPositionGlobalYaw.altitude_type = self.altitude_type.translate_to_rpc() - - - class VelocityBodyYawspeed: """ - Type for velocity commands in body coordinates. - - Parameters - ---------- - forward_m_s : float - Velocity forward (in metres/second) + Type for velocity commands in body coordinates. - right_m_s : float - Velocity right (in metres/second) + Parameters + ---------- + forward_m_s : float + Velocity forward (in metres/second) - down_m_s : float - Velocity down (in metres/second) + right_m_s : float + Velocity right (in metres/second) - yawspeed_deg_s : float - Yaw angular rate (in degrees/second, positive for clock-wise looking from above) + down_m_s : float + Velocity down (in metres/second) - """ + yawspeed_deg_s : float + Yaw angular rate (in degrees/second, positive for clock-wise looking from above) - + """ - def __init__( - self, - forward_m_s, - right_m_s, - down_m_s, - yawspeed_deg_s): - """ Initializes the VelocityBodyYawspeed object """ + def __init__(self, forward_m_s, right_m_s, down_m_s, yawspeed_deg_s): + """Initializes the VelocityBodyYawspeed object""" self.forward_m_s = forward_m_s self.right_m_s = right_m_s self.down_m_s = down_m_s self.yawspeed_deg_s = yawspeed_deg_s def __eq__(self, to_compare): - """ Checks if two VelocityBodyYawspeed are the same """ + """Checks if two VelocityBodyYawspeed are the same""" try: # Try to compare - this likely fails when it is compared to a non # VelocityBodyYawspeed object - return \ - (self.forward_m_s == to_compare.forward_m_s) and \ - (self.right_m_s == to_compare.right_m_s) and \ - (self.down_m_s == to_compare.down_m_s) and \ - (self.yawspeed_deg_s == to_compare.yawspeed_deg_s) + return ( + (self.forward_m_s == to_compare.forward_m_s) + and (self.right_m_s == to_compare.right_m_s) + and (self.down_m_s == to_compare.down_m_s) + and (self.yawspeed_deg_s == to_compare.yawspeed_deg_s) + ) except AttributeError: return False def __str__(self): - """ VelocityBodyYawspeed in string representation """ - struct_repr = ", ".join([ + """VelocityBodyYawspeed in string representation""" + struct_repr = ", ".join( + [ "forward_m_s: " + str(self.forward_m_s), "right_m_s: " + str(self.right_m_s), "down_m_s: " + str(self.down_m_s), - "yawspeed_deg_s: " + str(self.yawspeed_deg_s) - ]) + "yawspeed_deg_s: " + str(self.yawspeed_deg_s), + ] + ) return f"VelocityBodyYawspeed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVelocityBodyYawspeed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VelocityBodyYawspeed( - - rpcVelocityBodyYawspeed.forward_m_s, - - - rpcVelocityBodyYawspeed.right_m_s, - - - rpcVelocityBodyYawspeed.down_m_s, - - - rpcVelocityBodyYawspeed.yawspeed_deg_s - ) + rpcVelocityBodyYawspeed.forward_m_s, + rpcVelocityBodyYawspeed.right_m_s, + rpcVelocityBodyYawspeed.down_m_s, + rpcVelocityBodyYawspeed.yawspeed_deg_s, + ) def translate_to_rpc(self, rpcVelocityBodyYawspeed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVelocityBodyYawspeed.forward_m_s = self.forward_m_s - - - - - + rpcVelocityBodyYawspeed.right_m_s = self.right_m_s - - - - - + rpcVelocityBodyYawspeed.down_m_s = self.down_m_s - - - - - + rpcVelocityBodyYawspeed.yawspeed_deg_s = self.yawspeed_deg_s - - - class VelocityNedYaw: """ - Type for velocity commands in NED (North East Down) coordinates and yaw. + Type for velocity commands in NED (North East Down) coordinates and yaw. - Parameters - ---------- - north_m_s : float - Velocity North (in metres/second) + Parameters + ---------- + north_m_s : float + Velocity North (in metres/second) - east_m_s : float - Velocity East (in metres/second) + east_m_s : float + Velocity East (in metres/second) - down_m_s : float - Velocity Down (in metres/second) + down_m_s : float + Velocity Down (in metres/second) - yaw_deg : float - Yaw in degrees (0 North, positive is clock-wise looking from above) + yaw_deg : float + Yaw in degrees (0 North, positive is clock-wise looking from above) - """ - - + """ - def __init__( - self, - north_m_s, - east_m_s, - down_m_s, - yaw_deg): - """ Initializes the VelocityNedYaw object """ + def __init__(self, north_m_s, east_m_s, down_m_s, yaw_deg): + """Initializes the VelocityNedYaw object""" self.north_m_s = north_m_s self.east_m_s = east_m_s self.down_m_s = down_m_s self.yaw_deg = yaw_deg def __eq__(self, to_compare): - """ Checks if two VelocityNedYaw are the same """ + """Checks if two VelocityNedYaw are the same""" try: # Try to compare - this likely fails when it is compared to a non # VelocityNedYaw object - return \ - (self.north_m_s == to_compare.north_m_s) and \ - (self.east_m_s == to_compare.east_m_s) and \ - (self.down_m_s == to_compare.down_m_s) and \ - (self.yaw_deg == to_compare.yaw_deg) + return ( + (self.north_m_s == to_compare.north_m_s) + and (self.east_m_s == to_compare.east_m_s) + and (self.down_m_s == to_compare.down_m_s) + and (self.yaw_deg == to_compare.yaw_deg) + ) except AttributeError: return False def __str__(self): - """ VelocityNedYaw in string representation """ - struct_repr = ", ".join([ + """VelocityNedYaw in string representation""" + struct_repr = ", ".join( + [ "north_m_s: " + str(self.north_m_s), "east_m_s: " + str(self.east_m_s), "down_m_s: " + str(self.down_m_s), - "yaw_deg: " + str(self.yaw_deg) - ]) + "yaw_deg: " + str(self.yaw_deg), + ] + ) return f"VelocityNedYaw: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVelocityNedYaw): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VelocityNedYaw( - - rpcVelocityNedYaw.north_m_s, - - - rpcVelocityNedYaw.east_m_s, - - - rpcVelocityNedYaw.down_m_s, - - - rpcVelocityNedYaw.yaw_deg - ) + rpcVelocityNedYaw.north_m_s, + rpcVelocityNedYaw.east_m_s, + rpcVelocityNedYaw.down_m_s, + rpcVelocityNedYaw.yaw_deg, + ) def translate_to_rpc(self, rpcVelocityNedYaw): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVelocityNedYaw.north_m_s = self.north_m_s - - - - - + rpcVelocityNedYaw.east_m_s = self.east_m_s - - - - - + rpcVelocityNedYaw.down_m_s = self.down_m_s - - - - - + rpcVelocityNedYaw.yaw_deg = self.yaw_deg - - - class AccelerationNed: """ - Type for acceleration commands in NED (North East Down) coordinates. - - Parameters - ---------- - north_m_s2 : float - Acceleration North (in metres/second^2) + Type for acceleration commands in NED (North East Down) coordinates. - east_m_s2 : float - Acceleration East (in metres/second^2) + Parameters + ---------- + north_m_s2 : float + Acceleration North (in metres/second^2) - down_m_s2 : float - Acceleration Down (in metres/second^2) + east_m_s2 : float + Acceleration East (in metres/second^2) - """ + down_m_s2 : float + Acceleration Down (in metres/second^2) - + """ - def __init__( - self, - north_m_s2, - east_m_s2, - down_m_s2): - """ Initializes the AccelerationNed object """ + def __init__(self, north_m_s2, east_m_s2, down_m_s2): + """Initializes the AccelerationNed object""" self.north_m_s2 = north_m_s2 self.east_m_s2 = east_m_s2 self.down_m_s2 = down_m_s2 def __eq__(self, to_compare): - """ Checks if two AccelerationNed are the same """ + """Checks if two AccelerationNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # AccelerationNed object - return \ - (self.north_m_s2 == to_compare.north_m_s2) and \ - (self.east_m_s2 == to_compare.east_m_s2) and \ - (self.down_m_s2 == to_compare.down_m_s2) + return ( + (self.north_m_s2 == to_compare.north_m_s2) + and (self.east_m_s2 == to_compare.east_m_s2) + and (self.down_m_s2 == to_compare.down_m_s2) + ) except AttributeError: return False def __str__(self): - """ AccelerationNed in string representation """ - struct_repr = ", ".join([ + """AccelerationNed in string representation""" + struct_repr = ", ".join( + [ "north_m_s2: " + str(self.north_m_s2), "east_m_s2: " + str(self.east_m_s2), - "down_m_s2: " + str(self.down_m_s2) - ]) + "down_m_s2: " + str(self.down_m_s2), + ] + ) return f"AccelerationNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAccelerationNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AccelerationNed( - - rpcAccelerationNed.north_m_s2, - - - rpcAccelerationNed.east_m_s2, - - - rpcAccelerationNed.down_m_s2 - ) + rpcAccelerationNed.north_m_s2, + rpcAccelerationNed.east_m_s2, + rpcAccelerationNed.down_m_s2, + ) def translate_to_rpc(self, rpcAccelerationNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAccelerationNed.north_m_s2 = self.north_m_s2 - - - - - + rpcAccelerationNed.east_m_s2 = self.east_m_s2 - - - - - + rpcAccelerationNed.down_m_s2 = self.down_m_s2 - - - class OffboardResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for offboard requests + Possible results returned for offboard requests - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command denied + COMMAND_DENIED + Command denied - TIMEOUT - Request timed out + TIMEOUT + Request timed out - NO_SETPOINT_SET - Cannot start without setpoint set + NO_SETPOINT_SET + Cannot start without setpoint set - FAILED - Request failed + FAILED + Request failed - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -1015,7 +783,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == offboard_pb2.OffboardResult.RESULT_UNKNOWN: return OffboardResult.Result.UNKNOWN if rpc_enum_value == offboard_pb2.OffboardResult.RESULT_SUCCESS: @@ -1037,69 +805,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the OffboardResult object """ + def __init__(self, result, result_str): + """Initializes the OffboardResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two OffboardResult are the same """ + """Checks if two OffboardResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # OffboardResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ OffboardResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """OffboardResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"OffboardResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcOffboardResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return OffboardResult( - - OffboardResult.Result.translate_from_rpc(rpcOffboardResult.result), - - - rpcOffboardResult.result_str - ) + OffboardResult.Result.translate_from_rpc(rpcOffboardResult.result), + rpcOffboardResult.result_str, + ) def translate_to_rpc(self, rpcOffboardResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcOffboardResult.result = self.result.translate_to_rpc() - - - - - - rpcOffboardResult.result_str = self.result_str - - - + rpcOffboardResult.result_str = self.result_str class OffboardError(Exception): - """ Raised when a OffboardResult is a fail code """ + """Raised when a OffboardResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -1112,406 +861,374 @@ def __str__(self): class Offboard(AsyncBase): """ - Control a drone with position, velocity, attitude or motor commands. + Control a drone with position, velocity, attitude or motor commands. - The module is called offboard because the commands can be sent from external sources - as opposed to onboard control right inside the autopilot "board". + The module is called offboard because the commands can be sent from external sources + as opposed to onboard control right inside the autopilot "board". - Client code must specify a setpoint before starting offboard mode. - Mavsdk automatically sends setpoints at 20Hz (PX4 Offboard mode requires that setpoints - are minimally sent at 2Hz). + Client code must specify a setpoint before starting offboard mode. + Mavsdk automatically sends setpoints at 20Hz (PX4 Offboard mode requires that setpoints + are minimally sent at 2Hz). - Generated by dcsdkgen - MAVSDK Offboard API + Generated by dcsdkgen - MAVSDK Offboard API """ # Plugin name name = "Offboard" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = offboard_pb2_grpc.OffboardServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return OffboardResult.translate_from_rpc(response.offboard_result) - async def start(self): """ - Start offboard control. + Start offboard control. - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.StartRequest() response = await self._stub.Start(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "start()") - async def stop(self): """ - Stop offboard control. + Stop offboard control. - The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html + The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.StopRequest() response = await self._stub.Stop(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "stop()") - async def is_active(self): """ - Check if offboard control is active. + Check if offboard control is active. + + True means that the vehicle is in offboard mode and we are actively sending + setpoints. - True means that the vehicle is in offboard mode and we are actively sending - setpoints. + Returns + ------- + is_active : bool + True if offboard is active - Returns - ------- - is_active : bool - True if offboard is active - """ request = offboard_pb2.IsActiveRequest() response = await self._stub.IsActive(request) - - return response.is_active - async def set_attitude(self, attitude): """ - Set the attitude in terms of roll, pitch and yaw in degrees with thrust. + Set the attitude in terms of roll, pitch and yaw in degrees with thrust. - Parameters - ---------- - attitude : Attitude - Attitude roll, pitch and yaw along with thrust + Parameters + ---------- + attitude : Attitude + Attitude roll, pitch and yaw along with thrust - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetAttitudeRequest() - + attitude.translate_to_rpc(request.attitude) - - + response = await self._stub.SetAttitude(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_attitude()", attitude) - async def set_actuator_control(self, actuator_control): """ - Set direct actuator control values to groups #0 and #1. + Set direct actuator control values to groups #0 and #1. - First 8 controls will go to control group 0, the following 8 controls to control group 1 (if - actuator_control.num_controls more than 8). + First 8 controls will go to control group 0, the following 8 controls to control group 1 (if + actuator_control.num_controls more than 8). - Parameters - ---------- - actuator_control : ActuatorControl - Actuator control values + Parameters + ---------- + actuator_control : ActuatorControl + Actuator control values - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetActuatorControlRequest() - + actuator_control.translate_to_rpc(request.actuator_control) - - + response = await self._stub.SetActuatorControl(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_actuator_control()", actuator_control) - async def set_attitude_rate(self, attitude_rate): """ - Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust. + Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust. - Parameters - ---------- - attitude_rate : AttitudeRate - Attitude rate roll, pitch and yaw angular rate along with thrust + Parameters + ---------- + attitude_rate : AttitudeRate + Attitude rate roll, pitch and yaw angular rate along with thrust - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetAttitudeRateRequest() - + attitude_rate.translate_to_rpc(request.attitude_rate) - - + response = await self._stub.SetAttitudeRate(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_attitude_rate()", attitude_rate) - async def set_position_ned(self, position_ned_yaw): """ - Set the position in NED coordinates and yaw. + Set the position in NED coordinates and yaw. - Parameters - ---------- - position_ned_yaw : PositionNedYaw - Position and yaw + Parameters + ---------- + position_ned_yaw : PositionNedYaw + Position and yaw - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetPositionNedRequest() - + position_ned_yaw.translate_to_rpc(request.position_ned_yaw) - - + response = await self._stub.SetPositionNed(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_position_ned()", position_ned_yaw) - async def set_position_global(self, position_global_yaw): """ - Set the position in Global coordinates (latitude, longitude, altitude) and yaw + Set the position in Global coordinates (latitude, longitude, altitude) and yaw - Parameters - ---------- - position_global_yaw : PositionGlobalYaw - Position and yaw + Parameters + ---------- + position_global_yaw : PositionGlobalYaw + Position and yaw - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetPositionGlobalRequest() - + position_global_yaw.translate_to_rpc(request.position_global_yaw) - - + response = await self._stub.SetPositionGlobal(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_position_global()", position_global_yaw) - async def set_velocity_body(self, velocity_body_yawspeed): """ - Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft. + Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft. - Parameters - ---------- - velocity_body_yawspeed : VelocityBodyYawspeed - Velocity and yaw angular rate + Parameters + ---------- + velocity_body_yawspeed : VelocityBodyYawspeed + Velocity and yaw angular rate - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetVelocityBodyRequest() - + velocity_body_yawspeed.translate_to_rpc(request.velocity_body_yawspeed) - - + response = await self._stub.SetVelocityBody(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_velocity_body()", velocity_body_yawspeed) - async def set_velocity_ned(self, velocity_ned_yaw): """ - Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft. + Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft. - Parameters - ---------- - velocity_ned_yaw : VelocityNedYaw - Velocity and yaw + Parameters + ---------- + velocity_ned_yaw : VelocityNedYaw + Velocity and yaw - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetVelocityNedRequest() - + velocity_ned_yaw.translate_to_rpc(request.velocity_ned_yaw) - - + response = await self._stub.SetVelocityNed(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_velocity_ned()", velocity_ned_yaw) - async def set_position_velocity_ned(self, position_ned_yaw, velocity_ned_yaw): """ - Set the position in NED coordinates, with the velocity to be used as feed-forward. + Set the position in NED coordinates, with the velocity to be used as feed-forward. - Parameters - ---------- - position_ned_yaw : PositionNedYaw - Position and yaw + Parameters + ---------- + position_ned_yaw : PositionNedYaw + Position and yaw - velocity_ned_yaw : VelocityNedYaw - Velocity and yaw + velocity_ned_yaw : VelocityNedYaw + Velocity and yaw - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetPositionVelocityNedRequest() - + position_ned_yaw.translate_to_rpc(request.position_ned_yaw) - - - + velocity_ned_yaw.translate_to_rpc(request.velocity_ned_yaw) - - + response = await self._stub.SetPositionVelocityNed(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: - raise OffboardError(result, "set_position_velocity_ned()", position_ned_yaw, velocity_ned_yaw) - - - async def set_position_velocity_acceleration_ned(self, position_ned_yaw, velocity_ned_yaw, acceleration_ned): + raise OffboardError( + result, + "set_position_velocity_ned()", + position_ned_yaw, + velocity_ned_yaw, + ) + + async def set_position_velocity_acceleration_ned( + self, position_ned_yaw, velocity_ned_yaw, acceleration_ned + ): """ - Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward. + Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward. - Parameters - ---------- - position_ned_yaw : PositionNedYaw - Position and yaw + Parameters + ---------- + position_ned_yaw : PositionNedYaw + Position and yaw - velocity_ned_yaw : VelocityNedYaw - Velocity and yaw + velocity_ned_yaw : VelocityNedYaw + Velocity and yaw - acceleration_ned : AccelerationNed - Acceleration + acceleration_ned : AccelerationNed + Acceleration - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetPositionVelocityAccelerationNedRequest() - + position_ned_yaw.translate_to_rpc(request.position_ned_yaw) - - - + velocity_ned_yaw.translate_to_rpc(request.velocity_ned_yaw) - - - + acceleration_ned.translate_to_rpc(request.acceleration_ned) - - + response = await self._stub.SetPositionVelocityAccelerationNed(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: - raise OffboardError(result, "set_position_velocity_acceleration_ned()", position_ned_yaw, velocity_ned_yaw, acceleration_ned) - + raise OffboardError( + result, + "set_position_velocity_acceleration_ned()", + position_ned_yaw, + velocity_ned_yaw, + acceleration_ned, + ) async def set_acceleration_ned(self, acceleration_ned): """ - Set the acceleration in NED coordinates. + Set the acceleration in NED coordinates. - Parameters - ---------- - acceleration_ned : AccelerationNed - Acceleration + Parameters + ---------- + acceleration_ned : AccelerationNed + Acceleration - Raises - ------ - OffboardError - If the request fails. The error contains the reason for the failure. + Raises + ------ + OffboardError + If the request fails. The error contains the reason for the failure. """ request = offboard_pb2.SetAccelerationNedRequest() - + acceleration_ned.translate_to_rpc(request.acceleration_ned) - - + response = await self._stub.SetAccelerationNed(request) - result = self._extract_result(response) if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_acceleration_ned()", acceleration_ned) - \ No newline at end of file diff --git a/mavsdk/offboard_pb2.py b/mavsdk/offboard_pb2.py index bbf9ce76..be5f430a 100644 --- a/mavsdk/offboard_pb2.py +++ b/mavsdk/offboard_pb2.py @@ -4,18 +4,15 @@ # source: offboard/offboard.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'offboard/offboard.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "offboard/offboard.proto" ) # @@protoc_insertion_point(imports) @@ -25,112 +22,156 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x17offboard/offboard.proto\x12\x13mavsdk.rpc.offboard\x1a\x14mavsdk_options.proto\"\x0e\n\x0cStartRequest\"M\n\rStartResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"\r\n\x0bStopRequest\"L\n\x0cStopResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"\x11\n\x0fIsActiveRequest\"%\n\x10IsActiveResponse\x12\x11\n\tis_active\x18\x01 \x01(\x08\"E\n\x12SetAttitudeRequest\x12/\n\x08\x61ttitude\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.offboard.Attitude\"S\n\x13SetAttitudeResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"[\n\x19SetActuatorControlRequest\x12>\n\x10\x61\x63tuator_control\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.offboard.ActuatorControl\"Z\n\x1aSetActuatorControlResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"R\n\x16SetAttitudeRateRequest\x12\x38\n\rattitude_rate\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.offboard.AttitudeRate\"W\n\x17SetAttitudeRateResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"V\n\x15SetPositionNedRequest\x12=\n\x10position_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.PositionNedYaw\"V\n\x16SetPositionNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"_\n\x18SetPositionGlobalRequest\x12\x43\n\x13position_global_yaw\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.offboard.PositionGlobalYaw\"Y\n\x19SetPositionGlobalResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"c\n\x16SetVelocityBodyRequest\x12I\n\x16velocity_body_yawspeed\x18\x01 \x01(\x0b\x32).mavsdk.rpc.offboard.VelocityBodyYawspeed\"W\n\x17SetVelocityBodyResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"V\n\x15SetVelocityNedRequest\x12=\n\x10velocity_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.VelocityNedYaw\"V\n\x16SetVelocityNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"\x9d\x01\n\x1dSetPositionVelocityNedRequest\x12=\n\x10position_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.PositionNedYaw\x12=\n\x10velocity_ned_yaw\x18\x02 \x01(\x0b\x32#.mavsdk.rpc.offboard.VelocityNedYaw\"\xe9\x01\n)SetPositionVelocityAccelerationNedRequest\x12=\n\x10position_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.PositionNedYaw\x12=\n\x10velocity_ned_yaw\x18\x02 \x01(\x0b\x32#.mavsdk.rpc.offboard.VelocityNedYaw\x12>\n\x10\x61\x63\x63\x65leration_ned\x18\x03 \x01(\x0b\x32$.mavsdk.rpc.offboard.AccelerationNed\"^\n\x1eSetPositionVelocityNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"j\n*SetPositionVelocityAccelerationNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"[\n\x19SetAccelerationNedRequest\x12>\n\x10\x61\x63\x63\x65leration_ned\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.offboard.AccelerationNed\"Z\n\x1aSetAccelerationNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult\"V\n\x08\x41ttitude\x12\x10\n\x08roll_deg\x18\x01 \x01(\x02\x12\x11\n\tpitch_deg\x18\x02 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x03 \x01(\x02\x12\x14\n\x0cthrust_value\x18\x04 \x01(\x02\"(\n\x14\x41\x63tuatorControlGroup\x12\x10\n\x08\x63ontrols\x18\x01 \x03(\x02\"L\n\x0f\x41\x63tuatorControl\x12\x39\n\x06groups\x18\x01 \x03(\x0b\x32).mavsdk.rpc.offboard.ActuatorControlGroup\"`\n\x0c\x41ttitudeRate\x12\x12\n\nroll_deg_s\x18\x01 \x01(\x02\x12\x13\n\x0bpitch_deg_s\x18\x02 \x01(\x02\x12\x11\n\tyaw_deg_s\x18\x03 \x01(\x02\x12\x14\n\x0cthrust_value\x18\x04 \x01(\x02\"R\n\x0ePositionNedYaw\x12\x0f\n\x07north_m\x18\x01 \x01(\x02\x12\x0e\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x12\x0e\n\x06\x64own_m\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\"\xfc\x01\n\x11PositionGlobalYaw\x12\x0f\n\x07lat_deg\x18\x01 \x01(\x01\x12\x0f\n\x07lon_deg\x18\x02 \x01(\x01\x12\r\n\x05\x61lt_m\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\x12J\n\raltitude_type\x18\x05 \x01(\x0e\x32\x33.mavsdk.rpc.offboard.PositionGlobalYaw.AltitudeType\"Y\n\x0c\x41ltitudeType\x12\x1a\n\x16\x41LTITUDE_TYPE_REL_HOME\x10\x00\x12\x16\n\x12\x41LTITUDE_TYPE_AMSL\x10\x01\x12\x15\n\x11\x41LTITUDE_TYPE_AGL\x10\x02\"h\n\x14VelocityBodyYawspeed\x12\x13\n\x0b\x66orward_m_s\x18\x01 \x01(\x02\x12\x11\n\tright_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\x12\x16\n\x0eyawspeed_deg_s\x18\x04 \x01(\x02\"X\n\x0eVelocityNedYaw\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\"K\n\x0f\x41\x63\x63\x65lerationNed\x12\x12\n\nnorth_m_s2\x18\x01 \x01(\x02\x12\x11\n\teast_m_s2\x18\x02 \x01(\x02\x12\x11\n\tdown_m_s2\x18\x03 \x01(\x02\"\xb5\x02\n\x0eOffboardResult\x12:\n\x06result\x18\x01 \x01(\x0e\x32*.mavsdk.rpc.offboard.OffboardResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xd2\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\x1a\n\x16RESULT_NO_SETPOINT_SET\x10\x07\x12\x11\n\rRESULT_FAILED\x10\x08\x32\xef\x0b\n\x0fOffboardService\x12P\n\x05Start\x12!.mavsdk.rpc.offboard.StartRequest\x1a\".mavsdk.rpc.offboard.StartResponse\"\x00\x12M\n\x04Stop\x12 .mavsdk.rpc.offboard.StopRequest\x1a!.mavsdk.rpc.offboard.StopResponse\"\x00\x12]\n\x08IsActive\x12$.mavsdk.rpc.offboard.IsActiveRequest\x1a%.mavsdk.rpc.offboard.IsActiveResponse\"\x04\x80\xb5\x18\x01\x12\x66\n\x0bSetAttitude\x12\'.mavsdk.rpc.offboard.SetAttitudeRequest\x1a(.mavsdk.rpc.offboard.SetAttitudeResponse\"\x04\x80\xb5\x18\x01\x12{\n\x12SetActuatorControl\x12..mavsdk.rpc.offboard.SetActuatorControlRequest\x1a/.mavsdk.rpc.offboard.SetActuatorControlResponse\"\x04\x80\xb5\x18\x01\x12r\n\x0fSetAttitudeRate\x12+.mavsdk.rpc.offboard.SetAttitudeRateRequest\x1a,.mavsdk.rpc.offboard.SetAttitudeRateResponse\"\x04\x80\xb5\x18\x01\x12o\n\x0eSetPositionNed\x12*.mavsdk.rpc.offboard.SetPositionNedRequest\x1a+.mavsdk.rpc.offboard.SetPositionNedResponse\"\x04\x80\xb5\x18\x01\x12x\n\x11SetPositionGlobal\x12-.mavsdk.rpc.offboard.SetPositionGlobalRequest\x1a..mavsdk.rpc.offboard.SetPositionGlobalResponse\"\x04\x80\xb5\x18\x01\x12r\n\x0fSetVelocityBody\x12+.mavsdk.rpc.offboard.SetVelocityBodyRequest\x1a,.mavsdk.rpc.offboard.SetVelocityBodyResponse\"\x04\x80\xb5\x18\x01\x12o\n\x0eSetVelocityNed\x12*.mavsdk.rpc.offboard.SetVelocityNedRequest\x1a+.mavsdk.rpc.offboard.SetVelocityNedResponse\"\x04\x80\xb5\x18\x01\x12\x87\x01\n\x16SetPositionVelocityNed\x12\x32.mavsdk.rpc.offboard.SetPositionVelocityNedRequest\x1a\x33.mavsdk.rpc.offboard.SetPositionVelocityNedResponse\"\x04\x80\xb5\x18\x01\x12\xab\x01\n\"SetPositionVelocityAccelerationNed\x12>.mavsdk.rpc.offboard.SetPositionVelocityAccelerationNedRequest\x1a?.mavsdk.rpc.offboard.SetPositionVelocityAccelerationNedResponse\"\x04\x80\xb5\x18\x01\x12{\n\x12SetAccelerationNed\x12..mavsdk.rpc.offboard.SetAccelerationNedRequest\x1a/.mavsdk.rpc.offboard.SetAccelerationNedResponse\"\x04\x80\xb5\x18\x01\x42#\n\x12io.mavsdk.offboardB\rOffboardProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x17offboard/offboard.proto\x12\x13mavsdk.rpc.offboard\x1a\x14mavsdk_options.proto"\x0e\n\x0cStartRequest"M\n\rStartResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"\r\n\x0bStopRequest"L\n\x0cStopResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"\x11\n\x0fIsActiveRequest"%\n\x10IsActiveResponse\x12\x11\n\tis_active\x18\x01 \x01(\x08"E\n\x12SetAttitudeRequest\x12/\n\x08\x61ttitude\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.offboard.Attitude"S\n\x13SetAttitudeResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"[\n\x19SetActuatorControlRequest\x12>\n\x10\x61\x63tuator_control\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.offboard.ActuatorControl"Z\n\x1aSetActuatorControlResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"R\n\x16SetAttitudeRateRequest\x12\x38\n\rattitude_rate\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.offboard.AttitudeRate"W\n\x17SetAttitudeRateResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"V\n\x15SetPositionNedRequest\x12=\n\x10position_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.PositionNedYaw"V\n\x16SetPositionNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"_\n\x18SetPositionGlobalRequest\x12\x43\n\x13position_global_yaw\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.offboard.PositionGlobalYaw"Y\n\x19SetPositionGlobalResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"c\n\x16SetVelocityBodyRequest\x12I\n\x16velocity_body_yawspeed\x18\x01 \x01(\x0b\x32).mavsdk.rpc.offboard.VelocityBodyYawspeed"W\n\x17SetVelocityBodyResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"V\n\x15SetVelocityNedRequest\x12=\n\x10velocity_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.VelocityNedYaw"V\n\x16SetVelocityNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"\x9d\x01\n\x1dSetPositionVelocityNedRequest\x12=\n\x10position_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.PositionNedYaw\x12=\n\x10velocity_ned_yaw\x18\x02 \x01(\x0b\x32#.mavsdk.rpc.offboard.VelocityNedYaw"\xe9\x01\n)SetPositionVelocityAccelerationNedRequest\x12=\n\x10position_ned_yaw\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.PositionNedYaw\x12=\n\x10velocity_ned_yaw\x18\x02 \x01(\x0b\x32#.mavsdk.rpc.offboard.VelocityNedYaw\x12>\n\x10\x61\x63\x63\x65leration_ned\x18\x03 \x01(\x0b\x32$.mavsdk.rpc.offboard.AccelerationNed"^\n\x1eSetPositionVelocityNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"j\n*SetPositionVelocityAccelerationNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"[\n\x19SetAccelerationNedRequest\x12>\n\x10\x61\x63\x63\x65leration_ned\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.offboard.AccelerationNed"Z\n\x1aSetAccelerationNedResponse\x12<\n\x0foffboard_result\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.offboard.OffboardResult"V\n\x08\x41ttitude\x12\x10\n\x08roll_deg\x18\x01 \x01(\x02\x12\x11\n\tpitch_deg\x18\x02 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x03 \x01(\x02\x12\x14\n\x0cthrust_value\x18\x04 \x01(\x02"(\n\x14\x41\x63tuatorControlGroup\x12\x10\n\x08\x63ontrols\x18\x01 \x03(\x02"L\n\x0f\x41\x63tuatorControl\x12\x39\n\x06groups\x18\x01 \x03(\x0b\x32).mavsdk.rpc.offboard.ActuatorControlGroup"`\n\x0c\x41ttitudeRate\x12\x12\n\nroll_deg_s\x18\x01 \x01(\x02\x12\x13\n\x0bpitch_deg_s\x18\x02 \x01(\x02\x12\x11\n\tyaw_deg_s\x18\x03 \x01(\x02\x12\x14\n\x0cthrust_value\x18\x04 \x01(\x02"R\n\x0ePositionNedYaw\x12\x0f\n\x07north_m\x18\x01 \x01(\x02\x12\x0e\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x12\x0e\n\x06\x64own_m\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02"\xfc\x01\n\x11PositionGlobalYaw\x12\x0f\n\x07lat_deg\x18\x01 \x01(\x01\x12\x0f\n\x07lon_deg\x18\x02 \x01(\x01\x12\r\n\x05\x61lt_m\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02\x12J\n\raltitude_type\x18\x05 \x01(\x0e\x32\x33.mavsdk.rpc.offboard.PositionGlobalYaw.AltitudeType"Y\n\x0c\x41ltitudeType\x12\x1a\n\x16\x41LTITUDE_TYPE_REL_HOME\x10\x00\x12\x16\n\x12\x41LTITUDE_TYPE_AMSL\x10\x01\x12\x15\n\x11\x41LTITUDE_TYPE_AGL\x10\x02"h\n\x14VelocityBodyYawspeed\x12\x13\n\x0b\x66orward_m_s\x18\x01 \x01(\x02\x12\x11\n\tright_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\x12\x16\n\x0eyawspeed_deg_s\x18\x04 \x01(\x02"X\n\x0eVelocityNedYaw\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x04 \x01(\x02"K\n\x0f\x41\x63\x63\x65lerationNed\x12\x12\n\nnorth_m_s2\x18\x01 \x01(\x02\x12\x11\n\teast_m_s2\x18\x02 \x01(\x02\x12\x11\n\tdown_m_s2\x18\x03 \x01(\x02"\xb5\x02\n\x0eOffboardResult\x12:\n\x06result\x18\x01 \x01(\x0e\x32*.mavsdk.rpc.offboard.OffboardResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xd2\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\x1a\n\x16RESULT_NO_SETPOINT_SET\x10\x07\x12\x11\n\rRESULT_FAILED\x10\x08\x32\xef\x0b\n\x0fOffboardService\x12P\n\x05Start\x12!.mavsdk.rpc.offboard.StartRequest\x1a".mavsdk.rpc.offboard.StartResponse"\x00\x12M\n\x04Stop\x12 .mavsdk.rpc.offboard.StopRequest\x1a!.mavsdk.rpc.offboard.StopResponse"\x00\x12]\n\x08IsActive\x12$.mavsdk.rpc.offboard.IsActiveRequest\x1a%.mavsdk.rpc.offboard.IsActiveResponse"\x04\x80\xb5\x18\x01\x12\x66\n\x0bSetAttitude\x12\'.mavsdk.rpc.offboard.SetAttitudeRequest\x1a(.mavsdk.rpc.offboard.SetAttitudeResponse"\x04\x80\xb5\x18\x01\x12{\n\x12SetActuatorControl\x12..mavsdk.rpc.offboard.SetActuatorControlRequest\x1a/.mavsdk.rpc.offboard.SetActuatorControlResponse"\x04\x80\xb5\x18\x01\x12r\n\x0fSetAttitudeRate\x12+.mavsdk.rpc.offboard.SetAttitudeRateRequest\x1a,.mavsdk.rpc.offboard.SetAttitudeRateResponse"\x04\x80\xb5\x18\x01\x12o\n\x0eSetPositionNed\x12*.mavsdk.rpc.offboard.SetPositionNedRequest\x1a+.mavsdk.rpc.offboard.SetPositionNedResponse"\x04\x80\xb5\x18\x01\x12x\n\x11SetPositionGlobal\x12-.mavsdk.rpc.offboard.SetPositionGlobalRequest\x1a..mavsdk.rpc.offboard.SetPositionGlobalResponse"\x04\x80\xb5\x18\x01\x12r\n\x0fSetVelocityBody\x12+.mavsdk.rpc.offboard.SetVelocityBodyRequest\x1a,.mavsdk.rpc.offboard.SetVelocityBodyResponse"\x04\x80\xb5\x18\x01\x12o\n\x0eSetVelocityNed\x12*.mavsdk.rpc.offboard.SetVelocityNedRequest\x1a+.mavsdk.rpc.offboard.SetVelocityNedResponse"\x04\x80\xb5\x18\x01\x12\x87\x01\n\x16SetPositionVelocityNed\x12\x32.mavsdk.rpc.offboard.SetPositionVelocityNedRequest\x1a\x33.mavsdk.rpc.offboard.SetPositionVelocityNedResponse"\x04\x80\xb5\x18\x01\x12\xab\x01\n"SetPositionVelocityAccelerationNed\x12>.mavsdk.rpc.offboard.SetPositionVelocityAccelerationNedRequest\x1a?.mavsdk.rpc.offboard.SetPositionVelocityAccelerationNedResponse"\x04\x80\xb5\x18\x01\x12{\n\x12SetAccelerationNed\x12..mavsdk.rpc.offboard.SetAccelerationNedRequest\x1a/.mavsdk.rpc.offboard.SetAccelerationNedResponse"\x04\x80\xb5\x18\x01\x42#\n\x12io.mavsdk.offboardB\rOffboardProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'offboard.offboard_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "offboard.offboard_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\022io.mavsdk.offboardB\rOffboardProto' - _globals['_OFFBOARDSERVICE'].methods_by_name['IsActive']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['IsActive']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetAttitude']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetAttitude']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetActuatorControl']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetActuatorControl']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetAttitudeRate']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetAttitudeRate']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionNed']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionNed']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionGlobal']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionGlobal']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetVelocityBody']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetVelocityBody']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetVelocityNed']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetVelocityNed']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionVelocityNed']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionVelocityNed']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionVelocityAccelerationNed']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetPositionVelocityAccelerationNed']._serialized_options = b'\200\265\030\001' - _globals['_OFFBOARDSERVICE'].methods_by_name['SetAccelerationNed']._loaded_options = None - _globals['_OFFBOARDSERVICE'].methods_by_name['SetAccelerationNed']._serialized_options = b'\200\265\030\001' - _globals['_STARTREQUEST']._serialized_start=70 - _globals['_STARTREQUEST']._serialized_end=84 - _globals['_STARTRESPONSE']._serialized_start=86 - _globals['_STARTRESPONSE']._serialized_end=163 - _globals['_STOPREQUEST']._serialized_start=165 - _globals['_STOPREQUEST']._serialized_end=178 - _globals['_STOPRESPONSE']._serialized_start=180 - _globals['_STOPRESPONSE']._serialized_end=256 - _globals['_ISACTIVEREQUEST']._serialized_start=258 - _globals['_ISACTIVEREQUEST']._serialized_end=275 - _globals['_ISACTIVERESPONSE']._serialized_start=277 - _globals['_ISACTIVERESPONSE']._serialized_end=314 - _globals['_SETATTITUDEREQUEST']._serialized_start=316 - _globals['_SETATTITUDEREQUEST']._serialized_end=385 - _globals['_SETATTITUDERESPONSE']._serialized_start=387 - _globals['_SETATTITUDERESPONSE']._serialized_end=470 - _globals['_SETACTUATORCONTROLREQUEST']._serialized_start=472 - _globals['_SETACTUATORCONTROLREQUEST']._serialized_end=563 - _globals['_SETACTUATORCONTROLRESPONSE']._serialized_start=565 - _globals['_SETACTUATORCONTROLRESPONSE']._serialized_end=655 - _globals['_SETATTITUDERATEREQUEST']._serialized_start=657 - _globals['_SETATTITUDERATEREQUEST']._serialized_end=739 - _globals['_SETATTITUDERATERESPONSE']._serialized_start=741 - _globals['_SETATTITUDERATERESPONSE']._serialized_end=828 - _globals['_SETPOSITIONNEDREQUEST']._serialized_start=830 - _globals['_SETPOSITIONNEDREQUEST']._serialized_end=916 - _globals['_SETPOSITIONNEDRESPONSE']._serialized_start=918 - _globals['_SETPOSITIONNEDRESPONSE']._serialized_end=1004 - _globals['_SETPOSITIONGLOBALREQUEST']._serialized_start=1006 - _globals['_SETPOSITIONGLOBALREQUEST']._serialized_end=1101 - _globals['_SETPOSITIONGLOBALRESPONSE']._serialized_start=1103 - _globals['_SETPOSITIONGLOBALRESPONSE']._serialized_end=1192 - _globals['_SETVELOCITYBODYREQUEST']._serialized_start=1194 - _globals['_SETVELOCITYBODYREQUEST']._serialized_end=1293 - _globals['_SETVELOCITYBODYRESPONSE']._serialized_start=1295 - _globals['_SETVELOCITYBODYRESPONSE']._serialized_end=1382 - _globals['_SETVELOCITYNEDREQUEST']._serialized_start=1384 - _globals['_SETVELOCITYNEDREQUEST']._serialized_end=1470 - _globals['_SETVELOCITYNEDRESPONSE']._serialized_start=1472 - _globals['_SETVELOCITYNEDRESPONSE']._serialized_end=1558 - _globals['_SETPOSITIONVELOCITYNEDREQUEST']._serialized_start=1561 - _globals['_SETPOSITIONVELOCITYNEDREQUEST']._serialized_end=1718 - _globals['_SETPOSITIONVELOCITYACCELERATIONNEDREQUEST']._serialized_start=1721 - _globals['_SETPOSITIONVELOCITYACCELERATIONNEDREQUEST']._serialized_end=1954 - _globals['_SETPOSITIONVELOCITYNEDRESPONSE']._serialized_start=1956 - _globals['_SETPOSITIONVELOCITYNEDRESPONSE']._serialized_end=2050 - _globals['_SETPOSITIONVELOCITYACCELERATIONNEDRESPONSE']._serialized_start=2052 - _globals['_SETPOSITIONVELOCITYACCELERATIONNEDRESPONSE']._serialized_end=2158 - _globals['_SETACCELERATIONNEDREQUEST']._serialized_start=2160 - _globals['_SETACCELERATIONNEDREQUEST']._serialized_end=2251 - _globals['_SETACCELERATIONNEDRESPONSE']._serialized_start=2253 - _globals['_SETACCELERATIONNEDRESPONSE']._serialized_end=2343 - _globals['_ATTITUDE']._serialized_start=2345 - _globals['_ATTITUDE']._serialized_end=2431 - _globals['_ACTUATORCONTROLGROUP']._serialized_start=2433 - _globals['_ACTUATORCONTROLGROUP']._serialized_end=2473 - _globals['_ACTUATORCONTROL']._serialized_start=2475 - _globals['_ACTUATORCONTROL']._serialized_end=2551 - _globals['_ATTITUDERATE']._serialized_start=2553 - _globals['_ATTITUDERATE']._serialized_end=2649 - _globals['_POSITIONNEDYAW']._serialized_start=2651 - _globals['_POSITIONNEDYAW']._serialized_end=2733 - _globals['_POSITIONGLOBALYAW']._serialized_start=2736 - _globals['_POSITIONGLOBALYAW']._serialized_end=2988 - _globals['_POSITIONGLOBALYAW_ALTITUDETYPE']._serialized_start=2899 - _globals['_POSITIONGLOBALYAW_ALTITUDETYPE']._serialized_end=2988 - _globals['_VELOCITYBODYYAWSPEED']._serialized_start=2990 - _globals['_VELOCITYBODYYAWSPEED']._serialized_end=3094 - _globals['_VELOCITYNEDYAW']._serialized_start=3096 - _globals['_VELOCITYNEDYAW']._serialized_end=3184 - _globals['_ACCELERATIONNED']._serialized_start=3186 - _globals['_ACCELERATIONNED']._serialized_end=3261 - _globals['_OFFBOARDRESULT']._serialized_start=3264 - _globals['_OFFBOARDRESULT']._serialized_end=3573 - _globals['_OFFBOARDRESULT_RESULT']._serialized_start=3363 - _globals['_OFFBOARDRESULT_RESULT']._serialized_end=3573 - _globals['_OFFBOARDSERVICE']._serialized_start=3576 - _globals['_OFFBOARDSERVICE']._serialized_end=5095 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\022io.mavsdk.offboardB\rOffboardProto" + _globals["_OFFBOARDSERVICE"].methods_by_name["IsActive"]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "IsActive" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name["SetAttitude"]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetAttitude" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetActuatorControl" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetActuatorControl" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetAttitudeRate" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetAttitudeRate" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionNed" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionNed" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionGlobal" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionGlobal" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetVelocityBody" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetVelocityBody" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetVelocityNed" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetVelocityNed" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionVelocityNed" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionVelocityNed" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionVelocityAccelerationNed" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetPositionVelocityAccelerationNed" + ]._serialized_options = b"\200\265\030\001" + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetAccelerationNed" + ]._loaded_options = None + _globals["_OFFBOARDSERVICE"].methods_by_name[ + "SetAccelerationNed" + ]._serialized_options = b"\200\265\030\001" + _globals["_STARTREQUEST"]._serialized_start = 70 + _globals["_STARTREQUEST"]._serialized_end = 84 + _globals["_STARTRESPONSE"]._serialized_start = 86 + _globals["_STARTRESPONSE"]._serialized_end = 163 + _globals["_STOPREQUEST"]._serialized_start = 165 + _globals["_STOPREQUEST"]._serialized_end = 178 + _globals["_STOPRESPONSE"]._serialized_start = 180 + _globals["_STOPRESPONSE"]._serialized_end = 256 + _globals["_ISACTIVEREQUEST"]._serialized_start = 258 + _globals["_ISACTIVEREQUEST"]._serialized_end = 275 + _globals["_ISACTIVERESPONSE"]._serialized_start = 277 + _globals["_ISACTIVERESPONSE"]._serialized_end = 314 + _globals["_SETATTITUDEREQUEST"]._serialized_start = 316 + _globals["_SETATTITUDEREQUEST"]._serialized_end = 385 + _globals["_SETATTITUDERESPONSE"]._serialized_start = 387 + _globals["_SETATTITUDERESPONSE"]._serialized_end = 470 + _globals["_SETACTUATORCONTROLREQUEST"]._serialized_start = 472 + _globals["_SETACTUATORCONTROLREQUEST"]._serialized_end = 563 + _globals["_SETACTUATORCONTROLRESPONSE"]._serialized_start = 565 + _globals["_SETACTUATORCONTROLRESPONSE"]._serialized_end = 655 + _globals["_SETATTITUDERATEREQUEST"]._serialized_start = 657 + _globals["_SETATTITUDERATEREQUEST"]._serialized_end = 739 + _globals["_SETATTITUDERATERESPONSE"]._serialized_start = 741 + _globals["_SETATTITUDERATERESPONSE"]._serialized_end = 828 + _globals["_SETPOSITIONNEDREQUEST"]._serialized_start = 830 + _globals["_SETPOSITIONNEDREQUEST"]._serialized_end = 916 + _globals["_SETPOSITIONNEDRESPONSE"]._serialized_start = 918 + _globals["_SETPOSITIONNEDRESPONSE"]._serialized_end = 1004 + _globals["_SETPOSITIONGLOBALREQUEST"]._serialized_start = 1006 + _globals["_SETPOSITIONGLOBALREQUEST"]._serialized_end = 1101 + _globals["_SETPOSITIONGLOBALRESPONSE"]._serialized_start = 1103 + _globals["_SETPOSITIONGLOBALRESPONSE"]._serialized_end = 1192 + _globals["_SETVELOCITYBODYREQUEST"]._serialized_start = 1194 + _globals["_SETVELOCITYBODYREQUEST"]._serialized_end = 1293 + _globals["_SETVELOCITYBODYRESPONSE"]._serialized_start = 1295 + _globals["_SETVELOCITYBODYRESPONSE"]._serialized_end = 1382 + _globals["_SETVELOCITYNEDREQUEST"]._serialized_start = 1384 + _globals["_SETVELOCITYNEDREQUEST"]._serialized_end = 1470 + _globals["_SETVELOCITYNEDRESPONSE"]._serialized_start = 1472 + _globals["_SETVELOCITYNEDRESPONSE"]._serialized_end = 1558 + _globals["_SETPOSITIONVELOCITYNEDREQUEST"]._serialized_start = 1561 + _globals["_SETPOSITIONVELOCITYNEDREQUEST"]._serialized_end = 1718 + _globals["_SETPOSITIONVELOCITYACCELERATIONNEDREQUEST"]._serialized_start = 1721 + _globals["_SETPOSITIONVELOCITYACCELERATIONNEDREQUEST"]._serialized_end = 1954 + _globals["_SETPOSITIONVELOCITYNEDRESPONSE"]._serialized_start = 1956 + _globals["_SETPOSITIONVELOCITYNEDRESPONSE"]._serialized_end = 2050 + _globals["_SETPOSITIONVELOCITYACCELERATIONNEDRESPONSE"]._serialized_start = 2052 + _globals["_SETPOSITIONVELOCITYACCELERATIONNEDRESPONSE"]._serialized_end = 2158 + _globals["_SETACCELERATIONNEDREQUEST"]._serialized_start = 2160 + _globals["_SETACCELERATIONNEDREQUEST"]._serialized_end = 2251 + _globals["_SETACCELERATIONNEDRESPONSE"]._serialized_start = 2253 + _globals["_SETACCELERATIONNEDRESPONSE"]._serialized_end = 2343 + _globals["_ATTITUDE"]._serialized_start = 2345 + _globals["_ATTITUDE"]._serialized_end = 2431 + _globals["_ACTUATORCONTROLGROUP"]._serialized_start = 2433 + _globals["_ACTUATORCONTROLGROUP"]._serialized_end = 2473 + _globals["_ACTUATORCONTROL"]._serialized_start = 2475 + _globals["_ACTUATORCONTROL"]._serialized_end = 2551 + _globals["_ATTITUDERATE"]._serialized_start = 2553 + _globals["_ATTITUDERATE"]._serialized_end = 2649 + _globals["_POSITIONNEDYAW"]._serialized_start = 2651 + _globals["_POSITIONNEDYAW"]._serialized_end = 2733 + _globals["_POSITIONGLOBALYAW"]._serialized_start = 2736 + _globals["_POSITIONGLOBALYAW"]._serialized_end = 2988 + _globals["_POSITIONGLOBALYAW_ALTITUDETYPE"]._serialized_start = 2899 + _globals["_POSITIONGLOBALYAW_ALTITUDETYPE"]._serialized_end = 2988 + _globals["_VELOCITYBODYYAWSPEED"]._serialized_start = 2990 + _globals["_VELOCITYBODYYAWSPEED"]._serialized_end = 3094 + _globals["_VELOCITYNEDYAW"]._serialized_start = 3096 + _globals["_VELOCITYNEDYAW"]._serialized_end = 3184 + _globals["_ACCELERATIONNED"]._serialized_start = 3186 + _globals["_ACCELERATIONNED"]._serialized_end = 3261 + _globals["_OFFBOARDRESULT"]._serialized_start = 3264 + _globals["_OFFBOARDRESULT"]._serialized_end = 3573 + _globals["_OFFBOARDRESULT_RESULT"]._serialized_start = 3363 + _globals["_OFFBOARDRESULT_RESULT"]._serialized_end = 3573 + _globals["_OFFBOARDSERVICE"]._serialized_start = 3576 + _globals["_OFFBOARDSERVICE"]._serialized_end = 5095 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/offboard_pb2_grpc.py b/mavsdk/offboard_pb2_grpc.py index 64b88c1d..00c741e4 100644 --- a/mavsdk/offboard_pb2_grpc.py +++ b/mavsdk/offboard_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import offboard_pb2 as offboard_dot_offboard__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in offboard/offboard_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in offboard/offboard_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -44,70 +48,83 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.Start = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/Start', - request_serializer=offboard_dot_offboard__pb2.StartRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.StartResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/Start", + request_serializer=offboard_dot_offboard__pb2.StartRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.StartResponse.FromString, + _registered_method=True, + ) self.Stop = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/Stop', - request_serializer=offboard_dot_offboard__pb2.StopRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.StopResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/Stop", + request_serializer=offboard_dot_offboard__pb2.StopRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.StopResponse.FromString, + _registered_method=True, + ) self.IsActive = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/IsActive', - request_serializer=offboard_dot_offboard__pb2.IsActiveRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.IsActiveResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/IsActive", + request_serializer=offboard_dot_offboard__pb2.IsActiveRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.IsActiveResponse.FromString, + _registered_method=True, + ) self.SetAttitude = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetAttitude', - request_serializer=offboard_dot_offboard__pb2.SetAttitudeRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetAttitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetAttitude", + request_serializer=offboard_dot_offboard__pb2.SetAttitudeRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetAttitudeResponse.FromString, + _registered_method=True, + ) self.SetActuatorControl = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetActuatorControl', - request_serializer=offboard_dot_offboard__pb2.SetActuatorControlRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetActuatorControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetActuatorControl", + request_serializer=offboard_dot_offboard__pb2.SetActuatorControlRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetActuatorControlResponse.FromString, + _registered_method=True, + ) self.SetAttitudeRate = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetAttitudeRate', - request_serializer=offboard_dot_offboard__pb2.SetAttitudeRateRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetAttitudeRateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetAttitudeRate", + request_serializer=offboard_dot_offboard__pb2.SetAttitudeRateRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetAttitudeRateResponse.FromString, + _registered_method=True, + ) self.SetPositionNed = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetPositionNed', - request_serializer=offboard_dot_offboard__pb2.SetPositionNedRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetPositionNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetPositionNed", + request_serializer=offboard_dot_offboard__pb2.SetPositionNedRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetPositionNedResponse.FromString, + _registered_method=True, + ) self.SetPositionGlobal = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetPositionGlobal', - request_serializer=offboard_dot_offboard__pb2.SetPositionGlobalRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetPositionGlobalResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetPositionGlobal", + request_serializer=offboard_dot_offboard__pb2.SetPositionGlobalRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetPositionGlobalResponse.FromString, + _registered_method=True, + ) self.SetVelocityBody = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetVelocityBody', - request_serializer=offboard_dot_offboard__pb2.SetVelocityBodyRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetVelocityBodyResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetVelocityBody", + request_serializer=offboard_dot_offboard__pb2.SetVelocityBodyRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetVelocityBodyResponse.FromString, + _registered_method=True, + ) self.SetVelocityNed = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetVelocityNed', - request_serializer=offboard_dot_offboard__pb2.SetVelocityNedRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetVelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetVelocityNed", + request_serializer=offboard_dot_offboard__pb2.SetVelocityNedRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetVelocityNedResponse.FromString, + _registered_method=True, + ) self.SetPositionVelocityNed = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityNed', - request_serializer=offboard_dot_offboard__pb2.SetPositionVelocityNedRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityNed", + request_serializer=offboard_dot_offboard__pb2.SetPositionVelocityNedRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityNedResponse.FromString, + _registered_method=True, + ) self.SetPositionVelocityAccelerationNed = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityAccelerationNed', - request_serializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityAccelerationNed", + request_serializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedResponse.FromString, + _registered_method=True, + ) self.SetAccelerationNed = channel.unary_unary( - '/mavsdk.rpc.offboard.OffboardService/SetAccelerationNed', - request_serializer=offboard_dot_offboard__pb2.SetAccelerationNedRequest.SerializeToString, - response_deserializer=offboard_dot_offboard__pb2.SetAccelerationNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.offboard.OffboardService/SetAccelerationNed", + request_serializer=offboard_dot_offboard__pb2.SetAccelerationNedRequest.SerializeToString, + response_deserializer=offboard_dot_offboard__pb2.SetAccelerationNedResponse.FromString, + _registered_method=True, + ) class OffboardServiceServicer(object): @@ -127,8 +144,8 @@ def Start(self, request, context): Start offboard control. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Stop(self, request, context): """ @@ -137,8 +154,8 @@ def Stop(self, request, context): The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def IsActive(self, request, context): """ @@ -148,16 +165,16 @@ def IsActive(self, request, context): setpoints. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAttitude(self, request, context): """ Set the attitude in terms of roll, pitch and yaw in degrees with thrust. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetActuatorControl(self, request, context): """ @@ -167,149 +184,152 @@ def SetActuatorControl(self, request, context): actuator_control.num_controls more than 8). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAttitudeRate(self, request, context): """ Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetPositionNed(self, request, context): """ Set the position in NED coordinates and yaw. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetPositionGlobal(self, request, context): """ Set the position in Global coordinates (latitude, longitude, altitude) and yaw """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetVelocityBody(self, request, context): """ Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetVelocityNed(self, request, context): """ Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetPositionVelocityNed(self, request, context): """ Set the position in NED coordinates, with the velocity to be used as feed-forward. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetPositionVelocityAccelerationNed(self, request, context): """ Set the position, velocity and acceleration in NED coordinates, with velocity and acceleration used as feed-forward. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetAccelerationNed(self, request, context): """ Set the acceleration in NED coordinates. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_OffboardServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'Start': grpc.unary_unary_rpc_method_handler( - servicer.Start, - request_deserializer=offboard_dot_offboard__pb2.StartRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.StartResponse.SerializeToString, - ), - 'Stop': grpc.unary_unary_rpc_method_handler( - servicer.Stop, - request_deserializer=offboard_dot_offboard__pb2.StopRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.StopResponse.SerializeToString, - ), - 'IsActive': grpc.unary_unary_rpc_method_handler( - servicer.IsActive, - request_deserializer=offboard_dot_offboard__pb2.IsActiveRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.IsActiveResponse.SerializeToString, - ), - 'SetAttitude': grpc.unary_unary_rpc_method_handler( - servicer.SetAttitude, - request_deserializer=offboard_dot_offboard__pb2.SetAttitudeRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetAttitudeResponse.SerializeToString, - ), - 'SetActuatorControl': grpc.unary_unary_rpc_method_handler( - servicer.SetActuatorControl, - request_deserializer=offboard_dot_offboard__pb2.SetActuatorControlRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetActuatorControlResponse.SerializeToString, - ), - 'SetAttitudeRate': grpc.unary_unary_rpc_method_handler( - servicer.SetAttitudeRate, - request_deserializer=offboard_dot_offboard__pb2.SetAttitudeRateRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetAttitudeRateResponse.SerializeToString, - ), - 'SetPositionNed': grpc.unary_unary_rpc_method_handler( - servicer.SetPositionNed, - request_deserializer=offboard_dot_offboard__pb2.SetPositionNedRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetPositionNedResponse.SerializeToString, - ), - 'SetPositionGlobal': grpc.unary_unary_rpc_method_handler( - servicer.SetPositionGlobal, - request_deserializer=offboard_dot_offboard__pb2.SetPositionGlobalRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetPositionGlobalResponse.SerializeToString, - ), - 'SetVelocityBody': grpc.unary_unary_rpc_method_handler( - servicer.SetVelocityBody, - request_deserializer=offboard_dot_offboard__pb2.SetVelocityBodyRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetVelocityBodyResponse.SerializeToString, - ), - 'SetVelocityNed': grpc.unary_unary_rpc_method_handler( - servicer.SetVelocityNed, - request_deserializer=offboard_dot_offboard__pb2.SetVelocityNedRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetVelocityNedResponse.SerializeToString, - ), - 'SetPositionVelocityNed': grpc.unary_unary_rpc_method_handler( - servicer.SetPositionVelocityNed, - request_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityNedRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetPositionVelocityNedResponse.SerializeToString, - ), - 'SetPositionVelocityAccelerationNed': grpc.unary_unary_rpc_method_handler( - servicer.SetPositionVelocityAccelerationNed, - request_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedResponse.SerializeToString, - ), - 'SetAccelerationNed': grpc.unary_unary_rpc_method_handler( - servicer.SetAccelerationNed, - request_deserializer=offboard_dot_offboard__pb2.SetAccelerationNedRequest.FromString, - response_serializer=offboard_dot_offboard__pb2.SetAccelerationNedResponse.SerializeToString, - ), + "Start": grpc.unary_unary_rpc_method_handler( + servicer.Start, + request_deserializer=offboard_dot_offboard__pb2.StartRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.StartResponse.SerializeToString, + ), + "Stop": grpc.unary_unary_rpc_method_handler( + servicer.Stop, + request_deserializer=offboard_dot_offboard__pb2.StopRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.StopResponse.SerializeToString, + ), + "IsActive": grpc.unary_unary_rpc_method_handler( + servicer.IsActive, + request_deserializer=offboard_dot_offboard__pb2.IsActiveRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.IsActiveResponse.SerializeToString, + ), + "SetAttitude": grpc.unary_unary_rpc_method_handler( + servicer.SetAttitude, + request_deserializer=offboard_dot_offboard__pb2.SetAttitudeRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetAttitudeResponse.SerializeToString, + ), + "SetActuatorControl": grpc.unary_unary_rpc_method_handler( + servicer.SetActuatorControl, + request_deserializer=offboard_dot_offboard__pb2.SetActuatorControlRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetActuatorControlResponse.SerializeToString, + ), + "SetAttitudeRate": grpc.unary_unary_rpc_method_handler( + servicer.SetAttitudeRate, + request_deserializer=offboard_dot_offboard__pb2.SetAttitudeRateRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetAttitudeRateResponse.SerializeToString, + ), + "SetPositionNed": grpc.unary_unary_rpc_method_handler( + servicer.SetPositionNed, + request_deserializer=offboard_dot_offboard__pb2.SetPositionNedRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetPositionNedResponse.SerializeToString, + ), + "SetPositionGlobal": grpc.unary_unary_rpc_method_handler( + servicer.SetPositionGlobal, + request_deserializer=offboard_dot_offboard__pb2.SetPositionGlobalRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetPositionGlobalResponse.SerializeToString, + ), + "SetVelocityBody": grpc.unary_unary_rpc_method_handler( + servicer.SetVelocityBody, + request_deserializer=offboard_dot_offboard__pb2.SetVelocityBodyRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetVelocityBodyResponse.SerializeToString, + ), + "SetVelocityNed": grpc.unary_unary_rpc_method_handler( + servicer.SetVelocityNed, + request_deserializer=offboard_dot_offboard__pb2.SetVelocityNedRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetVelocityNedResponse.SerializeToString, + ), + "SetPositionVelocityNed": grpc.unary_unary_rpc_method_handler( + servicer.SetPositionVelocityNed, + request_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityNedRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetPositionVelocityNedResponse.SerializeToString, + ), + "SetPositionVelocityAccelerationNed": grpc.unary_unary_rpc_method_handler( + servicer.SetPositionVelocityAccelerationNed, + request_deserializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedResponse.SerializeToString, + ), + "SetAccelerationNed": grpc.unary_unary_rpc_method_handler( + servicer.SetAccelerationNed, + request_deserializer=offboard_dot_offboard__pb2.SetAccelerationNedRequest.FromString, + response_serializer=offboard_dot_offboard__pb2.SetAccelerationNedResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.offboard.OffboardService', rpc_method_handlers) + "mavsdk.rpc.offboard.OffboardService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.offboard.OffboardService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.offboard.OffboardService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class OffboardService(object): """ Control a drone with position, velocity, attitude or motor commands. @@ -323,20 +343,22 @@ class OffboardService(object): """ @staticmethod - def Start(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Start( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/Start', + "/mavsdk.rpc.offboard.OffboardService/Start", offboard_dot_offboard__pb2.StartRequest.SerializeToString, offboard_dot_offboard__pb2.StartResponse.FromString, options, @@ -347,23 +369,26 @@ def Start(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Stop(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Stop( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/Stop', + "/mavsdk.rpc.offboard.OffboardService/Stop", offboard_dot_offboard__pb2.StopRequest.SerializeToString, offboard_dot_offboard__pb2.StopResponse.FromString, options, @@ -374,23 +399,26 @@ def Stop(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def IsActive(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def IsActive( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/IsActive', + "/mavsdk.rpc.offboard.OffboardService/IsActive", offboard_dot_offboard__pb2.IsActiveRequest.SerializeToString, offboard_dot_offboard__pb2.IsActiveResponse.FromString, options, @@ -401,23 +429,26 @@ def IsActive(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAttitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAttitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetAttitude', + "/mavsdk.rpc.offboard.OffboardService/SetAttitude", offboard_dot_offboard__pb2.SetAttitudeRequest.SerializeToString, offboard_dot_offboard__pb2.SetAttitudeResponse.FromString, options, @@ -428,23 +459,26 @@ def SetAttitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetActuatorControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetActuatorControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetActuatorControl', + "/mavsdk.rpc.offboard.OffboardService/SetActuatorControl", offboard_dot_offboard__pb2.SetActuatorControlRequest.SerializeToString, offboard_dot_offboard__pb2.SetActuatorControlResponse.FromString, options, @@ -455,23 +489,26 @@ def SetActuatorControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAttitudeRate(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAttitudeRate( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetAttitudeRate', + "/mavsdk.rpc.offboard.OffboardService/SetAttitudeRate", offboard_dot_offboard__pb2.SetAttitudeRateRequest.SerializeToString, offboard_dot_offboard__pb2.SetAttitudeRateResponse.FromString, options, @@ -482,23 +519,26 @@ def SetAttitudeRate(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetPositionNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetPositionNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetPositionNed', + "/mavsdk.rpc.offboard.OffboardService/SetPositionNed", offboard_dot_offboard__pb2.SetPositionNedRequest.SerializeToString, offboard_dot_offboard__pb2.SetPositionNedResponse.FromString, options, @@ -509,23 +549,26 @@ def SetPositionNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetPositionGlobal(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetPositionGlobal( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetPositionGlobal', + "/mavsdk.rpc.offboard.OffboardService/SetPositionGlobal", offboard_dot_offboard__pb2.SetPositionGlobalRequest.SerializeToString, offboard_dot_offboard__pb2.SetPositionGlobalResponse.FromString, options, @@ -536,23 +579,26 @@ def SetPositionGlobal(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetVelocityBody(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetVelocityBody( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetVelocityBody', + "/mavsdk.rpc.offboard.OffboardService/SetVelocityBody", offboard_dot_offboard__pb2.SetVelocityBodyRequest.SerializeToString, offboard_dot_offboard__pb2.SetVelocityBodyResponse.FromString, options, @@ -563,23 +609,26 @@ def SetVelocityBody(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetVelocityNed', + "/mavsdk.rpc.offboard.OffboardService/SetVelocityNed", offboard_dot_offboard__pb2.SetVelocityNedRequest.SerializeToString, offboard_dot_offboard__pb2.SetVelocityNedResponse.FromString, options, @@ -590,23 +639,26 @@ def SetVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetPositionVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetPositionVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityNed', + "/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityNed", offboard_dot_offboard__pb2.SetPositionVelocityNedRequest.SerializeToString, offboard_dot_offboard__pb2.SetPositionVelocityNedResponse.FromString, options, @@ -617,23 +669,26 @@ def SetPositionVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetPositionVelocityAccelerationNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetPositionVelocityAccelerationNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityAccelerationNed', + "/mavsdk.rpc.offboard.OffboardService/SetPositionVelocityAccelerationNed", offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedRequest.SerializeToString, offboard_dot_offboard__pb2.SetPositionVelocityAccelerationNedResponse.FromString, options, @@ -644,23 +699,26 @@ def SetPositionVelocityAccelerationNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetAccelerationNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetAccelerationNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.offboard.OffboardService/SetAccelerationNed', + "/mavsdk.rpc.offboard.OffboardService/SetAccelerationNed", offboard_dot_offboard__pb2.SetAccelerationNedRequest.SerializeToString, offboard_dot_offboard__pb2.SetAccelerationNedResponse.FromString, options, @@ -671,4 +729,5 @@ def SetAccelerationNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/param.py b/mavsdk/param.py index ff90f71e..2bd98ae1 100644 --- a/mavsdk/param.py +++ b/mavsdk/param.py @@ -8,19 +8,18 @@ class ProtocolVersion(Enum): """ - Parameter version + Parameter version - Values - ------ - V1 - Original v1 version + Values + ------ + V1 + Original v1 version - EXT - Extended param version + EXT + Extended param version - """ + """ - V1 = 0 EXT = 1 @@ -32,7 +31,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == param_pb2.PROTOCOL_VERSION_V1: return ProtocolVersion.V1 if rpc_enum_value == param_pb2.PROTOCOL_VERSION_EXT: @@ -44,389 +43,304 @@ def __str__(self): class IntParam: """ - Type for integer parameters. - - Parameters - ---------- - name : std::string - Name of the parameter + Type for integer parameters. - value : int32_t - Value of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - """ + value : int32_t + Value of the parameter - + """ - def __init__( - self, - name, - value): - """ Initializes the IntParam object """ + def __init__(self, name, value): + """Initializes the IntParam object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two IntParam are the same """ + """Checks if two IntParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # IntParam object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ IntParam in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """IntParam in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"IntParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcIntParam): - """ Translates a gRPC struct to the SDK equivalent """ - return IntParam( - - rpcIntParam.name, - - - rpcIntParam.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return IntParam(rpcIntParam.name, rpcIntParam.value) def translate_to_rpc(self, rpcIntParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcIntParam.name = self.name - - - - - + rpcIntParam.value = self.value - - - class FloatParam: """ - Type for float parameters. + Type for float parameters. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - value : float - Value of the parameter + value : float + Value of the parameter - """ - - + """ - def __init__( - self, - name, - value): - """ Initializes the FloatParam object """ + def __init__(self, name, value): + """Initializes the FloatParam object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two FloatParam are the same """ + """Checks if two FloatParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # FloatParam object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ FloatParam in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """FloatParam in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"FloatParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFloatParam): - """ Translates a gRPC struct to the SDK equivalent """ - return FloatParam( - - rpcFloatParam.name, - - - rpcFloatParam.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return FloatParam(rpcFloatParam.name, rpcFloatParam.value) def translate_to_rpc(self, rpcFloatParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFloatParam.name = self.name - - - - - + rpcFloatParam.value = self.value - - - class CustomParam: """ - Type for custom parameters - - Parameters - ---------- - name : std::string - Name of the parameter + Type for custom parameters - value : std::string - Value of the parameter (max len 128 bytes) + Parameters + ---------- + name : std::string + Name of the parameter - """ + value : std::string + Value of the parameter (max len 128 bytes) - + """ - def __init__( - self, - name, - value): - """ Initializes the CustomParam object """ + def __init__(self, name, value): + """Initializes the CustomParam object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two CustomParam are the same """ + """Checks if two CustomParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # CustomParam object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ CustomParam in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """CustomParam in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"CustomParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCustomParam): - """ Translates a gRPC struct to the SDK equivalent """ - return CustomParam( - - rpcCustomParam.name, - - - rpcCustomParam.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return CustomParam(rpcCustomParam.name, rpcCustomParam.value) def translate_to_rpc(self, rpcCustomParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCustomParam.name = self.name - - - - - + rpcCustomParam.value = self.value - - - class AllParams: """ - Type collecting all integer, float, and custom parameters. + Type collecting all integer, float, and custom parameters. - Parameters - ---------- - int_params : [IntParam] - Collection of all parameter names and values of type int + Parameters + ---------- + int_params : [IntParam] + Collection of all parameter names and values of type int - float_params : [FloatParam] - Collection of all parameter names and values of type float + float_params : [FloatParam] + Collection of all parameter names and values of type float - custom_params : [CustomParam] - Collection of all parameter names and values of type custom + custom_params : [CustomParam] + Collection of all parameter names and values of type custom - """ - - + """ - def __init__( - self, - int_params, - float_params, - custom_params): - """ Initializes the AllParams object """ + def __init__(self, int_params, float_params, custom_params): + """Initializes the AllParams object""" self.int_params = int_params self.float_params = float_params self.custom_params = custom_params def __eq__(self, to_compare): - """ Checks if two AllParams are the same """ + """Checks if two AllParams are the same""" try: # Try to compare - this likely fails when it is compared to a non # AllParams object - return \ - (self.int_params == to_compare.int_params) and \ - (self.float_params == to_compare.float_params) and \ - (self.custom_params == to_compare.custom_params) + return ( + (self.int_params == to_compare.int_params) + and (self.float_params == to_compare.float_params) + and (self.custom_params == to_compare.custom_params) + ) except AttributeError: return False def __str__(self): - """ AllParams in string representation """ - struct_repr = ", ".join([ + """AllParams in string representation""" + struct_repr = ", ".join( + [ "int_params: " + str(self.int_params), "float_params: " + str(self.float_params), - "custom_params: " + str(self.custom_params) - ]) + "custom_params: " + str(self.custom_params), + ] + ) return f"AllParams: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAllParams): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AllParams( - - list(map(lambda elem: IntParam.translate_from_rpc(elem), rpcAllParams.int_params)), - - - list(map(lambda elem: FloatParam.translate_from_rpc(elem), rpcAllParams.float_params)), - - - list(map(lambda elem: CustomParam.translate_from_rpc(elem), rpcAllParams.custom_params)) + list( + map( + lambda elem: IntParam.translate_from_rpc(elem), + rpcAllParams.int_params, ) + ), + list( + map( + lambda elem: FloatParam.translate_from_rpc(elem), + rpcAllParams.float_params, + ) + ), + list( + map( + lambda elem: CustomParam.translate_from_rpc(elem), + rpcAllParams.custom_params, + ) + ), + ) def translate_to_rpc(self, rpcAllParams): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.int_params: - rpc_elem = param_pb2.IntParam() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcAllParams.int_params.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.float_params: - rpc_elem = param_pb2.FloatParam() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcAllParams.float_params.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.custom_params: - rpc_elem = param_pb2.CustomParam() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcAllParams.custom_params.extend(rpc_elems_list) - - - class ParamResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for param requests. + Possible results returned for param requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - TIMEOUT - Request timed out + TIMEOUT + Request timed out - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - WRONG_TYPE - Wrong type + WRONG_TYPE + Wrong type - PARAM_NAME_TOO_LONG - Parameter name too long (> 16) + PARAM_NAME_TOO_LONG + Parameter name too long (> 16) - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - PARAM_VALUE_TOO_LONG - Param value too long (> 128) + PARAM_VALUE_TOO_LONG + Param value too long (> 128) - FAILED - Operation failed. + FAILED + Operation failed. - """ + """ - UNKNOWN = 0 SUCCESS = 1 TIMEOUT = 2 @@ -459,7 +373,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == param_pb2.ParamResult.RESULT_UNKNOWN: return ParamResult.Result.UNKNOWN if rpc_enum_value == param_pb2.ParamResult.RESULT_SUCCESS: @@ -481,69 +395,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ParamResult object """ + def __init__(self, result, result_str): + """Initializes the ParamResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ParamResult are the same """ + """Checks if two ParamResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ParamResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ParamResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ParamResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ParamResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcParamResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ParamResult( - - ParamResult.Result.translate_from_rpc(rpcParamResult.result), - - - rpcParamResult.result_str - ) + ParamResult.Result.translate_from_rpc(rpcParamResult.result), + rpcParamResult.result_str, + ) def translate_to_rpc(self, rpcParamResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcParamResult.result = self.result.translate_to_rpc() - - - - - - rpcParamResult.result_str = self.result_str - - - + rpcParamResult.result_str = self.result_str class ParamError(Exception): - """ Raised when a ParamResult is a fail code """ + """Raised when a ParamResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -556,81 +451,75 @@ def __str__(self): class Param(AsyncBase): """ - Provide raw access to get and set parameters. + Provide raw access to get and set parameters. - Generated by dcsdkgen - MAVSDK Param API + Generated by dcsdkgen - MAVSDK Param API """ # Plugin name name = "Param" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = param_pb2_grpc.ParamServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ParamResult.translate_from_rpc(response.param_result) - async def get_param_int(self, name): """ - Get an int parameter. + Get an int parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - Returns - ------- - value : int32_t - Value of the requested parameter + Returns + ------- + value : int32_t + Value of the requested parameter - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.GetParamIntRequest() - - + request.name = name - + response = await self._stub.GetParamInt(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "get_param_int()", name) - return response.value - async def set_param_int(self, name, value): """ - Set an int parameter. + Set an int parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter to set + Parameters + ---------- + name : std::string + Name of the parameter to set - value : int32_t - Value the parameter should be set to + value : int32_t + Value the parameter should be set to - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.SetParamIntRequest() @@ -638,70 +527,64 @@ async def set_param_int(self, name, value): request.value = value response = await self._stub.SetParamInt(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "set_param_int()", name, value) - async def get_param_float(self, name): """ - Get a float parameter. + Get a float parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - Returns - ------- - value : float - Value of the requested parameter + Returns + ------- + value : float + Value of the requested parameter - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.GetParamFloatRequest() - - + request.name = name - + response = await self._stub.GetParamFloat(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "get_param_float()", name) - return response.value - async def set_param_float(self, name, value): """ - Set a float parameter. + Set a float parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter to set + Parameters + ---------- + name : std::string + Name of the parameter to set - value : float - Value the parameter should be set to + value : float + Value the parameter should be set to - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.SetParamFloatRequest() @@ -709,70 +592,64 @@ async def set_param_float(self, name, value): request.value = value response = await self._stub.SetParamFloat(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "set_param_float()", name, value) - async def get_param_custom(self, name): """ - Get a custom parameter. + Get a custom parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - Returns - ------- - value : std::string - Value of the requested parameter + Returns + ------- + value : std::string + Value of the requested parameter - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.GetParamCustomRequest() - - + request.name = name - + response = await self._stub.GetParamCustom(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "get_param_custom()", name) - return response.value - async def set_param_custom(self, name, value): """ - Set a custom parameter. + Set a custom parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter to set + Parameters + ---------- + name : std::string + Name of the parameter to set - value : std::string - Value the parameter should be set to + value : std::string + Value the parameter should be set to - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.SetParamCustomRequest() @@ -780,64 +657,58 @@ async def set_param_custom(self, name, value): request.value = value response = await self._stub.SetParamCustom(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "set_param_custom()", name, value) - async def get_all_params(self): """ - Get all parameters. + Get all parameters. + + Returns + ------- + params : AllParams + Collection of all parameters - Returns - ------- - params : AllParams - Collection of all parameters - """ request = param_pb2.GetAllParamsRequest() response = await self._stub.GetAllParams(request) - - return AllParams.translate_from_rpc(response.params) - async def select_component(self, component_id, protocol_version): """ - Select component ID of parameter component to talk to and param protocol version. + Select component ID of parameter component to talk to and param protocol version. - Default is the autopilot component (1), and Version (0). + Default is the autopilot component (1), and Version (0). - Parameters - ---------- - component_id : int32_t - MAVLink component Id of component to select + Parameters + ---------- + component_id : int32_t + MAVLink component Id of component to select - protocol_version : ProtocolVersion - Protocol version + protocol_version : ProtocolVersion + Protocol version - Raises - ------ - ParamError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamError + If the request fails. The error contains the reason for the failure. """ request = param_pb2.SelectComponentRequest() request.component_id = component_id - + request.protocol_version = protocol_version.translate_to_rpc() - - + response = await self._stub.SelectComponent(request) - result = self._extract_result(response) if result.result != ParamResult.Result.SUCCESS: - raise ParamError(result, "select_component()", component_id, protocol_version) - \ No newline at end of file + raise ParamError( + result, "select_component()", component_id, protocol_version + ) diff --git a/mavsdk/param_pb2.py b/mavsdk/param_pb2.py index 1875c2b5..5b9cce95 100644 --- a/mavsdk/param_pb2.py +++ b/mavsdk/param_pb2.py @@ -4,18 +4,15 @@ # source: param/param.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'param/param.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "param/param.proto" ) # @@protoc_insertion_point(imports) @@ -25,76 +22,94 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x11param/param.proto\x12\x10mavsdk.rpc.param\x1a\x14mavsdk_options.proto\"\"\n\x12GetParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\"Y\n\x13GetParamIntResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\x12\r\n\x05value\x18\x02 \x01(\x05\"1\n\x12SetParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05\"J\n\x13SetParamIntResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\"$\n\x14GetParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\"[\n\x15GetParamFloatResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\x12\r\n\x05value\x18\x02 \x01(\x02\"3\n\x14SetParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02\"L\n\x15SetParamFloatResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\"%\n\x15GetParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\"\\\n\x16GetParamCustomResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\x12\r\n\x05value\x18\x02 \x01(\t\"4\n\x15SetParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t\"M\n\x16SetParamCustomResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\"\x15\n\x13GetAllParamsRequest\"C\n\x14GetAllParamsResponse\x12+\n\x06params\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.param.AllParams\"N\n\x17SelectComponentResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\"k\n\x16SelectComponentRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12;\n\x10protocol_version\x18\x02 \x01(\x0e\x32!.mavsdk.rpc.param.ProtocolVersion\"\'\n\x08IntParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05\")\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02\"*\n\x0b\x43ustomParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t\"\xa5\x01\n\tAllParams\x12.\n\nint_params\x18\x01 \x03(\x0b\x32\x1a.mavsdk.rpc.param.IntParam\x12\x32\n\x0c\x66loat_params\x18\x02 \x03(\x0b\x32\x1c.mavsdk.rpc.param.FloatParam\x12\x34\n\rcustom_params\x18\x03 \x03(\x0b\x32\x1d.mavsdk.rpc.param.CustomParam\"\xbc\x02\n\x0bParamResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.param.ParamResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xe2\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x12\n\x0eRESULT_TIMEOUT\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x15\n\x11RESULT_WRONG_TYPE\x10\x04\x12\x1e\n\x1aRESULT_PARAM_NAME_TOO_LONG\x10\x05\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x06\x12\x1f\n\x1bRESULT_PARAM_VALUE_TOO_LONG\x10\x07\x12\x11\n\rRESULT_FAILED\x10\x08*D\n\x0fProtocolVersion\x12\x17\n\x13PROTOCOL_VERSION_V1\x10\x00\x12\x18\n\x14PROTOCOL_VERSION_EXT\x10\x01\x32\xcb\x06\n\x0cParamService\x12`\n\x0bGetParamInt\x12$.mavsdk.rpc.param.GetParamIntRequest\x1a%.mavsdk.rpc.param.GetParamIntResponse\"\x04\x80\xb5\x18\x01\x12`\n\x0bSetParamInt\x12$.mavsdk.rpc.param.SetParamIntRequest\x1a%.mavsdk.rpc.param.SetParamIntResponse\"\x04\x80\xb5\x18\x01\x12\x66\n\rGetParamFloat\x12&.mavsdk.rpc.param.GetParamFloatRequest\x1a\'.mavsdk.rpc.param.GetParamFloatResponse\"\x04\x80\xb5\x18\x01\x12\x66\n\rSetParamFloat\x12&.mavsdk.rpc.param.SetParamFloatRequest\x1a\'.mavsdk.rpc.param.SetParamFloatResponse\"\x04\x80\xb5\x18\x01\x12i\n\x0eGetParamCustom\x12\'.mavsdk.rpc.param.GetParamCustomRequest\x1a(.mavsdk.rpc.param.GetParamCustomResponse\"\x04\x80\xb5\x18\x01\x12i\n\x0eSetParamCustom\x12\'.mavsdk.rpc.param.SetParamCustomRequest\x1a(.mavsdk.rpc.param.SetParamCustomResponse\"\x04\x80\xb5\x18\x01\x12\x63\n\x0cGetAllParams\x12%.mavsdk.rpc.param.GetAllParamsRequest\x1a&.mavsdk.rpc.param.GetAllParamsResponse\"\x04\x80\xb5\x18\x01\x12l\n\x0fSelectComponent\x12(.mavsdk.rpc.param.SelectComponentRequest\x1a).mavsdk.rpc.param.SelectComponentResponse\"\x04\x80\xb5\x18\x01\x42\x1d\n\x0fio.mavsdk.paramB\nParamProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x11param/param.proto\x12\x10mavsdk.rpc.param\x1a\x14mavsdk_options.proto""\n\x12GetParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t"Y\n\x13GetParamIntResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\x12\r\n\x05value\x18\x02 \x01(\x05"1\n\x12SetParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05"J\n\x13SetParamIntResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult"$\n\x14GetParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t"[\n\x15GetParamFloatResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\x12\r\n\x05value\x18\x02 \x01(\x02"3\n\x14SetParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02"L\n\x15SetParamFloatResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult"%\n\x15GetParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t"\\\n\x16GetParamCustomResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult\x12\r\n\x05value\x18\x02 \x01(\t"4\n\x15SetParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t"M\n\x16SetParamCustomResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult"\x15\n\x13GetAllParamsRequest"C\n\x14GetAllParamsResponse\x12+\n\x06params\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.param.AllParams"N\n\x17SelectComponentResponse\x12\x33\n\x0cparam_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.param.ParamResult"k\n\x16SelectComponentRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\x05\x12;\n\x10protocol_version\x18\x02 \x01(\x0e\x32!.mavsdk.rpc.param.ProtocolVersion"\'\n\x08IntParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05")\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02"*\n\x0b\x43ustomParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t"\xa5\x01\n\tAllParams\x12.\n\nint_params\x18\x01 \x03(\x0b\x32\x1a.mavsdk.rpc.param.IntParam\x12\x32\n\x0c\x66loat_params\x18\x02 \x03(\x0b\x32\x1c.mavsdk.rpc.param.FloatParam\x12\x34\n\rcustom_params\x18\x03 \x03(\x0b\x32\x1d.mavsdk.rpc.param.CustomParam"\xbc\x02\n\x0bParamResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.param.ParamResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xe2\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x12\n\x0eRESULT_TIMEOUT\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x15\n\x11RESULT_WRONG_TYPE\x10\x04\x12\x1e\n\x1aRESULT_PARAM_NAME_TOO_LONG\x10\x05\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x06\x12\x1f\n\x1bRESULT_PARAM_VALUE_TOO_LONG\x10\x07\x12\x11\n\rRESULT_FAILED\x10\x08*D\n\x0fProtocolVersion\x12\x17\n\x13PROTOCOL_VERSION_V1\x10\x00\x12\x18\n\x14PROTOCOL_VERSION_EXT\x10\x01\x32\xcb\x06\n\x0cParamService\x12`\n\x0bGetParamInt\x12$.mavsdk.rpc.param.GetParamIntRequest\x1a%.mavsdk.rpc.param.GetParamIntResponse"\x04\x80\xb5\x18\x01\x12`\n\x0bSetParamInt\x12$.mavsdk.rpc.param.SetParamIntRequest\x1a%.mavsdk.rpc.param.SetParamIntResponse"\x04\x80\xb5\x18\x01\x12\x66\n\rGetParamFloat\x12&.mavsdk.rpc.param.GetParamFloatRequest\x1a\'.mavsdk.rpc.param.GetParamFloatResponse"\x04\x80\xb5\x18\x01\x12\x66\n\rSetParamFloat\x12&.mavsdk.rpc.param.SetParamFloatRequest\x1a\'.mavsdk.rpc.param.SetParamFloatResponse"\x04\x80\xb5\x18\x01\x12i\n\x0eGetParamCustom\x12\'.mavsdk.rpc.param.GetParamCustomRequest\x1a(.mavsdk.rpc.param.GetParamCustomResponse"\x04\x80\xb5\x18\x01\x12i\n\x0eSetParamCustom\x12\'.mavsdk.rpc.param.SetParamCustomRequest\x1a(.mavsdk.rpc.param.SetParamCustomResponse"\x04\x80\xb5\x18\x01\x12\x63\n\x0cGetAllParams\x12%.mavsdk.rpc.param.GetAllParamsRequest\x1a&.mavsdk.rpc.param.GetAllParamsResponse"\x04\x80\xb5\x18\x01\x12l\n\x0fSelectComponent\x12(.mavsdk.rpc.param.SelectComponentRequest\x1a).mavsdk.rpc.param.SelectComponentResponse"\x04\x80\xb5\x18\x01\x42\x1d\n\x0fio.mavsdk.paramB\nParamProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'param.param_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "param.param_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\017io.mavsdk.paramB\nParamProto' - _globals['_PARAMSERVICE'].methods_by_name['GetParamInt']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['GetParamInt']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['SetParamInt']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['SetParamInt']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['GetParamFloat']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['GetParamFloat']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['SetParamFloat']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['SetParamFloat']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['GetParamCustom']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['GetParamCustom']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['SetParamCustom']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['SetParamCustom']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['GetAllParams']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['GetAllParams']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVICE'].methods_by_name['SelectComponent']._loaded_options = None - _globals['_PARAMSERVICE'].methods_by_name['SelectComponent']._serialized_options = b'\200\265\030\001' - _globals['_PROTOCOLVERSION']._serialized_start=1739 - _globals['_PROTOCOLVERSION']._serialized_end=1807 - _globals['_GETPARAMINTREQUEST']._serialized_start=61 - _globals['_GETPARAMINTREQUEST']._serialized_end=95 - _globals['_GETPARAMINTRESPONSE']._serialized_start=97 - _globals['_GETPARAMINTRESPONSE']._serialized_end=186 - _globals['_SETPARAMINTREQUEST']._serialized_start=188 - _globals['_SETPARAMINTREQUEST']._serialized_end=237 - _globals['_SETPARAMINTRESPONSE']._serialized_start=239 - _globals['_SETPARAMINTRESPONSE']._serialized_end=313 - _globals['_GETPARAMFLOATREQUEST']._serialized_start=315 - _globals['_GETPARAMFLOATREQUEST']._serialized_end=351 - _globals['_GETPARAMFLOATRESPONSE']._serialized_start=353 - _globals['_GETPARAMFLOATRESPONSE']._serialized_end=444 - _globals['_SETPARAMFLOATREQUEST']._serialized_start=446 - _globals['_SETPARAMFLOATREQUEST']._serialized_end=497 - _globals['_SETPARAMFLOATRESPONSE']._serialized_start=499 - _globals['_SETPARAMFLOATRESPONSE']._serialized_end=575 - _globals['_GETPARAMCUSTOMREQUEST']._serialized_start=577 - _globals['_GETPARAMCUSTOMREQUEST']._serialized_end=614 - _globals['_GETPARAMCUSTOMRESPONSE']._serialized_start=616 - _globals['_GETPARAMCUSTOMRESPONSE']._serialized_end=708 - _globals['_SETPARAMCUSTOMREQUEST']._serialized_start=710 - _globals['_SETPARAMCUSTOMREQUEST']._serialized_end=762 - _globals['_SETPARAMCUSTOMRESPONSE']._serialized_start=764 - _globals['_SETPARAMCUSTOMRESPONSE']._serialized_end=841 - _globals['_GETALLPARAMSREQUEST']._serialized_start=843 - _globals['_GETALLPARAMSREQUEST']._serialized_end=864 - _globals['_GETALLPARAMSRESPONSE']._serialized_start=866 - _globals['_GETALLPARAMSRESPONSE']._serialized_end=933 - _globals['_SELECTCOMPONENTRESPONSE']._serialized_start=935 - _globals['_SELECTCOMPONENTRESPONSE']._serialized_end=1013 - _globals['_SELECTCOMPONENTREQUEST']._serialized_start=1015 - _globals['_SELECTCOMPONENTREQUEST']._serialized_end=1122 - _globals['_INTPARAM']._serialized_start=1124 - _globals['_INTPARAM']._serialized_end=1163 - _globals['_FLOATPARAM']._serialized_start=1165 - _globals['_FLOATPARAM']._serialized_end=1206 - _globals['_CUSTOMPARAM']._serialized_start=1208 - _globals['_CUSTOMPARAM']._serialized_end=1250 - _globals['_ALLPARAMS']._serialized_start=1253 - _globals['_ALLPARAMS']._serialized_end=1418 - _globals['_PARAMRESULT']._serialized_start=1421 - _globals['_PARAMRESULT']._serialized_end=1737 - _globals['_PARAMRESULT_RESULT']._serialized_start=1511 - _globals['_PARAMRESULT_RESULT']._serialized_end=1737 - _globals['_PARAMSERVICE']._serialized_start=1810 - _globals['_PARAMSERVICE']._serialized_end=2653 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\017io.mavsdk.paramB\nParamProto" + _globals["_PARAMSERVICE"].methods_by_name["GetParamInt"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "GetParamInt" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["SetParamInt"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "SetParamInt" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["GetParamFloat"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "GetParamFloat" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["SetParamFloat"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "SetParamFloat" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["GetParamCustom"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "GetParamCustom" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["SetParamCustom"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "SetParamCustom" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["GetAllParams"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "GetAllParams" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVICE"].methods_by_name["SelectComponent"]._loaded_options = None + _globals["_PARAMSERVICE"].methods_by_name[ + "SelectComponent" + ]._serialized_options = b"\200\265\030\001" + _globals["_PROTOCOLVERSION"]._serialized_start = 1739 + _globals["_PROTOCOLVERSION"]._serialized_end = 1807 + _globals["_GETPARAMINTREQUEST"]._serialized_start = 61 + _globals["_GETPARAMINTREQUEST"]._serialized_end = 95 + _globals["_GETPARAMINTRESPONSE"]._serialized_start = 97 + _globals["_GETPARAMINTRESPONSE"]._serialized_end = 186 + _globals["_SETPARAMINTREQUEST"]._serialized_start = 188 + _globals["_SETPARAMINTREQUEST"]._serialized_end = 237 + _globals["_SETPARAMINTRESPONSE"]._serialized_start = 239 + _globals["_SETPARAMINTRESPONSE"]._serialized_end = 313 + _globals["_GETPARAMFLOATREQUEST"]._serialized_start = 315 + _globals["_GETPARAMFLOATREQUEST"]._serialized_end = 351 + _globals["_GETPARAMFLOATRESPONSE"]._serialized_start = 353 + _globals["_GETPARAMFLOATRESPONSE"]._serialized_end = 444 + _globals["_SETPARAMFLOATREQUEST"]._serialized_start = 446 + _globals["_SETPARAMFLOATREQUEST"]._serialized_end = 497 + _globals["_SETPARAMFLOATRESPONSE"]._serialized_start = 499 + _globals["_SETPARAMFLOATRESPONSE"]._serialized_end = 575 + _globals["_GETPARAMCUSTOMREQUEST"]._serialized_start = 577 + _globals["_GETPARAMCUSTOMREQUEST"]._serialized_end = 614 + _globals["_GETPARAMCUSTOMRESPONSE"]._serialized_start = 616 + _globals["_GETPARAMCUSTOMRESPONSE"]._serialized_end = 708 + _globals["_SETPARAMCUSTOMREQUEST"]._serialized_start = 710 + _globals["_SETPARAMCUSTOMREQUEST"]._serialized_end = 762 + _globals["_SETPARAMCUSTOMRESPONSE"]._serialized_start = 764 + _globals["_SETPARAMCUSTOMRESPONSE"]._serialized_end = 841 + _globals["_GETALLPARAMSREQUEST"]._serialized_start = 843 + _globals["_GETALLPARAMSREQUEST"]._serialized_end = 864 + _globals["_GETALLPARAMSRESPONSE"]._serialized_start = 866 + _globals["_GETALLPARAMSRESPONSE"]._serialized_end = 933 + _globals["_SELECTCOMPONENTRESPONSE"]._serialized_start = 935 + _globals["_SELECTCOMPONENTRESPONSE"]._serialized_end = 1013 + _globals["_SELECTCOMPONENTREQUEST"]._serialized_start = 1015 + _globals["_SELECTCOMPONENTREQUEST"]._serialized_end = 1122 + _globals["_INTPARAM"]._serialized_start = 1124 + _globals["_INTPARAM"]._serialized_end = 1163 + _globals["_FLOATPARAM"]._serialized_start = 1165 + _globals["_FLOATPARAM"]._serialized_end = 1206 + _globals["_CUSTOMPARAM"]._serialized_start = 1208 + _globals["_CUSTOMPARAM"]._serialized_end = 1250 + _globals["_ALLPARAMS"]._serialized_start = 1253 + _globals["_ALLPARAMS"]._serialized_end = 1418 + _globals["_PARAMRESULT"]._serialized_start = 1421 + _globals["_PARAMRESULT"]._serialized_end = 1737 + _globals["_PARAMRESULT_RESULT"]._serialized_start = 1511 + _globals["_PARAMRESULT_RESULT"]._serialized_end = 1737 + _globals["_PARAMSERVICE"]._serialized_start = 1810 + _globals["_PARAMSERVICE"]._serialized_end = 2653 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/param_pb2_grpc.py b/mavsdk/param_pb2_grpc.py index 568f38f9..0ab63c1c 100644 --- a/mavsdk/param_pb2_grpc.py +++ b/mavsdk/param_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import param_pb2 as param_dot_param__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in param/param_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in param/param_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ParamServiceStub(object): - """Provide raw access to get and set parameters. - """ + """Provide raw access to get and set parameters.""" def __init__(self, channel): """Constructor. @@ -36,50 +39,57 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.GetParamInt = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/GetParamInt', - request_serializer=param_dot_param__pb2.GetParamIntRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.GetParamIntResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/GetParamInt", + request_serializer=param_dot_param__pb2.GetParamIntRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.GetParamIntResponse.FromString, + _registered_method=True, + ) self.SetParamInt = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/SetParamInt', - request_serializer=param_dot_param__pb2.SetParamIntRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.SetParamIntResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/SetParamInt", + request_serializer=param_dot_param__pb2.SetParamIntRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.SetParamIntResponse.FromString, + _registered_method=True, + ) self.GetParamFloat = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/GetParamFloat', - request_serializer=param_dot_param__pb2.GetParamFloatRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.GetParamFloatResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/GetParamFloat", + request_serializer=param_dot_param__pb2.GetParamFloatRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.GetParamFloatResponse.FromString, + _registered_method=True, + ) self.SetParamFloat = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/SetParamFloat', - request_serializer=param_dot_param__pb2.SetParamFloatRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.SetParamFloatResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/SetParamFloat", + request_serializer=param_dot_param__pb2.SetParamFloatRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.SetParamFloatResponse.FromString, + _registered_method=True, + ) self.GetParamCustom = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/GetParamCustom', - request_serializer=param_dot_param__pb2.GetParamCustomRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.GetParamCustomResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/GetParamCustom", + request_serializer=param_dot_param__pb2.GetParamCustomRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.GetParamCustomResponse.FromString, + _registered_method=True, + ) self.SetParamCustom = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/SetParamCustom', - request_serializer=param_dot_param__pb2.SetParamCustomRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.SetParamCustomResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/SetParamCustom", + request_serializer=param_dot_param__pb2.SetParamCustomRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.SetParamCustomResponse.FromString, + _registered_method=True, + ) self.GetAllParams = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/GetAllParams', - request_serializer=param_dot_param__pb2.GetAllParamsRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.GetAllParamsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/GetAllParams", + request_serializer=param_dot_param__pb2.GetAllParamsRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.GetAllParamsResponse.FromString, + _registered_method=True, + ) self.SelectComponent = channel.unary_unary( - '/mavsdk.rpc.param.ParamService/SelectComponent', - request_serializer=param_dot_param__pb2.SelectComponentRequest.SerializeToString, - response_deserializer=param_dot_param__pb2.SelectComponentResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param.ParamService/SelectComponent", + request_serializer=param_dot_param__pb2.SelectComponentRequest.SerializeToString, + response_deserializer=param_dot_param__pb2.SelectComponentResponse.FromString, + _registered_method=True, + ) class ParamServiceServicer(object): - """Provide raw access to get and set parameters. - """ + """Provide raw access to get and set parameters.""" def GetParamInt(self, request, context): """ @@ -88,8 +98,8 @@ def GetParamInt(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetParamInt(self, request, context): """ @@ -98,8 +108,8 @@ def SetParamInt(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetParamFloat(self, request, context): """ @@ -108,8 +118,8 @@ def GetParamFloat(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetParamFloat(self, request, context): """ @@ -118,8 +128,8 @@ def SetParamFloat(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetParamCustom(self, request, context): """ @@ -128,8 +138,8 @@ def GetParamCustom(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetParamCustom(self, request, context): """ @@ -138,16 +148,16 @@ def SetParamCustom(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetAllParams(self, request, context): """ Get all parameters. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SelectComponent(self, request, context): """ @@ -156,79 +166,83 @@ def SelectComponent(self, request, context): Default is the autopilot component (1), and Version (0). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ParamServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'GetParamInt': grpc.unary_unary_rpc_method_handler( - servicer.GetParamInt, - request_deserializer=param_dot_param__pb2.GetParamIntRequest.FromString, - response_serializer=param_dot_param__pb2.GetParamIntResponse.SerializeToString, - ), - 'SetParamInt': grpc.unary_unary_rpc_method_handler( - servicer.SetParamInt, - request_deserializer=param_dot_param__pb2.SetParamIntRequest.FromString, - response_serializer=param_dot_param__pb2.SetParamIntResponse.SerializeToString, - ), - 'GetParamFloat': grpc.unary_unary_rpc_method_handler( - servicer.GetParamFloat, - request_deserializer=param_dot_param__pb2.GetParamFloatRequest.FromString, - response_serializer=param_dot_param__pb2.GetParamFloatResponse.SerializeToString, - ), - 'SetParamFloat': grpc.unary_unary_rpc_method_handler( - servicer.SetParamFloat, - request_deserializer=param_dot_param__pb2.SetParamFloatRequest.FromString, - response_serializer=param_dot_param__pb2.SetParamFloatResponse.SerializeToString, - ), - 'GetParamCustom': grpc.unary_unary_rpc_method_handler( - servicer.GetParamCustom, - request_deserializer=param_dot_param__pb2.GetParamCustomRequest.FromString, - response_serializer=param_dot_param__pb2.GetParamCustomResponse.SerializeToString, - ), - 'SetParamCustom': grpc.unary_unary_rpc_method_handler( - servicer.SetParamCustom, - request_deserializer=param_dot_param__pb2.SetParamCustomRequest.FromString, - response_serializer=param_dot_param__pb2.SetParamCustomResponse.SerializeToString, - ), - 'GetAllParams': grpc.unary_unary_rpc_method_handler( - servicer.GetAllParams, - request_deserializer=param_dot_param__pb2.GetAllParamsRequest.FromString, - response_serializer=param_dot_param__pb2.GetAllParamsResponse.SerializeToString, - ), - 'SelectComponent': grpc.unary_unary_rpc_method_handler( - servicer.SelectComponent, - request_deserializer=param_dot_param__pb2.SelectComponentRequest.FromString, - response_serializer=param_dot_param__pb2.SelectComponentResponse.SerializeToString, - ), + "GetParamInt": grpc.unary_unary_rpc_method_handler( + servicer.GetParamInt, + request_deserializer=param_dot_param__pb2.GetParamIntRequest.FromString, + response_serializer=param_dot_param__pb2.GetParamIntResponse.SerializeToString, + ), + "SetParamInt": grpc.unary_unary_rpc_method_handler( + servicer.SetParamInt, + request_deserializer=param_dot_param__pb2.SetParamIntRequest.FromString, + response_serializer=param_dot_param__pb2.SetParamIntResponse.SerializeToString, + ), + "GetParamFloat": grpc.unary_unary_rpc_method_handler( + servicer.GetParamFloat, + request_deserializer=param_dot_param__pb2.GetParamFloatRequest.FromString, + response_serializer=param_dot_param__pb2.GetParamFloatResponse.SerializeToString, + ), + "SetParamFloat": grpc.unary_unary_rpc_method_handler( + servicer.SetParamFloat, + request_deserializer=param_dot_param__pb2.SetParamFloatRequest.FromString, + response_serializer=param_dot_param__pb2.SetParamFloatResponse.SerializeToString, + ), + "GetParamCustom": grpc.unary_unary_rpc_method_handler( + servicer.GetParamCustom, + request_deserializer=param_dot_param__pb2.GetParamCustomRequest.FromString, + response_serializer=param_dot_param__pb2.GetParamCustomResponse.SerializeToString, + ), + "SetParamCustom": grpc.unary_unary_rpc_method_handler( + servicer.SetParamCustom, + request_deserializer=param_dot_param__pb2.SetParamCustomRequest.FromString, + response_serializer=param_dot_param__pb2.SetParamCustomResponse.SerializeToString, + ), + "GetAllParams": grpc.unary_unary_rpc_method_handler( + servicer.GetAllParams, + request_deserializer=param_dot_param__pb2.GetAllParamsRequest.FromString, + response_serializer=param_dot_param__pb2.GetAllParamsResponse.SerializeToString, + ), + "SelectComponent": grpc.unary_unary_rpc_method_handler( + servicer.SelectComponent, + request_deserializer=param_dot_param__pb2.SelectComponentRequest.FromString, + response_serializer=param_dot_param__pb2.SelectComponentResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.param.ParamService', rpc_method_handlers) + "mavsdk.rpc.param.ParamService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.param.ParamService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.param.ParamService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ParamService(object): - """Provide raw access to get and set parameters. - """ + """Provide raw access to get and set parameters.""" @staticmethod - def GetParamInt(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetParamInt( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/GetParamInt', + "/mavsdk.rpc.param.ParamService/GetParamInt", param_dot_param__pb2.GetParamIntRequest.SerializeToString, param_dot_param__pb2.GetParamIntResponse.FromString, options, @@ -239,23 +253,26 @@ def GetParamInt(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetParamInt(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetParamInt( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/SetParamInt', + "/mavsdk.rpc.param.ParamService/SetParamInt", param_dot_param__pb2.SetParamIntRequest.SerializeToString, param_dot_param__pb2.SetParamIntResponse.FromString, options, @@ -266,23 +283,26 @@ def SetParamInt(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetParamFloat(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetParamFloat( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/GetParamFloat', + "/mavsdk.rpc.param.ParamService/GetParamFloat", param_dot_param__pb2.GetParamFloatRequest.SerializeToString, param_dot_param__pb2.GetParamFloatResponse.FromString, options, @@ -293,23 +313,26 @@ def GetParamFloat(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetParamFloat(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetParamFloat( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/SetParamFloat', + "/mavsdk.rpc.param.ParamService/SetParamFloat", param_dot_param__pb2.SetParamFloatRequest.SerializeToString, param_dot_param__pb2.SetParamFloatResponse.FromString, options, @@ -320,23 +343,26 @@ def SetParamFloat(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetParamCustom(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetParamCustom( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/GetParamCustom', + "/mavsdk.rpc.param.ParamService/GetParamCustom", param_dot_param__pb2.GetParamCustomRequest.SerializeToString, param_dot_param__pb2.GetParamCustomResponse.FromString, options, @@ -347,23 +373,26 @@ def GetParamCustom(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetParamCustom(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetParamCustom( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/SetParamCustom', + "/mavsdk.rpc.param.ParamService/SetParamCustom", param_dot_param__pb2.SetParamCustomRequest.SerializeToString, param_dot_param__pb2.SetParamCustomResponse.FromString, options, @@ -374,23 +403,26 @@ def SetParamCustom(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetAllParams(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetAllParams( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/GetAllParams', + "/mavsdk.rpc.param.ParamService/GetAllParams", param_dot_param__pb2.GetAllParamsRequest.SerializeToString, param_dot_param__pb2.GetAllParamsResponse.FromString, options, @@ -401,23 +433,26 @@ def GetAllParams(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SelectComponent(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SelectComponent( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param.ParamService/SelectComponent', + "/mavsdk.rpc.param.ParamService/SelectComponent", param_dot_param__pb2.SelectComponentRequest.SerializeToString, param_dot_param__pb2.SelectComponentResponse.FromString, options, @@ -428,4 +463,5 @@ def SelectComponent(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/param_server.py b/mavsdk/param_server.py index fd10b23d..06d8a06e 100644 --- a/mavsdk/param_server.py +++ b/mavsdk/param_server.py @@ -8,383 +8,298 @@ class IntParam: """ - Type for integer parameters. + Type for integer parameters. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - value : int32_t - Value of the parameter + value : int32_t + Value of the parameter - """ - - + """ - def __init__( - self, - name, - value): - """ Initializes the IntParam object """ + def __init__(self, name, value): + """Initializes the IntParam object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two IntParam are the same """ + """Checks if two IntParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # IntParam object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ IntParam in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """IntParam in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"IntParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcIntParam): - """ Translates a gRPC struct to the SDK equivalent """ - return IntParam( - - rpcIntParam.name, - - - rpcIntParam.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return IntParam(rpcIntParam.name, rpcIntParam.value) def translate_to_rpc(self, rpcIntParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcIntParam.name = self.name - - - - - + rpcIntParam.value = self.value - - - class FloatParam: """ - Type for float parameters. - - Parameters - ---------- - name : std::string - Name of the parameter + Type for float parameters. - value : float - Value of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - """ + value : float + Value of the parameter - + """ - def __init__( - self, - name, - value): - """ Initializes the FloatParam object """ + def __init__(self, name, value): + """Initializes the FloatParam object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two FloatParam are the same """ + """Checks if two FloatParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # FloatParam object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ FloatParam in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """FloatParam in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"FloatParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFloatParam): - """ Translates a gRPC struct to the SDK equivalent """ - return FloatParam( - - rpcFloatParam.name, - - - rpcFloatParam.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return FloatParam(rpcFloatParam.name, rpcFloatParam.value) def translate_to_rpc(self, rpcFloatParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFloatParam.name = self.name - - - - - + rpcFloatParam.value = self.value - - - class CustomParam: """ - Type for float parameters. + Type for float parameters. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - value : std::string - Value of the parameter + value : std::string + Value of the parameter - """ - - + """ - def __init__( - self, - name, - value): - """ Initializes the CustomParam object """ + def __init__(self, name, value): + """Initializes the CustomParam object""" self.name = name self.value = value def __eq__(self, to_compare): - """ Checks if two CustomParam are the same """ + """Checks if two CustomParam are the same""" try: # Try to compare - this likely fails when it is compared to a non # CustomParam object - return \ - (self.name == to_compare.name) and \ - (self.value == to_compare.value) + return (self.name == to_compare.name) and (self.value == to_compare.value) except AttributeError: return False def __str__(self): - """ CustomParam in string representation """ - struct_repr = ", ".join([ - "name: " + str(self.name), - "value: " + str(self.value) - ]) + """CustomParam in string representation""" + struct_repr = ", ".join( + ["name: " + str(self.name), "value: " + str(self.value)] + ) return f"CustomParam: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCustomParam): - """ Translates a gRPC struct to the SDK equivalent """ - return CustomParam( - - rpcCustomParam.name, - - - rpcCustomParam.value - ) + """Translates a gRPC struct to the SDK equivalent""" + return CustomParam(rpcCustomParam.name, rpcCustomParam.value) def translate_to_rpc(self, rpcCustomParam): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcCustomParam.name = self.name - - - - - + rpcCustomParam.value = self.value - - - class AllParams: """ - Type collecting all integer, float, and custom parameters. - - Parameters - ---------- - int_params : [IntParam] - Collection of all parameter names and values of type int + Type collecting all integer, float, and custom parameters. - float_params : [FloatParam] - Collection of all parameter names and values of type float + Parameters + ---------- + int_params : [IntParam] + Collection of all parameter names and values of type int - custom_params : [CustomParam] - Collection of all parameter names and values of type custom + float_params : [FloatParam] + Collection of all parameter names and values of type float - """ + custom_params : [CustomParam] + Collection of all parameter names and values of type custom - + """ - def __init__( - self, - int_params, - float_params, - custom_params): - """ Initializes the AllParams object """ + def __init__(self, int_params, float_params, custom_params): + """Initializes the AllParams object""" self.int_params = int_params self.float_params = float_params self.custom_params = custom_params def __eq__(self, to_compare): - """ Checks if two AllParams are the same """ + """Checks if two AllParams are the same""" try: # Try to compare - this likely fails when it is compared to a non # AllParams object - return \ - (self.int_params == to_compare.int_params) and \ - (self.float_params == to_compare.float_params) and \ - (self.custom_params == to_compare.custom_params) + return ( + (self.int_params == to_compare.int_params) + and (self.float_params == to_compare.float_params) + and (self.custom_params == to_compare.custom_params) + ) except AttributeError: return False def __str__(self): - """ AllParams in string representation """ - struct_repr = ", ".join([ + """AllParams in string representation""" + struct_repr = ", ".join( + [ "int_params: " + str(self.int_params), "float_params: " + str(self.float_params), - "custom_params: " + str(self.custom_params) - ]) + "custom_params: " + str(self.custom_params), + ] + ) return f"AllParams: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAllParams): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AllParams( - - list(map(lambda elem: IntParam.translate_from_rpc(elem), rpcAllParams.int_params)), - - - list(map(lambda elem: FloatParam.translate_from_rpc(elem), rpcAllParams.float_params)), - - - list(map(lambda elem: CustomParam.translate_from_rpc(elem), rpcAllParams.custom_params)) + list( + map( + lambda elem: IntParam.translate_from_rpc(elem), + rpcAllParams.int_params, + ) + ), + list( + map( + lambda elem: FloatParam.translate_from_rpc(elem), + rpcAllParams.float_params, ) + ), + list( + map( + lambda elem: CustomParam.translate_from_rpc(elem), + rpcAllParams.custom_params, + ) + ), + ) def translate_to_rpc(self, rpcAllParams): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.int_params: - rpc_elem = param_server_pb2.IntParam() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcAllParams.int_params.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.float_params: - rpc_elem = param_server_pb2.FloatParam() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcAllParams.float_params.extend(rpc_elems_list) - - - - - + rpc_elems_list = [] for elem in self.custom_params: - rpc_elem = param_server_pb2.CustomParam() elem.translate_to_rpc(rpc_elem) rpc_elems_list.append(rpc_elem) - + rpcAllParams.custom_params.extend(rpc_elems_list) - - - class ParamServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for param requests. + Possible results returned for param requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NOT_FOUND - Not Found + NOT_FOUND + Not Found - WRONG_TYPE - Wrong type + WRONG_TYPE + Wrong type - PARAM_NAME_TOO_LONG - Parameter name too long (> 16) + PARAM_NAME_TOO_LONG + Parameter name too long (> 16) - NO_SYSTEM - No system available + NO_SYSTEM + No system available - PARAM_VALUE_TOO_LONG - Parameter name too long (> 128) + PARAM_VALUE_TOO_LONG + Parameter name too long (> 128) - """ + """ - UNKNOWN = 0 SUCCESS = 1 NOT_FOUND = 2 @@ -411,7 +326,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == param_server_pb2.ParamServerResult.RESULT_UNKNOWN: return ParamServerResult.Result.UNKNOWN if rpc_enum_value == param_server_pb2.ParamServerResult.RESULT_SUCCESS: @@ -420,78 +335,65 @@ def translate_from_rpc(rpc_enum_value): return ParamServerResult.Result.NOT_FOUND if rpc_enum_value == param_server_pb2.ParamServerResult.RESULT_WRONG_TYPE: return ParamServerResult.Result.WRONG_TYPE - if rpc_enum_value == param_server_pb2.ParamServerResult.RESULT_PARAM_NAME_TOO_LONG: + if ( + rpc_enum_value + == param_server_pb2.ParamServerResult.RESULT_PARAM_NAME_TOO_LONG + ): return ParamServerResult.Result.PARAM_NAME_TOO_LONG if rpc_enum_value == param_server_pb2.ParamServerResult.RESULT_NO_SYSTEM: return ParamServerResult.Result.NO_SYSTEM - if rpc_enum_value == param_server_pb2.ParamServerResult.RESULT_PARAM_VALUE_TOO_LONG: + if ( + rpc_enum_value + == param_server_pb2.ParamServerResult.RESULT_PARAM_VALUE_TOO_LONG + ): return ParamServerResult.Result.PARAM_VALUE_TOO_LONG def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ParamServerResult object """ + def __init__(self, result, result_str): + """Initializes the ParamServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ParamServerResult are the same """ + """Checks if two ParamServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ParamServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ParamServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ParamServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ParamServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcParamServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ParamServerResult( - - ParamServerResult.Result.translate_from_rpc(rpcParamServerResult.result), - - - rpcParamServerResult.result_str - ) + ParamServerResult.Result.translate_from_rpc(rpcParamServerResult.result), + rpcParamServerResult.result_str, + ) def translate_to_rpc(self, rpcParamServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcParamServerResult.result = self.result.translate_to_rpc() - - - - - - rpcParamServerResult.result_str = self.result_str - - - + rpcParamServerResult.result_str = self.result_str class ParamServerError(Exception): - """ Raised when a ParamServerResult is a fail code """ + """Raised when a ParamServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -504,111 +406,103 @@ def __str__(self): class ParamServer(AsyncBase): """ - Provide raw access to retrieve and provide server parameters. + Provide raw access to retrieve and provide server parameters. - Generated by dcsdkgen - MAVSDK ParamServer API + Generated by dcsdkgen - MAVSDK ParamServer API """ # Plugin name name = "ParamServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = param_server_pb2_grpc.ParamServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ParamServerResult.translate_from_rpc(response.param_server_result) - async def set_protocol(self, extended_protocol): """ - Set param protocol. + Set param protocol. - The extended param protocol is used by default. This allows to use the previous/normal one. + The extended param protocol is used by default. This allows to use the previous/normal one. - Note that camera definition files are meant to implement/use the extended protocol. + Note that camera definition files are meant to implement/use the extended protocol. - Parameters - ---------- - extended_protocol : bool - Use extended protocol + Parameters + ---------- + extended_protocol : bool + Use extended protocol - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.SetProtocolRequest() request.extended_protocol = extended_protocol response = await self._stub.SetProtocol(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "set_protocol()", extended_protocol) - async def retrieve_param_int(self, name): """ - Retrieve an int parameter. + Retrieve an int parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - Returns - ------- - value : int32_t - Value of the requested parameter + Returns + ------- + value : int32_t + Value of the requested parameter - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.RetrieveParamIntRequest() - - + request.name = name - + response = await self._stub.RetrieveParamInt(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "retrieve_param_int()", name) - return response.value - async def provide_param_int(self, name, value): """ - Provide an int parameter. + Provide an int parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter to provide + Parameters + ---------- + name : std::string + Name of the parameter to provide - value : int32_t - Value the parameter should be set to + value : int32_t + Value the parameter should be set to - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.ProvideParamIntRequest() @@ -616,70 +510,64 @@ async def provide_param_int(self, name, value): request.value = value response = await self._stub.ProvideParamInt(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "provide_param_int()", name, value) - async def retrieve_param_float(self, name): """ - Retrieve a float parameter. + Retrieve a float parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - Returns - ------- - value : float - Value of the requested parameter + Returns + ------- + value : float + Value of the requested parameter - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.RetrieveParamFloatRequest() - - + request.name = name - + response = await self._stub.RetrieveParamFloat(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "retrieve_param_float()", name) - return response.value - async def provide_param_float(self, name, value): """ - Provide a float parameter. + Provide a float parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter to provide + Parameters + ---------- + name : std::string + Name of the parameter to provide - value : float - Value the parameter should be set to + value : float + Value the parameter should be set to - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.ProvideParamFloatRequest() @@ -687,70 +575,64 @@ async def provide_param_float(self, name, value): request.value = value response = await self._stub.ProvideParamFloat(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "provide_param_float()", name, value) - async def retrieve_param_custom(self, name): """ - Retrieve a custom parameter. + Retrieve a custom parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter + Parameters + ---------- + name : std::string + Name of the parameter - Returns - ------- - value : std::string - Value of the requested parameter + Returns + ------- + value : std::string + Value of the requested parameter - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.RetrieveParamCustomRequest() - - + request.name = name - + response = await self._stub.RetrieveParamCustom(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "retrieve_param_custom()", name) - return response.value - async def provide_param_custom(self, name, value): """ - Provide a custom parameter. + Provide a custom parameter. - If the type is wrong, the result will be `WRONG_TYPE`. + If the type is wrong, the result will be `WRONG_TYPE`. - Parameters - ---------- - name : std::string - Name of the parameter to provide + Parameters + ---------- + name : std::string + Name of the parameter to provide - value : std::string - Value the parameter should be set to + value : std::string + Value the parameter should be set to - Raises - ------ - ParamServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ParamServerError + If the request fails. The error contains the reason for the failure. """ request = param_server_pb2.ProvideParamCustomRequest() @@ -758,43 +640,38 @@ async def provide_param_custom(self, name, value): request.value = value response = await self._stub.ProvideParamCustom(request) - result = self._extract_result(response) if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "provide_param_custom()", name, value) - async def retrieve_all_params(self): """ - Retrieve all parameters. + Retrieve all parameters. + + Returns + ------- + params : AllParams + Collection of all parameters - Returns - ------- - params : AllParams - Collection of all parameters - """ request = param_server_pb2.RetrieveAllParamsRequest() response = await self._stub.RetrieveAllParams(request) - - return AllParams.translate_from_rpc(response.params) - async def changed_param_int(self): """ - Subscribe to changed int param. + Subscribe to changed int param. + + Yields + ------- + param : IntParam + Param that changed - Yields - ------- - param : IntParam - Param that changed - """ request = param_server_pb2.SubscribeChangedParamIntRequest() @@ -802,23 +679,20 @@ async def changed_param_int(self): try: async for response in changed_param_int_stream: - - - yield IntParam.translate_from_rpc(response.param) finally: changed_param_int_stream.cancel() async def changed_param_float(self): """ - Subscribe to changed float param. + Subscribe to changed float param. + + Yields + ------- + param : FloatParam + Param that changed - Yields - ------- - param : FloatParam - Param that changed - """ request = param_server_pb2.SubscribeChangedParamFloatRequest() @@ -826,23 +700,20 @@ async def changed_param_float(self): try: async for response in changed_param_float_stream: - - - yield FloatParam.translate_from_rpc(response.param) finally: changed_param_float_stream.cancel() async def changed_param_custom(self): """ - Subscribe to changed custom param. + Subscribe to changed custom param. + + Yields + ------- + param : CustomParam + Param that changed - Yields - ------- - param : CustomParam - Param that changed - """ request = param_server_pb2.SubscribeChangedParamCustomRequest() @@ -850,9 +721,6 @@ async def changed_param_custom(self): try: async for response in changed_param_custom_stream: - - - yield CustomParam.translate_from_rpc(response.param) finally: - changed_param_custom_stream.cancel() \ No newline at end of file + changed_param_custom_stream.cancel() diff --git a/mavsdk/param_server_pb2.py b/mavsdk/param_server_pb2.py index f4d64128..1b445750 100644 --- a/mavsdk/param_server_pb2.py +++ b/mavsdk/param_server_pb2.py @@ -4,18 +4,15 @@ # source: param_server/param_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'param_server/param_server.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "param_server/param_server.proto" ) # @@protoc_insertion_point(imports) @@ -25,92 +22,142 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x1fparam_server/param_server.proto\x12\x17mavsdk.rpc.param_server\x1a\x14mavsdk_options.proto\"/\n\x12SetProtocolRequest\x12\x19\n\x11\x65xtended_protocol\x18\x01 \x01(\x08\"^\n\x13SetProtocolResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\"\'\n\x17RetrieveParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\"r\n\x18RetrieveParamIntResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\x12\r\n\x05value\x18\x02 \x01(\x05\"5\n\x16ProvideParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05\"b\n\x17ProvideParamIntResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\")\n\x19RetrieveParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\"t\n\x1aRetrieveParamFloatResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\x12\r\n\x05value\x18\x02 \x01(\x02\"7\n\x18ProvideParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02\"d\n\x19ProvideParamFloatResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\"*\n\x1aRetrieveParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\"u\n\x1bRetrieveParamCustomResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\x12\r\n\x05value\x18\x02 \x01(\t\"8\n\x19ProvideParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t\"e\n\x1aProvideParamCustomResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\"\x1a\n\x18RetrieveAllParamsRequest\"O\n\x19RetrieveAllParamsResponse\x12\x32\n\x06params\x18\x01 \x01(\x0b\x32\".mavsdk.rpc.param_server.AllParams\"!\n\x1fSubscribeChangedParamIntRequest\"K\n\x17\x43hangedParamIntResponse\x12\x30\n\x05param\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.param_server.IntParam\"#\n!SubscribeChangedParamFloatRequest\"O\n\x19\x43hangedParamFloatResponse\x12\x32\n\x05param\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.param_server.FloatParam\"$\n\"SubscribeChangedParamCustomRequest\"Q\n\x1a\x43hangedParamCustomResponse\x12\x33\n\x05param\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.param_server.CustomParam\"\'\n\x08IntParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05\")\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02\"*\n\x0b\x43ustomParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t\"\xba\x01\n\tAllParams\x12\x35\n\nint_params\x18\x01 \x03(\x0b\x32!.mavsdk.rpc.param_server.IntParam\x12\x39\n\x0c\x66loat_params\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.param_server.FloatParam\x12;\n\rcustom_params\x18\x03 \x03(\x0b\x32$.mavsdk.rpc.param_server.CustomParam\"\xa1\x02\n\x11ParamServerResult\x12\x41\n\x06result\x18\x01 \x01(\x0e\x32\x31.mavsdk.rpc.param_server.ParamServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xb4\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NOT_FOUND\x10\x02\x12\x15\n\x11RESULT_WRONG_TYPE\x10\x03\x12\x1e\n\x1aRESULT_PARAM_NAME_TOO_LONG\x10\x04\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x05\x12\x1f\n\x1bRESULT_PARAM_VALUE_TOO_LONG\x10\x06\x32\xdc\x0b\n\x12ParamServerService\x12n\n\x0bSetProtocol\x12+.mavsdk.rpc.param_server.SetProtocolRequest\x1a,.mavsdk.rpc.param_server.SetProtocolResponse\"\x04\x80\xb5\x18\x01\x12}\n\x10RetrieveParamInt\x12\x30.mavsdk.rpc.param_server.RetrieveParamIntRequest\x1a\x31.mavsdk.rpc.param_server.RetrieveParamIntResponse\"\x04\x80\xb5\x18\x01\x12z\n\x0fProvideParamInt\x12/.mavsdk.rpc.param_server.ProvideParamIntRequest\x1a\x30.mavsdk.rpc.param_server.ProvideParamIntResponse\"\x04\x80\xb5\x18\x01\x12\x83\x01\n\x12RetrieveParamFloat\x12\x32.mavsdk.rpc.param_server.RetrieveParamFloatRequest\x1a\x33.mavsdk.rpc.param_server.RetrieveParamFloatResponse\"\x04\x80\xb5\x18\x01\x12\x80\x01\n\x11ProvideParamFloat\x12\x31.mavsdk.rpc.param_server.ProvideParamFloatRequest\x1a\x32.mavsdk.rpc.param_server.ProvideParamFloatResponse\"\x04\x80\xb5\x18\x01\x12\x86\x01\n\x13RetrieveParamCustom\x12\x33.mavsdk.rpc.param_server.RetrieveParamCustomRequest\x1a\x34.mavsdk.rpc.param_server.RetrieveParamCustomResponse\"\x04\x80\xb5\x18\x01\x12\x83\x01\n\x12ProvideParamCustom\x12\x32.mavsdk.rpc.param_server.ProvideParamCustomRequest\x1a\x33.mavsdk.rpc.param_server.ProvideParamCustomResponse\"\x04\x80\xb5\x18\x01\x12\x80\x01\n\x11RetrieveAllParams\x12\x31.mavsdk.rpc.param_server.RetrieveAllParamsRequest\x1a\x32.mavsdk.rpc.param_server.RetrieveAllParamsResponse\"\x04\x80\xb5\x18\x01\x12\x8e\x01\n\x18SubscribeChangedParamInt\x12\x38.mavsdk.rpc.param_server.SubscribeChangedParamIntRequest\x1a\x30.mavsdk.rpc.param_server.ChangedParamIntResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x94\x01\n\x1aSubscribeChangedParamFloat\x12:.mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest\x1a\x32.mavsdk.rpc.param_server.ChangedParamFloatResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x97\x01\n\x1bSubscribeChangedParamCustom\x12;.mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest\x1a\x33.mavsdk.rpc.param_server.ChangedParamCustomResponse\"\x04\x80\xb5\x18\x00\x30\x01\x42*\n\x16io.mavsdk.param_serverB\x10ParamServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x1fparam_server/param_server.proto\x12\x17mavsdk.rpc.param_server\x1a\x14mavsdk_options.proto"/\n\x12SetProtocolRequest\x12\x19\n\x11\x65xtended_protocol\x18\x01 \x01(\x08"^\n\x13SetProtocolResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult"\'\n\x17RetrieveParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t"r\n\x18RetrieveParamIntResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\x12\r\n\x05value\x18\x02 \x01(\x05"5\n\x16ProvideParamIntRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05"b\n\x17ProvideParamIntResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult")\n\x19RetrieveParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t"t\n\x1aRetrieveParamFloatResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\x12\r\n\x05value\x18\x02 \x01(\x02"7\n\x18ProvideParamFloatRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02"d\n\x19ProvideParamFloatResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult"*\n\x1aRetrieveParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t"u\n\x1bRetrieveParamCustomResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult\x12\r\n\x05value\x18\x02 \x01(\t"8\n\x19ProvideParamCustomRequest\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t"e\n\x1aProvideParamCustomResponse\x12G\n\x13param_server_result\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.param_server.ParamServerResult"\x1a\n\x18RetrieveAllParamsRequest"O\n\x19RetrieveAllParamsResponse\x12\x32\n\x06params\x18\x01 \x01(\x0b\x32".mavsdk.rpc.param_server.AllParams"!\n\x1fSubscribeChangedParamIntRequest"K\n\x17\x43hangedParamIntResponse\x12\x30\n\x05param\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.param_server.IntParam"#\n!SubscribeChangedParamFloatRequest"O\n\x19\x43hangedParamFloatResponse\x12\x32\n\x05param\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.param_server.FloatParam"$\n"SubscribeChangedParamCustomRequest"Q\n\x1a\x43hangedParamCustomResponse\x12\x33\n\x05param\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.param_server.CustomParam"\'\n\x08IntParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x05")\n\nFloatParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\x02"*\n\x0b\x43ustomParam\x12\x0c\n\x04name\x18\x01 \x01(\t\x12\r\n\x05value\x18\x02 \x01(\t"\xba\x01\n\tAllParams\x12\x35\n\nint_params\x18\x01 \x03(\x0b\x32!.mavsdk.rpc.param_server.IntParam\x12\x39\n\x0c\x66loat_params\x18\x02 \x03(\x0b\x32#.mavsdk.rpc.param_server.FloatParam\x12;\n\rcustom_params\x18\x03 \x03(\x0b\x32$.mavsdk.rpc.param_server.CustomParam"\xa1\x02\n\x11ParamServerResult\x12\x41\n\x06result\x18\x01 \x01(\x0e\x32\x31.mavsdk.rpc.param_server.ParamServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xb4\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NOT_FOUND\x10\x02\x12\x15\n\x11RESULT_WRONG_TYPE\x10\x03\x12\x1e\n\x1aRESULT_PARAM_NAME_TOO_LONG\x10\x04\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x05\x12\x1f\n\x1bRESULT_PARAM_VALUE_TOO_LONG\x10\x06\x32\xdc\x0b\n\x12ParamServerService\x12n\n\x0bSetProtocol\x12+.mavsdk.rpc.param_server.SetProtocolRequest\x1a,.mavsdk.rpc.param_server.SetProtocolResponse"\x04\x80\xb5\x18\x01\x12}\n\x10RetrieveParamInt\x12\x30.mavsdk.rpc.param_server.RetrieveParamIntRequest\x1a\x31.mavsdk.rpc.param_server.RetrieveParamIntResponse"\x04\x80\xb5\x18\x01\x12z\n\x0fProvideParamInt\x12/.mavsdk.rpc.param_server.ProvideParamIntRequest\x1a\x30.mavsdk.rpc.param_server.ProvideParamIntResponse"\x04\x80\xb5\x18\x01\x12\x83\x01\n\x12RetrieveParamFloat\x12\x32.mavsdk.rpc.param_server.RetrieveParamFloatRequest\x1a\x33.mavsdk.rpc.param_server.RetrieveParamFloatResponse"\x04\x80\xb5\x18\x01\x12\x80\x01\n\x11ProvideParamFloat\x12\x31.mavsdk.rpc.param_server.ProvideParamFloatRequest\x1a\x32.mavsdk.rpc.param_server.ProvideParamFloatResponse"\x04\x80\xb5\x18\x01\x12\x86\x01\n\x13RetrieveParamCustom\x12\x33.mavsdk.rpc.param_server.RetrieveParamCustomRequest\x1a\x34.mavsdk.rpc.param_server.RetrieveParamCustomResponse"\x04\x80\xb5\x18\x01\x12\x83\x01\n\x12ProvideParamCustom\x12\x32.mavsdk.rpc.param_server.ProvideParamCustomRequest\x1a\x33.mavsdk.rpc.param_server.ProvideParamCustomResponse"\x04\x80\xb5\x18\x01\x12\x80\x01\n\x11RetrieveAllParams\x12\x31.mavsdk.rpc.param_server.RetrieveAllParamsRequest\x1a\x32.mavsdk.rpc.param_server.RetrieveAllParamsResponse"\x04\x80\xb5\x18\x01\x12\x8e\x01\n\x18SubscribeChangedParamInt\x12\x38.mavsdk.rpc.param_server.SubscribeChangedParamIntRequest\x1a\x30.mavsdk.rpc.param_server.ChangedParamIntResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x94\x01\n\x1aSubscribeChangedParamFloat\x12:.mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest\x1a\x32.mavsdk.rpc.param_server.ChangedParamFloatResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x97\x01\n\x1bSubscribeChangedParamCustom\x12;.mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest\x1a\x33.mavsdk.rpc.param_server.ChangedParamCustomResponse"\x04\x80\xb5\x18\x00\x30\x01\x42*\n\x16io.mavsdk.param_serverB\x10ParamServerProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'param_server.param_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "param_server.param_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\026io.mavsdk.param_serverB\020ParamServerProto' - _globals['_PARAMSERVERSERVICE'].methods_by_name['SetProtocol']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['SetProtocol']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveParamInt']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveParamInt']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['ProvideParamInt']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['ProvideParamInt']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveParamFloat']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveParamFloat']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['ProvideParamFloat']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['ProvideParamFloat']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveParamCustom']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveParamCustom']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['ProvideParamCustom']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['ProvideParamCustom']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveAllParams']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['RetrieveAllParams']._serialized_options = b'\200\265\030\001' - _globals['_PARAMSERVERSERVICE'].methods_by_name['SubscribeChangedParamInt']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['SubscribeChangedParamInt']._serialized_options = b'\200\265\030\000' - _globals['_PARAMSERVERSERVICE'].methods_by_name['SubscribeChangedParamFloat']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['SubscribeChangedParamFloat']._serialized_options = b'\200\265\030\000' - _globals['_PARAMSERVERSERVICE'].methods_by_name['SubscribeChangedParamCustom']._loaded_options = None - _globals['_PARAMSERVERSERVICE'].methods_by_name['SubscribeChangedParamCustom']._serialized_options = b'\200\265\030\000' - _globals['_SETPROTOCOLREQUEST']._serialized_start=82 - _globals['_SETPROTOCOLREQUEST']._serialized_end=129 - _globals['_SETPROTOCOLRESPONSE']._serialized_start=131 - _globals['_SETPROTOCOLRESPONSE']._serialized_end=225 - _globals['_RETRIEVEPARAMINTREQUEST']._serialized_start=227 - _globals['_RETRIEVEPARAMINTREQUEST']._serialized_end=266 - _globals['_RETRIEVEPARAMINTRESPONSE']._serialized_start=268 - _globals['_RETRIEVEPARAMINTRESPONSE']._serialized_end=382 - _globals['_PROVIDEPARAMINTREQUEST']._serialized_start=384 - _globals['_PROVIDEPARAMINTREQUEST']._serialized_end=437 - _globals['_PROVIDEPARAMINTRESPONSE']._serialized_start=439 - _globals['_PROVIDEPARAMINTRESPONSE']._serialized_end=537 - _globals['_RETRIEVEPARAMFLOATREQUEST']._serialized_start=539 - _globals['_RETRIEVEPARAMFLOATREQUEST']._serialized_end=580 - _globals['_RETRIEVEPARAMFLOATRESPONSE']._serialized_start=582 - _globals['_RETRIEVEPARAMFLOATRESPONSE']._serialized_end=698 - _globals['_PROVIDEPARAMFLOATREQUEST']._serialized_start=700 - _globals['_PROVIDEPARAMFLOATREQUEST']._serialized_end=755 - _globals['_PROVIDEPARAMFLOATRESPONSE']._serialized_start=757 - _globals['_PROVIDEPARAMFLOATRESPONSE']._serialized_end=857 - _globals['_RETRIEVEPARAMCUSTOMREQUEST']._serialized_start=859 - _globals['_RETRIEVEPARAMCUSTOMREQUEST']._serialized_end=901 - _globals['_RETRIEVEPARAMCUSTOMRESPONSE']._serialized_start=903 - _globals['_RETRIEVEPARAMCUSTOMRESPONSE']._serialized_end=1020 - _globals['_PROVIDEPARAMCUSTOMREQUEST']._serialized_start=1022 - _globals['_PROVIDEPARAMCUSTOMREQUEST']._serialized_end=1078 - _globals['_PROVIDEPARAMCUSTOMRESPONSE']._serialized_start=1080 - _globals['_PROVIDEPARAMCUSTOMRESPONSE']._serialized_end=1181 - _globals['_RETRIEVEALLPARAMSREQUEST']._serialized_start=1183 - _globals['_RETRIEVEALLPARAMSREQUEST']._serialized_end=1209 - _globals['_RETRIEVEALLPARAMSRESPONSE']._serialized_start=1211 - _globals['_RETRIEVEALLPARAMSRESPONSE']._serialized_end=1290 - _globals['_SUBSCRIBECHANGEDPARAMINTREQUEST']._serialized_start=1292 - _globals['_SUBSCRIBECHANGEDPARAMINTREQUEST']._serialized_end=1325 - _globals['_CHANGEDPARAMINTRESPONSE']._serialized_start=1327 - _globals['_CHANGEDPARAMINTRESPONSE']._serialized_end=1402 - _globals['_SUBSCRIBECHANGEDPARAMFLOATREQUEST']._serialized_start=1404 - _globals['_SUBSCRIBECHANGEDPARAMFLOATREQUEST']._serialized_end=1439 - _globals['_CHANGEDPARAMFLOATRESPONSE']._serialized_start=1441 - _globals['_CHANGEDPARAMFLOATRESPONSE']._serialized_end=1520 - _globals['_SUBSCRIBECHANGEDPARAMCUSTOMREQUEST']._serialized_start=1522 - _globals['_SUBSCRIBECHANGEDPARAMCUSTOMREQUEST']._serialized_end=1558 - _globals['_CHANGEDPARAMCUSTOMRESPONSE']._serialized_start=1560 - _globals['_CHANGEDPARAMCUSTOMRESPONSE']._serialized_end=1641 - _globals['_INTPARAM']._serialized_start=1643 - _globals['_INTPARAM']._serialized_end=1682 - _globals['_FLOATPARAM']._serialized_start=1684 - _globals['_FLOATPARAM']._serialized_end=1725 - _globals['_CUSTOMPARAM']._serialized_start=1727 - _globals['_CUSTOMPARAM']._serialized_end=1769 - _globals['_ALLPARAMS']._serialized_start=1772 - _globals['_ALLPARAMS']._serialized_end=1958 - _globals['_PARAMSERVERRESULT']._serialized_start=1961 - _globals['_PARAMSERVERRESULT']._serialized_end=2250 - _globals['_PARAMSERVERRESULT_RESULT']._serialized_start=2070 - _globals['_PARAMSERVERRESULT_RESULT']._serialized_end=2250 - _globals['_PARAMSERVERSERVICE']._serialized_start=2253 - _globals['_PARAMSERVERSERVICE']._serialized_end=3753 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\026io.mavsdk.param_serverB\020ParamServerProto" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SetProtocol" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SetProtocol" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveParamInt" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveParamInt" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "ProvideParamInt" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "ProvideParamInt" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveParamFloat" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveParamFloat" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "ProvideParamFloat" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "ProvideParamFloat" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveParamCustom" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveParamCustom" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "ProvideParamCustom" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "ProvideParamCustom" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveAllParams" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "RetrieveAllParams" + ]._serialized_options = b"\200\265\030\001" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SubscribeChangedParamInt" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SubscribeChangedParamInt" + ]._serialized_options = b"\200\265\030\000" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SubscribeChangedParamFloat" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SubscribeChangedParamFloat" + ]._serialized_options = b"\200\265\030\000" + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SubscribeChangedParamCustom" + ]._loaded_options = None + _globals["_PARAMSERVERSERVICE"].methods_by_name[ + "SubscribeChangedParamCustom" + ]._serialized_options = b"\200\265\030\000" + _globals["_SETPROTOCOLREQUEST"]._serialized_start = 82 + _globals["_SETPROTOCOLREQUEST"]._serialized_end = 129 + _globals["_SETPROTOCOLRESPONSE"]._serialized_start = 131 + _globals["_SETPROTOCOLRESPONSE"]._serialized_end = 225 + _globals["_RETRIEVEPARAMINTREQUEST"]._serialized_start = 227 + _globals["_RETRIEVEPARAMINTREQUEST"]._serialized_end = 266 + _globals["_RETRIEVEPARAMINTRESPONSE"]._serialized_start = 268 + _globals["_RETRIEVEPARAMINTRESPONSE"]._serialized_end = 382 + _globals["_PROVIDEPARAMINTREQUEST"]._serialized_start = 384 + _globals["_PROVIDEPARAMINTREQUEST"]._serialized_end = 437 + _globals["_PROVIDEPARAMINTRESPONSE"]._serialized_start = 439 + _globals["_PROVIDEPARAMINTRESPONSE"]._serialized_end = 537 + _globals["_RETRIEVEPARAMFLOATREQUEST"]._serialized_start = 539 + _globals["_RETRIEVEPARAMFLOATREQUEST"]._serialized_end = 580 + _globals["_RETRIEVEPARAMFLOATRESPONSE"]._serialized_start = 582 + _globals["_RETRIEVEPARAMFLOATRESPONSE"]._serialized_end = 698 + _globals["_PROVIDEPARAMFLOATREQUEST"]._serialized_start = 700 + _globals["_PROVIDEPARAMFLOATREQUEST"]._serialized_end = 755 + _globals["_PROVIDEPARAMFLOATRESPONSE"]._serialized_start = 757 + _globals["_PROVIDEPARAMFLOATRESPONSE"]._serialized_end = 857 + _globals["_RETRIEVEPARAMCUSTOMREQUEST"]._serialized_start = 859 + _globals["_RETRIEVEPARAMCUSTOMREQUEST"]._serialized_end = 901 + _globals["_RETRIEVEPARAMCUSTOMRESPONSE"]._serialized_start = 903 + _globals["_RETRIEVEPARAMCUSTOMRESPONSE"]._serialized_end = 1020 + _globals["_PROVIDEPARAMCUSTOMREQUEST"]._serialized_start = 1022 + _globals["_PROVIDEPARAMCUSTOMREQUEST"]._serialized_end = 1078 + _globals["_PROVIDEPARAMCUSTOMRESPONSE"]._serialized_start = 1080 + _globals["_PROVIDEPARAMCUSTOMRESPONSE"]._serialized_end = 1181 + _globals["_RETRIEVEALLPARAMSREQUEST"]._serialized_start = 1183 + _globals["_RETRIEVEALLPARAMSREQUEST"]._serialized_end = 1209 + _globals["_RETRIEVEALLPARAMSRESPONSE"]._serialized_start = 1211 + _globals["_RETRIEVEALLPARAMSRESPONSE"]._serialized_end = 1290 + _globals["_SUBSCRIBECHANGEDPARAMINTREQUEST"]._serialized_start = 1292 + _globals["_SUBSCRIBECHANGEDPARAMINTREQUEST"]._serialized_end = 1325 + _globals["_CHANGEDPARAMINTRESPONSE"]._serialized_start = 1327 + _globals["_CHANGEDPARAMINTRESPONSE"]._serialized_end = 1402 + _globals["_SUBSCRIBECHANGEDPARAMFLOATREQUEST"]._serialized_start = 1404 + _globals["_SUBSCRIBECHANGEDPARAMFLOATREQUEST"]._serialized_end = 1439 + _globals["_CHANGEDPARAMFLOATRESPONSE"]._serialized_start = 1441 + _globals["_CHANGEDPARAMFLOATRESPONSE"]._serialized_end = 1520 + _globals["_SUBSCRIBECHANGEDPARAMCUSTOMREQUEST"]._serialized_start = 1522 + _globals["_SUBSCRIBECHANGEDPARAMCUSTOMREQUEST"]._serialized_end = 1558 + _globals["_CHANGEDPARAMCUSTOMRESPONSE"]._serialized_start = 1560 + _globals["_CHANGEDPARAMCUSTOMRESPONSE"]._serialized_end = 1641 + _globals["_INTPARAM"]._serialized_start = 1643 + _globals["_INTPARAM"]._serialized_end = 1682 + _globals["_FLOATPARAM"]._serialized_start = 1684 + _globals["_FLOATPARAM"]._serialized_end = 1725 + _globals["_CUSTOMPARAM"]._serialized_start = 1727 + _globals["_CUSTOMPARAM"]._serialized_end = 1769 + _globals["_ALLPARAMS"]._serialized_start = 1772 + _globals["_ALLPARAMS"]._serialized_end = 1958 + _globals["_PARAMSERVERRESULT"]._serialized_start = 1961 + _globals["_PARAMSERVERRESULT"]._serialized_end = 2250 + _globals["_PARAMSERVERRESULT_RESULT"]._serialized_start = 2070 + _globals["_PARAMSERVERRESULT_RESULT"]._serialized_end = 2250 + _globals["_PARAMSERVERSERVICE"]._serialized_start = 2253 + _globals["_PARAMSERVERSERVICE"]._serialized_end = 3753 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/param_server_pb2_grpc.py b/mavsdk/param_server_pb2_grpc.py index 8b68247d..97af3acf 100644 --- a/mavsdk/param_server_pb2_grpc.py +++ b/mavsdk/param_server_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import param_server_pb2 as param__server_dot_param__server__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in param_server/param_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in param_server/param_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class ParamServerServiceStub(object): - """Provide raw access to retrieve and provide server parameters. - """ + """Provide raw access to retrieve and provide server parameters.""" def __init__(self, channel): """Constructor. @@ -36,65 +39,75 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetProtocol = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/SetProtocol', - request_serializer=param__server_dot_param__server__pb2.SetProtocolRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.SetProtocolResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/SetProtocol", + request_serializer=param__server_dot_param__server__pb2.SetProtocolRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.SetProtocolResponse.FromString, + _registered_method=True, + ) self.RetrieveParamInt = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/RetrieveParamInt', - request_serializer=param__server_dot_param__server__pb2.RetrieveParamIntRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.RetrieveParamIntResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamInt", + request_serializer=param__server_dot_param__server__pb2.RetrieveParamIntRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.RetrieveParamIntResponse.FromString, + _registered_method=True, + ) self.ProvideParamInt = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/ProvideParamInt', - request_serializer=param__server_dot_param__server__pb2.ProvideParamIntRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.ProvideParamIntResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/ProvideParamInt", + request_serializer=param__server_dot_param__server__pb2.ProvideParamIntRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.ProvideParamIntResponse.FromString, + _registered_method=True, + ) self.RetrieveParamFloat = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/RetrieveParamFloat', - request_serializer=param__server_dot_param__server__pb2.RetrieveParamFloatRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.RetrieveParamFloatResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamFloat", + request_serializer=param__server_dot_param__server__pb2.RetrieveParamFloatRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.RetrieveParamFloatResponse.FromString, + _registered_method=True, + ) self.ProvideParamFloat = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/ProvideParamFloat', - request_serializer=param__server_dot_param__server__pb2.ProvideParamFloatRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.ProvideParamFloatResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/ProvideParamFloat", + request_serializer=param__server_dot_param__server__pb2.ProvideParamFloatRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.ProvideParamFloatResponse.FromString, + _registered_method=True, + ) self.RetrieveParamCustom = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/RetrieveParamCustom', - request_serializer=param__server_dot_param__server__pb2.RetrieveParamCustomRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.RetrieveParamCustomResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamCustom", + request_serializer=param__server_dot_param__server__pb2.RetrieveParamCustomRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.RetrieveParamCustomResponse.FromString, + _registered_method=True, + ) self.ProvideParamCustom = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/ProvideParamCustom', - request_serializer=param__server_dot_param__server__pb2.ProvideParamCustomRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.ProvideParamCustomResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/ProvideParamCustom", + request_serializer=param__server_dot_param__server__pb2.ProvideParamCustomRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.ProvideParamCustomResponse.FromString, + _registered_method=True, + ) self.RetrieveAllParams = channel.unary_unary( - '/mavsdk.rpc.param_server.ParamServerService/RetrieveAllParams', - request_serializer=param__server_dot_param__server__pb2.RetrieveAllParamsRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.RetrieveAllParamsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/RetrieveAllParams", + request_serializer=param__server_dot_param__server__pb2.RetrieveAllParamsRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.RetrieveAllParamsResponse.FromString, + _registered_method=True, + ) self.SubscribeChangedParamInt = channel.unary_stream( - '/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamInt', - request_serializer=param__server_dot_param__server__pb2.SubscribeChangedParamIntRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.ChangedParamIntResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamInt", + request_serializer=param__server_dot_param__server__pb2.SubscribeChangedParamIntRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.ChangedParamIntResponse.FromString, + _registered_method=True, + ) self.SubscribeChangedParamFloat = channel.unary_stream( - '/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamFloat', - request_serializer=param__server_dot_param__server__pb2.SubscribeChangedParamFloatRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.ChangedParamFloatResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamFloat", + request_serializer=param__server_dot_param__server__pb2.SubscribeChangedParamFloatRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.ChangedParamFloatResponse.FromString, + _registered_method=True, + ) self.SubscribeChangedParamCustom = channel.unary_stream( - '/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamCustom', - request_serializer=param__server_dot_param__server__pb2.SubscribeChangedParamCustomRequest.SerializeToString, - response_deserializer=param__server_dot_param__server__pb2.ChangedParamCustomResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamCustom", + request_serializer=param__server_dot_param__server__pb2.SubscribeChangedParamCustomRequest.SerializeToString, + response_deserializer=param__server_dot_param__server__pb2.ChangedParamCustomResponse.FromString, + _registered_method=True, + ) class ParamServerServiceServicer(object): - """Provide raw access to retrieve and provide server parameters. - """ + """Provide raw access to retrieve and provide server parameters.""" def SetProtocol(self, request, context): """ @@ -105,8 +118,8 @@ def SetProtocol(self, request, context): Note that camera definition files are meant to implement/use the extended protocol. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RetrieveParamInt(self, request, context): """ @@ -115,8 +128,8 @@ def RetrieveParamInt(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ProvideParamInt(self, request, context): """ @@ -125,8 +138,8 @@ def ProvideParamInt(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RetrieveParamFloat(self, request, context): """ @@ -135,8 +148,8 @@ def RetrieveParamFloat(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ProvideParamFloat(self, request, context): """ @@ -145,8 +158,8 @@ def ProvideParamFloat(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RetrieveParamCustom(self, request, context): """ @@ -155,8 +168,8 @@ def RetrieveParamCustom(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def ProvideParamCustom(self, request, context): """ @@ -165,123 +178,124 @@ def ProvideParamCustom(self, request, context): If the type is wrong, the result will be `WRONG_TYPE`. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RetrieveAllParams(self, request, context): """ Retrieve all parameters. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeChangedParamInt(self, request, context): - """Subscribe to changed int param. - """ + """Subscribe to changed int param.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeChangedParamFloat(self, request, context): - """Subscribe to changed float param. - """ + """Subscribe to changed float param.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeChangedParamCustom(self, request, context): - """Subscribe to changed custom param. - """ + """Subscribe to changed custom param.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ParamServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetProtocol': grpc.unary_unary_rpc_method_handler( - servicer.SetProtocol, - request_deserializer=param__server_dot_param__server__pb2.SetProtocolRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.SetProtocolResponse.SerializeToString, - ), - 'RetrieveParamInt': grpc.unary_unary_rpc_method_handler( - servicer.RetrieveParamInt, - request_deserializer=param__server_dot_param__server__pb2.RetrieveParamIntRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.RetrieveParamIntResponse.SerializeToString, - ), - 'ProvideParamInt': grpc.unary_unary_rpc_method_handler( - servicer.ProvideParamInt, - request_deserializer=param__server_dot_param__server__pb2.ProvideParamIntRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.ProvideParamIntResponse.SerializeToString, - ), - 'RetrieveParamFloat': grpc.unary_unary_rpc_method_handler( - servicer.RetrieveParamFloat, - request_deserializer=param__server_dot_param__server__pb2.RetrieveParamFloatRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.RetrieveParamFloatResponse.SerializeToString, - ), - 'ProvideParamFloat': grpc.unary_unary_rpc_method_handler( - servicer.ProvideParamFloat, - request_deserializer=param__server_dot_param__server__pb2.ProvideParamFloatRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.ProvideParamFloatResponse.SerializeToString, - ), - 'RetrieveParamCustom': grpc.unary_unary_rpc_method_handler( - servicer.RetrieveParamCustom, - request_deserializer=param__server_dot_param__server__pb2.RetrieveParamCustomRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.RetrieveParamCustomResponse.SerializeToString, - ), - 'ProvideParamCustom': grpc.unary_unary_rpc_method_handler( - servicer.ProvideParamCustom, - request_deserializer=param__server_dot_param__server__pb2.ProvideParamCustomRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.ProvideParamCustomResponse.SerializeToString, - ), - 'RetrieveAllParams': grpc.unary_unary_rpc_method_handler( - servicer.RetrieveAllParams, - request_deserializer=param__server_dot_param__server__pb2.RetrieveAllParamsRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.RetrieveAllParamsResponse.SerializeToString, - ), - 'SubscribeChangedParamInt': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeChangedParamInt, - request_deserializer=param__server_dot_param__server__pb2.SubscribeChangedParamIntRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.ChangedParamIntResponse.SerializeToString, - ), - 'SubscribeChangedParamFloat': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeChangedParamFloat, - request_deserializer=param__server_dot_param__server__pb2.SubscribeChangedParamFloatRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.ChangedParamFloatResponse.SerializeToString, - ), - 'SubscribeChangedParamCustom': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeChangedParamCustom, - request_deserializer=param__server_dot_param__server__pb2.SubscribeChangedParamCustomRequest.FromString, - response_serializer=param__server_dot_param__server__pb2.ChangedParamCustomResponse.SerializeToString, - ), + "SetProtocol": grpc.unary_unary_rpc_method_handler( + servicer.SetProtocol, + request_deserializer=param__server_dot_param__server__pb2.SetProtocolRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.SetProtocolResponse.SerializeToString, + ), + "RetrieveParamInt": grpc.unary_unary_rpc_method_handler( + servicer.RetrieveParamInt, + request_deserializer=param__server_dot_param__server__pb2.RetrieveParamIntRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.RetrieveParamIntResponse.SerializeToString, + ), + "ProvideParamInt": grpc.unary_unary_rpc_method_handler( + servicer.ProvideParamInt, + request_deserializer=param__server_dot_param__server__pb2.ProvideParamIntRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.ProvideParamIntResponse.SerializeToString, + ), + "RetrieveParamFloat": grpc.unary_unary_rpc_method_handler( + servicer.RetrieveParamFloat, + request_deserializer=param__server_dot_param__server__pb2.RetrieveParamFloatRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.RetrieveParamFloatResponse.SerializeToString, + ), + "ProvideParamFloat": grpc.unary_unary_rpc_method_handler( + servicer.ProvideParamFloat, + request_deserializer=param__server_dot_param__server__pb2.ProvideParamFloatRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.ProvideParamFloatResponse.SerializeToString, + ), + "RetrieveParamCustom": grpc.unary_unary_rpc_method_handler( + servicer.RetrieveParamCustom, + request_deserializer=param__server_dot_param__server__pb2.RetrieveParamCustomRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.RetrieveParamCustomResponse.SerializeToString, + ), + "ProvideParamCustom": grpc.unary_unary_rpc_method_handler( + servicer.ProvideParamCustom, + request_deserializer=param__server_dot_param__server__pb2.ProvideParamCustomRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.ProvideParamCustomResponse.SerializeToString, + ), + "RetrieveAllParams": grpc.unary_unary_rpc_method_handler( + servicer.RetrieveAllParams, + request_deserializer=param__server_dot_param__server__pb2.RetrieveAllParamsRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.RetrieveAllParamsResponse.SerializeToString, + ), + "SubscribeChangedParamInt": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeChangedParamInt, + request_deserializer=param__server_dot_param__server__pb2.SubscribeChangedParamIntRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.ChangedParamIntResponse.SerializeToString, + ), + "SubscribeChangedParamFloat": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeChangedParamFloat, + request_deserializer=param__server_dot_param__server__pb2.SubscribeChangedParamFloatRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.ChangedParamFloatResponse.SerializeToString, + ), + "SubscribeChangedParamCustom": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeChangedParamCustom, + request_deserializer=param__server_dot_param__server__pb2.SubscribeChangedParamCustomRequest.FromString, + response_serializer=param__server_dot_param__server__pb2.ChangedParamCustomResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.param_server.ParamServerService', rpc_method_handlers) + "mavsdk.rpc.param_server.ParamServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.param_server.ParamServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.param_server.ParamServerService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ParamServerService(object): - """Provide raw access to retrieve and provide server parameters. - """ + """Provide raw access to retrieve and provide server parameters.""" @staticmethod - def SetProtocol(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetProtocol( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/SetProtocol', + "/mavsdk.rpc.param_server.ParamServerService/SetProtocol", param__server_dot_param__server__pb2.SetProtocolRequest.SerializeToString, param__server_dot_param__server__pb2.SetProtocolResponse.FromString, options, @@ -292,23 +306,26 @@ def SetProtocol(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RetrieveParamInt(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RetrieveParamInt( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/RetrieveParamInt', + "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamInt", param__server_dot_param__server__pb2.RetrieveParamIntRequest.SerializeToString, param__server_dot_param__server__pb2.RetrieveParamIntResponse.FromString, options, @@ -319,23 +336,26 @@ def RetrieveParamInt(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ProvideParamInt(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ProvideParamInt( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/ProvideParamInt', + "/mavsdk.rpc.param_server.ParamServerService/ProvideParamInt", param__server_dot_param__server__pb2.ProvideParamIntRequest.SerializeToString, param__server_dot_param__server__pb2.ProvideParamIntResponse.FromString, options, @@ -346,23 +366,26 @@ def ProvideParamInt(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RetrieveParamFloat(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RetrieveParamFloat( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/RetrieveParamFloat', + "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamFloat", param__server_dot_param__server__pb2.RetrieveParamFloatRequest.SerializeToString, param__server_dot_param__server__pb2.RetrieveParamFloatResponse.FromString, options, @@ -373,23 +396,26 @@ def RetrieveParamFloat(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ProvideParamFloat(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ProvideParamFloat( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/ProvideParamFloat', + "/mavsdk.rpc.param_server.ParamServerService/ProvideParamFloat", param__server_dot_param__server__pb2.ProvideParamFloatRequest.SerializeToString, param__server_dot_param__server__pb2.ProvideParamFloatResponse.FromString, options, @@ -400,23 +426,26 @@ def ProvideParamFloat(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RetrieveParamCustom(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RetrieveParamCustom( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/RetrieveParamCustom', + "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamCustom", param__server_dot_param__server__pb2.RetrieveParamCustomRequest.SerializeToString, param__server_dot_param__server__pb2.RetrieveParamCustomResponse.FromString, options, @@ -427,23 +456,26 @@ def RetrieveParamCustom(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def ProvideParamCustom(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def ProvideParamCustom( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/ProvideParamCustom', + "/mavsdk.rpc.param_server.ParamServerService/ProvideParamCustom", param__server_dot_param__server__pb2.ProvideParamCustomRequest.SerializeToString, param__server_dot_param__server__pb2.ProvideParamCustomResponse.FromString, options, @@ -454,23 +486,26 @@ def ProvideParamCustom(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RetrieveAllParams(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RetrieveAllParams( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.param_server.ParamServerService/RetrieveAllParams', + "/mavsdk.rpc.param_server.ParamServerService/RetrieveAllParams", param__server_dot_param__server__pb2.RetrieveAllParamsRequest.SerializeToString, param__server_dot_param__server__pb2.RetrieveAllParamsResponse.FromString, options, @@ -481,23 +516,26 @@ def RetrieveAllParams(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeChangedParamInt(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeChangedParamInt( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamInt', + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamInt", param__server_dot_param__server__pb2.SubscribeChangedParamIntRequest.SerializeToString, param__server_dot_param__server__pb2.ChangedParamIntResponse.FromString, options, @@ -508,23 +546,26 @@ def SubscribeChangedParamInt(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeChangedParamFloat(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeChangedParamFloat( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamFloat', + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamFloat", param__server_dot_param__server__pb2.SubscribeChangedParamFloatRequest.SerializeToString, param__server_dot_param__server__pb2.ChangedParamFloatResponse.FromString, options, @@ -535,23 +576,26 @@ def SubscribeChangedParamFloat(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeChangedParamCustom(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeChangedParamCustom( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamCustom', + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamCustom", param__server_dot_param__server__pb2.SubscribeChangedParamCustomRequest.SerializeToString, param__server_dot_param__server__pb2.ChangedParamCustomResponse.FromString, options, @@ -562,4 +606,5 @@ def SubscribeChangedParamCustom(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/rtk.py b/mavsdk/rtk.py index 58a0468c..fa8b31e4 100644 --- a/mavsdk/rtk.py +++ b/mavsdk/rtk.py @@ -8,102 +8,83 @@ class RtcmData: """ - RTCM data type + RTCM data type - Parameters - ---------- - data_base64 : std::string - The data encoded as a base64 string + Parameters + ---------- + data_base64 : std::string + The data encoded as a base64 string - """ - - + """ - def __init__( - self, - data_base64): - """ Initializes the RtcmData object """ + def __init__(self, data_base64): + """Initializes the RtcmData object""" self.data_base64 = data_base64 def __eq__(self, to_compare): - """ Checks if two RtcmData are the same """ + """Checks if two RtcmData are the same""" try: # Try to compare - this likely fails when it is compared to a non # RtcmData object - return \ - (self.data_base64 == to_compare.data_base64) + return self.data_base64 == to_compare.data_base64 except AttributeError: return False def __str__(self): - """ RtcmData in string representation """ - struct_repr = ", ".join([ - "data_base64: " + str(self.data_base64) - ]) + """RtcmData in string representation""" + struct_repr = ", ".join(["data_base64: " + str(self.data_base64)]) return f"RtcmData: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcRtcmData): - """ Translates a gRPC struct to the SDK equivalent """ - return RtcmData( - - rpcRtcmData.data_base64 - ) + """Translates a gRPC struct to the SDK equivalent""" + return RtcmData(rpcRtcmData.data_base64) def translate_to_rpc(self, rpcRtcmData): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcRtcmData.data_base64 = self.data_base64 - - - class RtkResult: """ - - Parameters - ---------- - result : Result - Result enum value - result_str : std::string - Human-readable English string describing the result + Parameters + ---------- + result : Result + Result enum value - """ + result_str : std::string + Human-readable English string describing the result + + """ - - class Result(Enum): """ - Possible results returned for rtk requests. + Possible results returned for rtk requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - TOO_LONG - Passed data is too long + TOO_LONG + Passed data is too long - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - """ + """ - UNKNOWN = 0 SUCCESS = 1 TOO_LONG = 2 @@ -124,7 +105,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == rtk_pb2.RtkResult.RESULT_UNKNOWN: return RtkResult.Result.UNKNOWN if rpc_enum_value == rtk_pb2.RtkResult.RESULT_SUCCESS: @@ -138,69 +119,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the RtkResult object """ + def __init__(self, result, result_str): + """Initializes the RtkResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two RtkResult are the same """ + """Checks if two RtkResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # RtkResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ RtkResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """RtkResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"RtkResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcRtkResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return RtkResult( - - RtkResult.Result.translate_from_rpc(rpcRtkResult.result), - - - rpcRtkResult.result_str - ) + RtkResult.Result.translate_from_rpc(rpcRtkResult.result), + rpcRtkResult.result_str, + ) def translate_to_rpc(self, rpcRtkResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcRtkResult.result = self.result.translate_to_rpc() - - - - - - rpcRtkResult.result_str = self.result_str - - - + rpcRtkResult.result_str = self.result_str class RtkError(Exception): - """ Raised when a RtkResult is a fail code """ + """Raised when a RtkResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -213,49 +175,44 @@ def __str__(self): class Rtk(AsyncBase): """ - Service to send RTK corrections to the vehicle. + Service to send RTK corrections to the vehicle. - Generated by dcsdkgen - MAVSDK Rtk API + Generated by dcsdkgen - MAVSDK Rtk API """ # Plugin name name = "Rtk" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = rtk_pb2_grpc.RtkServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return RtkResult.translate_from_rpc(response.rtk_result) - async def send_rtcm_data(self, rtcm_data): """ - Send RTCM data. + Send RTCM data. - Parameters - ---------- - rtcm_data : RtcmData - The data + Parameters + ---------- + rtcm_data : RtcmData + The data - Raises - ------ - RtkError - If the request fails. The error contains the reason for the failure. + Raises + ------ + RtkError + If the request fails. The error contains the reason for the failure. """ request = rtk_pb2.SendRtcmDataRequest() - + rtcm_data.translate_to_rpc(request.rtcm_data) - - + response = await self._stub.SendRtcmData(request) - result = self._extract_result(response) if result.result != RtkResult.Result.SUCCESS: raise RtkError(result, "send_rtcm_data()", rtcm_data) - \ No newline at end of file diff --git a/mavsdk/rtk_pb2.py b/mavsdk/rtk_pb2.py index 6b44a8eb..a10de4bc 100644 --- a/mavsdk/rtk_pb2.py +++ b/mavsdk/rtk_pb2.py @@ -4,18 +4,15 @@ # source: rtk/rtk.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'rtk/rtk.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "rtk/rtk.proto" ) # @@protoc_insertion_point(imports) @@ -25,26 +22,30 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'rtk.rtk_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "rtk.rtk_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\rio.mavsdk.rtkB\010RtkProto' - _globals['_RTKSERVICE'].methods_by_name['SendRtcmData']._loaded_options = None - _globals['_RTKSERVICE'].methods_by_name['SendRtcmData']._serialized_options = b'\200\265\030\001' - _globals['_RTCMDATA']._serialized_start=55 - _globals['_RTCMDATA']._serialized_end=86 - _globals['_SENDRTCMDATAREQUEST']._serialized_start=88 - _globals['_SENDRTCMDATAREQUEST']._serialized_end=154 - _globals['_SENDRTCMDATARESPONSE']._serialized_start=156 - _globals['_SENDRTCMDATARESPONSE']._serialized_end=225 - _globals['_RTKRESULT']._serialized_start=228 - _globals['_RTKRESULT']._serialized_end=431 - _globals['_RTKRESULT_RESULT']._serialized_start=311 - _globals['_RTKRESULT_RESULT']._serialized_end=431 - _globals['_RTKSERVICE']._serialized_start=433 - _globals['_RTKSERVICE']._serialized_end=542 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\rio.mavsdk.rtkB\010RtkProto" + _globals["_RTKSERVICE"].methods_by_name["SendRtcmData"]._loaded_options = None + _globals["_RTKSERVICE"].methods_by_name[ + "SendRtcmData" + ]._serialized_options = b"\200\265\030\001" + _globals["_RTCMDATA"]._serialized_start = 55 + _globals["_RTCMDATA"]._serialized_end = 86 + _globals["_SENDRTCMDATAREQUEST"]._serialized_start = 88 + _globals["_SENDRTCMDATAREQUEST"]._serialized_end = 154 + _globals["_SENDRTCMDATARESPONSE"]._serialized_start = 156 + _globals["_SENDRTCMDATARESPONSE"]._serialized_end = 225 + _globals["_RTKRESULT"]._serialized_start = 228 + _globals["_RTKRESULT"]._serialized_end = 431 + _globals["_RTKRESULT_RESULT"]._serialized_start = 311 + _globals["_RTKRESULT_RESULT"]._serialized_end = 431 + _globals["_RTKSERVICE"]._serialized_start = 433 + _globals["_RTKSERVICE"]._serialized_end = 542 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/rtk_pb2_grpc.py b/mavsdk/rtk_pb2_grpc.py index 0cae9f85..0bf95e82 100644 --- a/mavsdk/rtk_pb2_grpc.py +++ b/mavsdk/rtk_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import rtk_pb2 as rtk_dot_rtk__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in rtk/rtk_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in rtk/rtk_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class RtkServiceStub(object): - """Service to send RTK corrections to the vehicle. - """ + """Service to send RTK corrections to the vehicle.""" def __init__(self, channel): """Constructor. @@ -36,58 +39,61 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SendRtcmData = channel.unary_unary( - '/mavsdk.rpc.rtk.RtkService/SendRtcmData', - request_serializer=rtk_dot_rtk__pb2.SendRtcmDataRequest.SerializeToString, - response_deserializer=rtk_dot_rtk__pb2.SendRtcmDataResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.rtk.RtkService/SendRtcmData", + request_serializer=rtk_dot_rtk__pb2.SendRtcmDataRequest.SerializeToString, + response_deserializer=rtk_dot_rtk__pb2.SendRtcmDataResponse.FromString, + _registered_method=True, + ) class RtkServiceServicer(object): - """Service to send RTK corrections to the vehicle. - """ + """Service to send RTK corrections to the vehicle.""" def SendRtcmData(self, request, context): - """Send RTCM data. - """ + """Send RTCM data.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_RtkServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SendRtcmData': grpc.unary_unary_rpc_method_handler( - servicer.SendRtcmData, - request_deserializer=rtk_dot_rtk__pb2.SendRtcmDataRequest.FromString, - response_serializer=rtk_dot_rtk__pb2.SendRtcmDataResponse.SerializeToString, - ), + "SendRtcmData": grpc.unary_unary_rpc_method_handler( + servicer.SendRtcmData, + request_deserializer=rtk_dot_rtk__pb2.SendRtcmDataRequest.FromString, + response_serializer=rtk_dot_rtk__pb2.SendRtcmDataResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.rtk.RtkService', rpc_method_handlers) + "mavsdk.rpc.rtk.RtkService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.rtk.RtkService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.rtk.RtkService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class RtkService(object): - """Service to send RTK corrections to the vehicle. - """ + """Service to send RTK corrections to the vehicle.""" @staticmethod - def SendRtcmData(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SendRtcmData( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.rtk.RtkService/SendRtcmData', + "/mavsdk.rpc.rtk.RtkService/SendRtcmData", rtk_dot_rtk__pb2.SendRtcmDataRequest.SerializeToString, rtk_dot_rtk__pb2.SendRtcmDataResponse.FromString, options, @@ -98,4 +104,5 @@ def SendRtcmData(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/server_utility.py b/mavsdk/server_utility.py index 619ded82..e1d57741 100644 --- a/mavsdk/server_utility.py +++ b/mavsdk/server_utility.py @@ -8,37 +8,36 @@ class StatusTextType(Enum): """ - Status types. + Status types. - Values - ------ - DEBUG - Debug + Values + ------ + DEBUG + Debug - INFO - Information + INFO + Information - NOTICE - Notice + NOTICE + Notice - WARNING - Warning + WARNING + Warning - ERROR - Error + ERROR + Error - CRITICAL - Critical + CRITICAL + Critical - ALERT - Alert + ALERT + Alert - EMERGENCY - Emergency + EMERGENCY + Emergency - """ + """ - DEBUG = 0 INFO = 1 NOTICE = 2 @@ -68,7 +67,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == server_utility_pb2.STATUS_TEXT_TYPE_DEBUG: return StatusTextType.DEBUG if rpc_enum_value == server_utility_pb2.STATUS_TEXT_TYPE_INFO: @@ -92,44 +91,41 @@ def __str__(self): class ServerUtilityResult: """ - - Parameters - ---------- - result : Result - Result enum value - result_str : std::string - Human-readable English string describing the result + Parameters + ---------- + result : Result + Result enum value + + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for server utility requests. + Possible results returned for server utility requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - INVALID_ARGUMENT - Invalid argument + INVALID_ARGUMENT + Invalid argument - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -150,83 +146,75 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == server_utility_pb2.ServerUtilityResult.RESULT_UNKNOWN: return ServerUtilityResult.Result.UNKNOWN if rpc_enum_value == server_utility_pb2.ServerUtilityResult.RESULT_SUCCESS: return ServerUtilityResult.Result.SUCCESS - if rpc_enum_value == server_utility_pb2.ServerUtilityResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == server_utility_pb2.ServerUtilityResult.RESULT_NO_SYSTEM + ): return ServerUtilityResult.Result.NO_SYSTEM - if rpc_enum_value == server_utility_pb2.ServerUtilityResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == server_utility_pb2.ServerUtilityResult.RESULT_CONNECTION_ERROR + ): return ServerUtilityResult.Result.CONNECTION_ERROR - if rpc_enum_value == server_utility_pb2.ServerUtilityResult.RESULT_INVALID_ARGUMENT: + if ( + rpc_enum_value + == server_utility_pb2.ServerUtilityResult.RESULT_INVALID_ARGUMENT + ): return ServerUtilityResult.Result.INVALID_ARGUMENT def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ServerUtilityResult object """ + def __init__(self, result, result_str): + """Initializes the ServerUtilityResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ServerUtilityResult are the same """ + """Checks if two ServerUtilityResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ServerUtilityResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ServerUtilityResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ServerUtilityResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ServerUtilityResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcServerUtilityResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ServerUtilityResult( - - ServerUtilityResult.Result.translate_from_rpc(rpcServerUtilityResult.result), - - - rpcServerUtilityResult.result_str - ) + ServerUtilityResult.Result.translate_from_rpc( + rpcServerUtilityResult.result + ), + rpcServerUtilityResult.result_str, + ) def translate_to_rpc(self, rpcServerUtilityResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcServerUtilityResult.result = self.result.translate_to_rpc() - - - - - - rpcServerUtilityResult.result_str = self.result_str - - - + rpcServerUtilityResult.result_str = self.result_str class ServerUtilityError(Exception): - """ Raised when a ServerUtilityResult is a fail code """ + """Raised when a ServerUtilityResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -239,53 +227,48 @@ def __str__(self): class ServerUtility(AsyncBase): """ - Utility for onboard MAVSDK instances for common "server" tasks. + Utility for onboard MAVSDK instances for common "server" tasks. - Generated by dcsdkgen - MAVSDK ServerUtility API + Generated by dcsdkgen - MAVSDK ServerUtility API """ # Plugin name name = "ServerUtility" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = server_utility_pb2_grpc.ServerUtilityServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ServerUtilityResult.translate_from_rpc(response.server_utility_result) - async def send_status_text(self, type, text): """ - Sends a statustext. + Sends a statustext. - Parameters - ---------- - type : StatusTextType - The text to send + Parameters + ---------- + type : StatusTextType + The text to send - text : std::string - Text message + text : std::string + Text message - Raises - ------ - ServerUtilityError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ServerUtilityError + If the request fails. The error contains the reason for the failure. """ request = server_utility_pb2.SendStatusTextRequest() - + request.type = type.translate_to_rpc() - - + request.text = text response = await self._stub.SendStatusText(request) - result = self._extract_result(response) if result.result != ServerUtilityResult.Result.SUCCESS: raise ServerUtilityError(result, "send_status_text()", type, text) - \ No newline at end of file diff --git a/mavsdk/server_utility_pb2.py b/mavsdk/server_utility_pb2.py index a18c20be..7d9410d4 100644 --- a/mavsdk/server_utility_pb2.py +++ b/mavsdk/server_utility_pb2.py @@ -4,18 +4,15 @@ # source: server_utility/server_utility.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'server_utility/server_utility.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "server_utility/server_utility.proto" ) # @@protoc_insertion_point(imports) @@ -25,26 +22,36 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'server_utility.server_utility_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "server_utility.server_utility_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\030io.mavsdk.server_utilityB\022ServerUtilityProto' - _globals['_SERVERUTILITYSERVICE'].methods_by_name['SendStatusText']._loaded_options = None - _globals['_SERVERUTILITYSERVICE'].methods_by_name['SendStatusText']._serialized_options = b'\200\265\030\001' - _globals['_STATUSTEXTTYPE']._serialized_start=536 - _globals['_STATUSTEXTTYPE']._serialized_end=785 - _globals['_SENDSTATUSTEXTREQUEST']._serialized_start=88 - _globals['_SENDSTATUSTEXTREQUEST']._serialized_end=182 - _globals['_SENDSTATUSTEXTRESPONSE']._serialized_start=184 - _globals['_SENDSTATUSTEXTRESPONSE']._serialized_end=287 - _globals['_SERVERUTILITYRESULT']._serialized_start=290 - _globals['_SERVERUTILITYRESULT']._serialized_end=533 - _globals['_SERVERUTILITYRESULT_RESULT']._serialized_start=405 - _globals['_SERVERUTILITYRESULT_RESULT']._serialized_end=533 - _globals['_SERVERUTILITYSERVICE']._serialized_start=788 - _globals['_SERVERUTILITYSERVICE']._serialized_end=935 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\030io.mavsdk.server_utilityB\022ServerUtilityProto" + _globals["_SERVERUTILITYSERVICE"].methods_by_name[ + "SendStatusText" + ]._loaded_options = None + _globals["_SERVERUTILITYSERVICE"].methods_by_name[ + "SendStatusText" + ]._serialized_options = b"\200\265\030\001" + _globals["_STATUSTEXTTYPE"]._serialized_start = 536 + _globals["_STATUSTEXTTYPE"]._serialized_end = 785 + _globals["_SENDSTATUSTEXTREQUEST"]._serialized_start = 88 + _globals["_SENDSTATUSTEXTREQUEST"]._serialized_end = 182 + _globals["_SENDSTATUSTEXTRESPONSE"]._serialized_start = 184 + _globals["_SENDSTATUSTEXTRESPONSE"]._serialized_end = 287 + _globals["_SERVERUTILITYRESULT"]._serialized_start = 290 + _globals["_SERVERUTILITYRESULT"]._serialized_end = 533 + _globals["_SERVERUTILITYRESULT_RESULT"]._serialized_start = 405 + _globals["_SERVERUTILITYRESULT_RESULT"]._serialized_end = 533 + _globals["_SERVERUTILITYSERVICE"]._serialized_start = 788 + _globals["_SERVERUTILITYSERVICE"]._serialized_end = 935 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/server_utility_pb2_grpc.py b/mavsdk/server_utility_pb2_grpc.py index 3cfdc3b9..3860afdc 100644 --- a/mavsdk/server_utility_pb2_grpc.py +++ b/mavsdk/server_utility_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import server_utility_pb2 as server__utility_dot_server__utility__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in server_utility/server_utility_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in server_utility/server_utility_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -37,10 +41,11 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SendStatusText = channel.unary_unary( - '/mavsdk.rpc.server_utility.ServerUtilityService/SendStatusText', - request_serializer=server__utility_dot_server__utility__pb2.SendStatusTextRequest.SerializeToString, - response_deserializer=server__utility_dot_server__utility__pb2.SendStatusTextResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.server_utility.ServerUtilityService/SendStatusText", + request_serializer=server__utility_dot_server__utility__pb2.SendStatusTextRequest.SerializeToString, + response_deserializer=server__utility_dot_server__utility__pb2.SendStatusTextResponse.FromString, + _registered_method=True, + ) class ServerUtilityServiceServicer(object): @@ -49,48 +54,52 @@ class ServerUtilityServiceServicer(object): """ def SendStatusText(self, request, context): - """Sends a statustext. - """ + """Sends a statustext.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ServerUtilityServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SendStatusText': grpc.unary_unary_rpc_method_handler( - servicer.SendStatusText, - request_deserializer=server__utility_dot_server__utility__pb2.SendStatusTextRequest.FromString, - response_serializer=server__utility_dot_server__utility__pb2.SendStatusTextResponse.SerializeToString, - ), + "SendStatusText": grpc.unary_unary_rpc_method_handler( + servicer.SendStatusText, + request_deserializer=server__utility_dot_server__utility__pb2.SendStatusTextRequest.FromString, + response_serializer=server__utility_dot_server__utility__pb2.SendStatusTextResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.server_utility.ServerUtilityService', rpc_method_handlers) + "mavsdk.rpc.server_utility.ServerUtilityService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.server_utility.ServerUtilityService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.server_utility.ServerUtilityService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ServerUtilityService(object): """ Utility for onboard MAVSDK instances for common "server" tasks. """ @staticmethod - def SendStatusText(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SendStatusText( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.server_utility.ServerUtilityService/SendStatusText', + "/mavsdk.rpc.server_utility.ServerUtilityService/SendStatusText", server__utility_dot_server__utility__pb2.SendStatusTextRequest.SerializeToString, server__utility_dot_server__utility__pb2.SendStatusTextResponse.FromString, options, @@ -101,4 +110,5 @@ def SendStatusText(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/shell.py b/mavsdk/shell.py index 6eb53eb6..42e109e1 100644 --- a/mavsdk/shell.py +++ b/mavsdk/shell.py @@ -8,47 +8,44 @@ class ShellResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for shell requests + Possible results returned for shell requests - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - NO_RESPONSE - Response was not received + NO_RESPONSE + Response was not received - BUSY - Shell busy (transfer in progress) + BUSY + Shell busy (transfer in progress) - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -72,7 +69,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == shell_pb2.ShellResult.RESULT_UNKNOWN: return ShellResult.Result.UNKNOWN if rpc_enum_value == shell_pb2.ShellResult.RESULT_SUCCESS: @@ -88,69 +85,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the ShellResult object """ + def __init__(self, result, result_str): + """Initializes the ShellResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two ShellResult are the same """ + """Checks if two ShellResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # ShellResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ ShellResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """ShellResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"ShellResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcShellResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ShellResult( - - ShellResult.Result.translate_from_rpc(rpcShellResult.result), - - - rpcShellResult.result_str - ) + ShellResult.Result.translate_from_rpc(rpcShellResult.result), + rpcShellResult.result_str, + ) def translate_to_rpc(self, rpcShellResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcShellResult.result = self.result.translate_to_rpc() - - - - - - rpcShellResult.result_str = self.result_str - - - + rpcShellResult.result_str = self.result_str class ShellError(Exception): - """ Raised when a ShellResult is a fail code """ + """Raised when a ShellResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -163,62 +141,58 @@ def __str__(self): class Shell(AsyncBase): """ - Allow to communicate with the vehicle's system shell. + Allow to communicate with the vehicle's system shell. - Generated by dcsdkgen - MAVSDK Shell API + Generated by dcsdkgen - MAVSDK Shell API """ # Plugin name name = "Shell" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = shell_pb2_grpc.ShellServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return ShellResult.translate_from_rpc(response.shell_result) - async def send(self, command): """ - Send a command line. + Send a command line. - Parameters - ---------- - command : std::string - The command line to send + Parameters + ---------- + command : std::string + The command line to send - Raises - ------ - ShellError - If the request fails. The error contains the reason for the failure. + Raises + ------ + ShellError + If the request fails. The error contains the reason for the failure. """ request = shell_pb2.SendRequest() request.command = command response = await self._stub.Send(request) - result = self._extract_result(response) if result.result != ShellResult.Result.SUCCESS: raise ShellError(result, "send()", command) - async def receive(self): """ - Receive feedback from a sent command line. + Receive feedback from a sent command line. + + This subscription needs to be made before a command line is sent, otherwise, no response will be sent. - This subscription needs to be made before a command line is sent, otherwise, no response will be sent. + Yields + ------- + data : std::string + Received data. - Yields - ------- - data : std::string - Received data. - """ request = shell_pb2.SubscribeReceiveRequest() @@ -226,9 +200,6 @@ async def receive(self): try: async for response in receive_stream: - - - yield response.data finally: - receive_stream.cancel() \ No newline at end of file + receive_stream.cancel() diff --git a/mavsdk/shell_pb2.py b/mavsdk/shell_pb2.py index 726af462..a35f8ae8 100644 --- a/mavsdk/shell_pb2.py +++ b/mavsdk/shell_pb2.py @@ -4,18 +4,15 @@ # source: shell/shell.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'shell/shell.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "shell/shell.proto" ) # @@protoc_insertion_point(imports) @@ -25,30 +22,36 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'shell.shell_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "shell.shell_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\017io.mavsdk.shellB\nShellProto' - _globals['_SHELLSERVICE'].methods_by_name['Send']._loaded_options = None - _globals['_SHELLSERVICE'].methods_by_name['Send']._serialized_options = b'\200\265\030\001' - _globals['_SHELLSERVICE'].methods_by_name['SubscribeReceive']._loaded_options = None - _globals['_SHELLSERVICE'].methods_by_name['SubscribeReceive']._serialized_options = b'\200\265\030\000' - _globals['_SENDREQUEST']._serialized_start=61 - _globals['_SENDREQUEST']._serialized_end=91 - _globals['_SENDRESPONSE']._serialized_start=93 - _globals['_SENDRESPONSE']._serialized_end=160 - _globals['_SUBSCRIBERECEIVEREQUEST']._serialized_start=162 - _globals['_SUBSCRIBERECEIVEREQUEST']._serialized_end=187 - _globals['_RECEIVERESPONSE']._serialized_start=189 - _globals['_RECEIVERESPONSE']._serialized_end=220 - _globals['_SHELLRESULT']._serialized_start=223 - _globals['_SHELLRESULT']._serialized_end=453 - _globals['_SHELLRESULT_RESULT']._serialized_start=313 - _globals['_SHELLRESULT_RESULT']._serialized_end=453 - _globals['_SHELLSERVICE']._serialized_start=456 - _globals['_SHELLSERVICE']._serialized_end=653 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\017io.mavsdk.shellB\nShellProto" + _globals["_SHELLSERVICE"].methods_by_name["Send"]._loaded_options = None + _globals["_SHELLSERVICE"].methods_by_name[ + "Send" + ]._serialized_options = b"\200\265\030\001" + _globals["_SHELLSERVICE"].methods_by_name["SubscribeReceive"]._loaded_options = None + _globals["_SHELLSERVICE"].methods_by_name[ + "SubscribeReceive" + ]._serialized_options = b"\200\265\030\000" + _globals["_SENDREQUEST"]._serialized_start = 61 + _globals["_SENDREQUEST"]._serialized_end = 91 + _globals["_SENDRESPONSE"]._serialized_start = 93 + _globals["_SENDRESPONSE"]._serialized_end = 160 + _globals["_SUBSCRIBERECEIVEREQUEST"]._serialized_start = 162 + _globals["_SUBSCRIBERECEIVEREQUEST"]._serialized_end = 187 + _globals["_RECEIVERESPONSE"]._serialized_start = 189 + _globals["_RECEIVERESPONSE"]._serialized_end = 220 + _globals["_SHELLRESULT"]._serialized_start = 223 + _globals["_SHELLRESULT"]._serialized_end = 453 + _globals["_SHELLRESULT_RESULT"]._serialized_start = 313 + _globals["_SHELLRESULT_RESULT"]._serialized_end = 453 + _globals["_SHELLSERVICE"]._serialized_start = 456 + _globals["_SHELLSERVICE"]._serialized_end = 653 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/shell_pb2_grpc.py b/mavsdk/shell_pb2_grpc.py index ff198c0d..f2172ac4 100644 --- a/mavsdk/shell_pb2_grpc.py +++ b/mavsdk/shell_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import shell_pb2 as shell_dot_shell__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in shell/shell_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in shell/shell_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -37,15 +41,17 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.Send = channel.unary_unary( - '/mavsdk.rpc.shell.ShellService/Send', - request_serializer=shell_dot_shell__pb2.SendRequest.SerializeToString, - response_deserializer=shell_dot_shell__pb2.SendResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.shell.ShellService/Send", + request_serializer=shell_dot_shell__pb2.SendRequest.SerializeToString, + response_deserializer=shell_dot_shell__pb2.SendResponse.FromString, + _registered_method=True, + ) self.SubscribeReceive = channel.unary_stream( - '/mavsdk.rpc.shell.ShellService/SubscribeReceive', - request_serializer=shell_dot_shell__pb2.SubscribeReceiveRequest.SerializeToString, - response_deserializer=shell_dot_shell__pb2.ReceiveResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.shell.ShellService/SubscribeReceive", + request_serializer=shell_dot_shell__pb2.SubscribeReceiveRequest.SerializeToString, + response_deserializer=shell_dot_shell__pb2.ReceiveResponse.FromString, + _registered_method=True, + ) class ShellServiceServicer(object): @@ -58,8 +64,8 @@ def Send(self, request, context): Send a command line. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeReceive(self, request, context): """ @@ -68,50 +74,55 @@ def SubscribeReceive(self, request, context): This subscription needs to be made before a command line is sent, otherwise, no response will be sent. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_ShellServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'Send': grpc.unary_unary_rpc_method_handler( - servicer.Send, - request_deserializer=shell_dot_shell__pb2.SendRequest.FromString, - response_serializer=shell_dot_shell__pb2.SendResponse.SerializeToString, - ), - 'SubscribeReceive': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeReceive, - request_deserializer=shell_dot_shell__pb2.SubscribeReceiveRequest.FromString, - response_serializer=shell_dot_shell__pb2.ReceiveResponse.SerializeToString, - ), + "Send": grpc.unary_unary_rpc_method_handler( + servicer.Send, + request_deserializer=shell_dot_shell__pb2.SendRequest.FromString, + response_serializer=shell_dot_shell__pb2.SendResponse.SerializeToString, + ), + "SubscribeReceive": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeReceive, + request_deserializer=shell_dot_shell__pb2.SubscribeReceiveRequest.FromString, + response_serializer=shell_dot_shell__pb2.ReceiveResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.shell.ShellService', rpc_method_handlers) + "mavsdk.rpc.shell.ShellService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.shell.ShellService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.shell.ShellService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class ShellService(object): """ Allow to communicate with the vehicle's system shell. """ @staticmethod - def Send(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Send( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.shell.ShellService/Send', + "/mavsdk.rpc.shell.ShellService/Send", shell_dot_shell__pb2.SendRequest.SerializeToString, shell_dot_shell__pb2.SendResponse.FromString, options, @@ -122,23 +133,26 @@ def Send(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeReceive(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeReceive( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.shell.ShellService/SubscribeReceive', + "/mavsdk.rpc.shell.ShellService/SubscribeReceive", shell_dot_shell__pb2.SubscribeReceiveRequest.SerializeToString, shell_dot_shell__pb2.ReceiveResponse.FromString, options, @@ -149,4 +163,5 @@ def SubscribeReceive(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/source/conf.py b/mavsdk/source/conf.py index c8a7e5d9..d6aa34f0 100644 --- a/mavsdk/source/conf.py +++ b/mavsdk/source/conf.py @@ -13,19 +13,20 @@ # If extensions (or modules to document with autodoc) are in another directory, # add these directories to sys.path here. If the directory is relative to the # documentation root, use os.path.abspath to make it absolute, like shown here. -sys.path.insert(0, os.path.abspath('../..')) +sys.path.insert(0, os.path.abspath("../..")) # -- Project information ----------------------------------------------------- -project = 'MAVSDK-Python' -copyright = '2020, Jonas Vautherin, Julian Oes' -author = 'Jonas Vautherin, Julian Oes' +project = "MAVSDK-Python" +copyright = "2020, Jonas Vautherin, Julian Oes" +author = "Jonas Vautherin, Julian Oes" -result = subprocess.run(['git', 'describe', '--tag', '--abbrev=0'], - stdout=subprocess.PIPE) +result = subprocess.run( + ["git", "describe", "--tag", "--abbrev=0"], stdout=subprocess.PIPE +) # The full version, including alpha/beta/rc tags -release = result.stdout.decode('utf-8') +release = result.stdout.decode("utf-8") # -- General configuration --------------------------------------------------- @@ -33,13 +34,10 @@ # Add any Sphinx extension module names here, as strings. They can be # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom # ones. -extensions = [ - 'sphinx.ext.autodoc', - 'sphinx.ext.napoleon' -] +extensions = ["sphinx.ext.autodoc", "sphinx.ext.napoleon"] # Add any paths that contain templates here, relative to this directory. -templates_path = ['_templates'] +templates_path = ["_templates"] # List of patterns, relative to source directory, that match files and # directories to ignore when looking for source files. @@ -52,12 +50,12 @@ # The theme to use for HTML and HTML Help pages. See the documentation for # a list of builtin themes. # -html_theme = 'nature_adapted' +html_theme = "nature_adapted" html_theme_path = ["."] # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, # so a file named "default.css" will overwrite the builtin "default.css". -html_static_path = ['nature_adapted/static'] +html_static_path = ["nature_adapted/static"] html_favicon = "nature_adapted/static/favicon.png" diff --git a/mavsdk/system.py b/mavsdk/system.py index 28da20f0..f1f9e03a 100644 --- a/mavsdk/system.py +++ b/mavsdk/system.py @@ -72,15 +72,15 @@ def run(self): # Strip ANSI color codes used by MAVSDK # MAVSDK uses: \x1b[31m, \x1b[32m, \x1b[33m, \x1b[34m, \x1b[37m, \x1b[0m # Also handle \033[ variant (equivalent to \x1b[) - for escape_seq in ['\x1b[', '\033[']: + for escape_seq in ["\x1b[", "\033["]: while escape_seq in message: start = message.find(escape_seq) if start == -1: break - end = message.find('m', start) + end = message.find("m", start) if end == -1: break - message = message[:start] + message[end + 1:] + message = message[:start] + message[end + 1 :] # Parse mavsdk_server log level prefixes and map to Python logging levels # Format is: [timestamp|Level] message (filename:line) @@ -110,6 +110,7 @@ def run(self): if self.pipe and not self.pipe.closed: self.pipe.close() + class System: """ Instantiate a System object, that will serve as a proxy to @@ -133,6 +134,7 @@ class System: MAVLink component ID of the mavsdk_server (1..255). """ + def __init__(self, mavsdk_server_address=None, port=50051, sysid=245, compid=190): self._mavsdk_server_address = mavsdk_server_address self._port = port @@ -171,10 +173,11 @@ async def connect(self, system_address=None): # add a delay to be sure resources have been freed and restart mavsdk_server await asyncio.sleep(1) - if self._mavsdk_server_address is None: - self._mavsdk_server_address = 'localhost' - self._server_process = self._start_mavsdk_server(system_address,self._port, self._sysid, self._compid) + self._mavsdk_server_address = "localhost" + self._server_process = self._start_mavsdk_server( + system_address, self._port, self._sysid, self._compid + ) await self._init_plugins(self._mavsdk_server_address, self._port) @@ -183,9 +186,10 @@ def _stop_mavsdk_server(self): kill the running mavsdk_server and clean the whole instance """ import subprocess - if isinstance(self._server_process,subprocess.Popen): + + if isinstance(self._server_process, subprocess.Popen): self._server_process.kill() - self.__init__(port = self._port) + self.__init__(port=self._port) async def _init_plugins(self, host, port): plugin_manager = await AsyncPluginManager.create(host=host, port=port) @@ -193,14 +197,24 @@ async def _init_plugins(self, host, port): self._plugins = {} self._plugins["action"] = action.Action(plugin_manager) self._plugins["action_server"] = action_server.ActionServer(plugin_manager) - self._plugins["arm_authorizer_server"] = arm_authorizer_server.ArmAuthorizerServer(plugin_manager) + self._plugins["arm_authorizer_server"] = ( + arm_authorizer_server.ArmAuthorizerServer(plugin_manager) + ) self._plugins["calibration"] = calibration.Calibration(plugin_manager) self._plugins["camera"] = camera.Camera(plugin_manager) self._plugins["camera_server"] = camera_server.CameraServer(plugin_manager) - self._plugins["component_information"] = component_information.ComponentInformation(plugin_manager) - self._plugins["component_information_server"] = component_information_server.ComponentInformationServer(plugin_manager) - self._plugins["component_metadata"] = component_metadata.ComponentMetadata(plugin_manager) - self._plugins["component_metadata_server"] = component_metadata_server.ComponentMetadataServer(plugin_manager) + self._plugins["component_information"] = ( + component_information.ComponentInformation(plugin_manager) + ) + self._plugins["component_information_server"] = ( + component_information_server.ComponentInformationServer(plugin_manager) + ) + self._plugins["component_metadata"] = component_metadata.ComponentMetadata( + plugin_manager + ) + self._plugins["component_metadata_server"] = ( + component_metadata_server.ComponentMetadataServer(plugin_manager) + ) self._plugins["core"] = core.Core(plugin_manager) self._plugins["events"] = events.Events(plugin_manager) self._plugins["failure"] = failure.Failure(plugin_manager) @@ -217,7 +231,9 @@ async def _init_plugins(self, host, port): self._plugins["mavlink_direct"] = mavlink_direct.MavlinkDirect(plugin_manager) self._plugins["mission"] = mission.Mission(plugin_manager) self._plugins["mission_raw"] = mission_raw.MissionRaw(plugin_manager) - self._plugins["mission_raw_server"] = mission_raw_server.MissionRawServer(plugin_manager) + self._plugins["mission_raw_server"] = mission_raw_server.MissionRawServer( + plugin_manager + ) self._plugins["mocap"] = mocap.Mocap(plugin_manager) self._plugins["offboard"] = offboard.Offboard(plugin_manager) self._plugins["param"] = param.Param(plugin_manager) @@ -226,16 +242,22 @@ async def _init_plugins(self, host, port): self._plugins["server_utility"] = server_utility.ServerUtility(plugin_manager) self._plugins["shell"] = shell.Shell(plugin_manager) self._plugins["telemetry"] = telemetry.Telemetry(plugin_manager) - self._plugins["telemetry_server"] = telemetry_server.TelemetryServer(plugin_manager) - self._plugins["tracking_server"] = tracking_server.TrackingServer(plugin_manager) + self._plugins["telemetry_server"] = telemetry_server.TelemetryServer( + plugin_manager + ) + self._plugins["tracking_server"] = tracking_server.TrackingServer( + plugin_manager + ) self._plugins["transponder"] = transponder.Transponder(plugin_manager) self._plugins["tune"] = tune.Tune(plugin_manager) self._plugins["winch"] = winch.Winch(plugin_manager) @staticmethod def error_uninitialized(plugin_name: str) -> str: - return f"{plugin_name} plugin has not been initialized! " \ + return ( + f"{plugin_name} plugin has not been initialized! " "Did you run `System.connect()`?" + ) @property def action(self) -> action.Action: @@ -280,7 +302,9 @@ def component_information(self) -> component_information.ComponentInformation: return self._plugins["component_information"] @property - def component_information_server(self) -> component_information_server.ComponentInformationServer: + def component_information_server( + self, + ) -> component_information_server.ComponentInformationServer: if "component_information_server" not in self._plugins: raise RuntimeError(self.error_uninitialized("ComponentInformationServer")) return self._plugins["component_information_server"] @@ -292,7 +316,9 @@ def component_metadata(self) -> component_metadata.ComponentMetadata: return self._plugins["component_metadata"] @property - def component_metadata_server(self) -> component_metadata_server.ComponentMetadataServer: + def component_metadata_server( + self, + ) -> component_metadata_server.ComponentMetadataServer: if "component_metadata_server" not in self._plugins: raise RuntimeError(self.error_uninitialized("ComponentMetadataServer")) return self._plugins["component_metadata_server"] @@ -494,25 +520,32 @@ def _start_mavsdk_server(system_address, port, sysid, compid): from importlib_resources import path try: - if sys.platform.startswith('win'): + if sys.platform.startswith("win"): mavsdk_exec_name = "mavsdk_server.exe" else: mavsdk_exec_name = "mavsdk_server" with path(bin, mavsdk_exec_name) as backend: - bin_path_and_args = [os.fspath(backend), - "-p", str(port), - "--sysid", str(sysid), - "--compid", str(compid)] + bin_path_and_args = [ + os.fspath(backend), + "-p", + str(port), + "--sysid", + str(sysid), + "--compid", + str(compid), + ] if system_address: bin_path_and_args.append(system_address) - p = subprocess.Popen(bin_path_and_args, - shell=False, - stdout=subprocess.PIPE, - stderr=subprocess.STDOUT) + p = subprocess.Popen( + bin_path_and_args, + shell=False, + stdout=subprocess.PIPE, + stderr=subprocess.STDOUT, + ) - logger = logging.getLogger('mavsdk_server') + logger = logging.getLogger("mavsdk_server") log_thread = _LoggingThread(p.stdout, logger) log_thread.start() except FileNotFoundError: diff --git a/mavsdk/telemetry.py b/mavsdk/telemetry.py index 11d994a9..398d545f 100644 --- a/mavsdk/telemetry.py +++ b/mavsdk/telemetry.py @@ -8,34 +8,33 @@ class FixType(Enum): """ - GPS fix type. + GPS fix type. - Values - ------ - NO_GPS - No GPS connected + Values + ------ + NO_GPS + No GPS connected - NO_FIX - No position information, GPS is connected + NO_FIX + No position information, GPS is connected - FIX_2D - 2D position + FIX_2D + 2D position - FIX_3D - 3D position + FIX_3D + 3D position - FIX_DGPS - DGPS/SBAS aided 3D position + FIX_DGPS + DGPS/SBAS aided 3D position - RTK_FLOAT - RTK float, 3D position + RTK_FLOAT + RTK float, 3D position - RTK_FIXED - RTK Fixed, 3D position + RTK_FIXED + RTK Fixed, 3D position - """ + """ - NO_GPS = 0 NO_FIX = 1 FIX_2D = 2 @@ -62,7 +61,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.FIX_TYPE_NO_GPS: return FixType.NO_GPS if rpc_enum_value == telemetry_pb2.FIX_TYPE_NO_FIX: @@ -84,28 +83,27 @@ def __str__(self): class BatteryFunction(Enum): """ - Battery function type. + Battery function type. - Values - ------ - UNKNOWN - Battery function is unknown + Values + ------ + UNKNOWN + Battery function is unknown - ALL - Battery supports all flight systems + ALL + Battery supports all flight systems - PROPULSION - Battery for the propulsion system + PROPULSION + Battery for the propulsion system - AVIONICS - Avionics battery + AVIONICS + Avionics battery - PAYLOAD - Payload battery + PAYLOAD + Payload battery - """ + """ - UNKNOWN = 0 ALL = 1 PROPULSION = 2 @@ -126,7 +124,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.BATTERY_FUNCTION_UNKNOWN: return BatteryFunction.UNKNOWN if rpc_enum_value == telemetry_pb2.BATTERY_FUNCTION_ALL: @@ -144,61 +142,60 @@ def __str__(self): class FlightMode(Enum): """ - Flight modes. + Flight modes. - For more information about flight modes, check out - https://docs.px4.io/master/en/config/flight_mode.html. + For more information about flight modes, check out + https://docs.px4.io/master/en/config/flight_mode.html. - Values - ------ - UNKNOWN - Mode not known + Values + ------ + UNKNOWN + Mode not known - READY - Armed and ready to take off + READY + Armed and ready to take off - TAKEOFF - Taking off + TAKEOFF + Taking off - HOLD - Holding (hovering in place (or circling for fixed-wing vehicles) + HOLD + Holding (hovering in place (or circling for fixed-wing vehicles) - MISSION - In mission + MISSION + In mission - RETURN_TO_LAUNCH - Returning to launch position (then landing) + RETURN_TO_LAUNCH + Returning to launch position (then landing) - LAND - Landing + LAND + Landing - OFFBOARD - In 'offboard' mode + OFFBOARD + In 'offboard' mode - FOLLOW_ME - In 'follow-me' mode + FOLLOW_ME + In 'follow-me' mode - MANUAL - In 'Manual' mode + MANUAL + In 'Manual' mode - ALTCTL - In 'Altitude Control' mode + ALTCTL + In 'Altitude Control' mode - POSCTL - In 'Position Control' mode + POSCTL + In 'Position Control' mode - ACRO - In 'Acro' mode + ACRO + In 'Acro' mode - STABILIZED - In 'Stabilize' mode + STABILIZED + In 'Stabilize' mode - RATTITUDE - In 'Rattitude' mode + RATTITUDE + In 'Rattitude' mode - """ + """ - UNKNOWN = 0 READY = 1 TAKEOFF = 2 @@ -249,7 +246,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.FLIGHT_MODE_UNKNOWN: return FlightMode.UNKNOWN if rpc_enum_value == telemetry_pb2.FLIGHT_MODE_READY: @@ -287,37 +284,36 @@ def __str__(self): class StatusTextType(Enum): """ - Status types. + Status types. - Values - ------ - DEBUG - Debug + Values + ------ + DEBUG + Debug - INFO - Information + INFO + Information - NOTICE - Notice + NOTICE + Notice - WARNING - Warning + WARNING + Warning - ERROR - Error + ERROR + Error - CRITICAL - Critical + CRITICAL + Critical - ALERT - Alert + ALERT + Alert - EMERGENCY - Emergency + EMERGENCY + Emergency - """ + """ - DEBUG = 0 INFO = 1 NOTICE = 2 @@ -347,7 +343,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.STATUS_TEXT_TYPE_DEBUG: return StatusTextType.DEBUG if rpc_enum_value == telemetry_pb2.STATUS_TEXT_TYPE_INFO: @@ -371,28 +367,27 @@ def __str__(self): class LandedState(Enum): """ - Landed State enumeration. + Landed State enumeration. - Values - ------ - UNKNOWN - Landed state is unknown + Values + ------ + UNKNOWN + Landed state is unknown - ON_GROUND - The vehicle is on the ground + ON_GROUND + The vehicle is on the ground - IN_AIR - The vehicle is in the air + IN_AIR + The vehicle is in the air - TAKING_OFF - The vehicle is taking off + TAKING_OFF + The vehicle is taking off - LANDING - The vehicle is landing + LANDING + The vehicle is landing - """ + """ - UNKNOWN = 0 ON_GROUND = 1 IN_AIR = 2 @@ -413,7 +408,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.LANDED_STATE_UNKNOWN: return LandedState.UNKNOWN if rpc_enum_value == telemetry_pb2.LANDED_STATE_ON_GROUND: @@ -431,28 +426,27 @@ def __str__(self): class VtolState(Enum): """ - VTOL State enumeration + VTOL State enumeration - Values - ------ - UNDEFINED - MAV is not configured as VTOL + Values + ------ + UNDEFINED + MAV is not configured as VTOL - TRANSITION_TO_FW - VTOL is in transition from multicopter to fixed-wing + TRANSITION_TO_FW + VTOL is in transition from multicopter to fixed-wing - TRANSITION_TO_MC - VTOL is in transition from fixed-wing to multicopter + TRANSITION_TO_MC + VTOL is in transition from fixed-wing to multicopter - MC - VTOL is in multicopter state + MC + VTOL is in multicopter state - FW - VTOL is in fixed-wing state + FW + VTOL is in fixed-wing state - """ + """ - UNDEFINED = 0 TRANSITION_TO_FW = 1 TRANSITION_TO_MC = 2 @@ -473,7 +467,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.VTOL_STATE_UNDEFINED: return VtolState.UNDEFINED if rpc_enum_value == telemetry_pb2.VTOL_STATE_TRANSITION_TO_FW: @@ -491,208 +485,157 @@ def __str__(self): class Position: """ - Position type in global coordinates. - - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Position type in global coordinates. - longitude_deg : double - Longitude in degrees (range: -180 to +180) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + longitude_deg : double + Longitude in degrees (range: -180 to +180) - relative_altitude_m : float - Altitude relative to takeoff altitude in metres + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - """ + relative_altitude_m : float + Altitude relative to takeoff altitude in metres - + """ def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m, - relative_altitude_m): - """ Initializes the Position object """ + self, latitude_deg, longitude_deg, absolute_altitude_m, relative_altitude_m + ): + """Initializes the Position object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m def __eq__(self, to_compare): - """ Checks if two Position are the same """ + """Checks if two Position are the same""" try: # Try to compare - this likely fails when it is compared to a non # Position object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.relative_altitude_m == to_compare.relative_altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.relative_altitude_m == to_compare.relative_altitude_m) + ) except AttributeError: return False def __str__(self): - """ Position in string representation """ - struct_repr = ", ".join([ + """Position in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), "absolute_altitude_m: " + str(self.absolute_altitude_m), - "relative_altitude_m: " + str(self.relative_altitude_m) - ]) + "relative_altitude_m: " + str(self.relative_altitude_m), + ] + ) return f"Position: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPosition): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Position( - - rpcPosition.latitude_deg, - - - rpcPosition.longitude_deg, - - - rpcPosition.absolute_altitude_m, - - - rpcPosition.relative_altitude_m - ) + rpcPosition.latitude_deg, + rpcPosition.longitude_deg, + rpcPosition.absolute_altitude_m, + rpcPosition.relative_altitude_m, + ) def translate_to_rpc(self, rpcPosition): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPosition.latitude_deg = self.latitude_deg - - - - - + rpcPosition.longitude_deg = self.longitude_deg - - - - - + rpcPosition.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcPosition.relative_altitude_m = self.relative_altitude_m - - - class Heading: """ - Heading type used for global position - - Parameters - ---------- - heading_deg : double - Heading in degrees (range: 0 to +360) + Heading type used for global position - """ + Parameters + ---------- + heading_deg : double + Heading in degrees (range: 0 to +360) - + """ - def __init__( - self, - heading_deg): - """ Initializes the Heading object """ + def __init__(self, heading_deg): + """Initializes the Heading object""" self.heading_deg = heading_deg def __eq__(self, to_compare): - """ Checks if two Heading are the same """ + """Checks if two Heading are the same""" try: # Try to compare - this likely fails when it is compared to a non # Heading object - return \ - (self.heading_deg == to_compare.heading_deg) + return self.heading_deg == to_compare.heading_deg except AttributeError: return False def __str__(self): - """ Heading in string representation """ - struct_repr = ", ".join([ - "heading_deg: " + str(self.heading_deg) - ]) + """Heading in string representation""" + struct_repr = ", ".join(["heading_deg: " + str(self.heading_deg)]) return f"Heading: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHeading): - """ Translates a gRPC struct to the SDK equivalent """ - return Heading( - - rpcHeading.heading_deg - ) + """Translates a gRPC struct to the SDK equivalent""" + return Heading(rpcHeading.heading_deg) def translate_to_rpc(self, rpcHeading): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcHeading.heading_deg = self.heading_deg - - - class Quaternion: """ - Quaternion type. - - All rotations and axis systems follow the right-hand rule. - The Hamilton quaternion product definition is used. - A zero-rotation quaternion is represented by (1,0,0,0). - The quaternion could also be written as w + xi + yj + zk. + Quaternion type. - For more info see: https://en.wikipedia.org/wiki/Quaternion + All rotations and axis systems follow the right-hand rule. + The Hamilton quaternion product definition is used. + A zero-rotation quaternion is represented by (1,0,0,0). + The quaternion could also be written as w + xi + yj + zk. - Parameters - ---------- - w : float - Quaternion entry 0, also denoted as a + For more info see: https://en.wikipedia.org/wiki/Quaternion - x : float - Quaternion entry 1, also denoted as b + Parameters + ---------- + w : float + Quaternion entry 0, also denoted as a - y : float - Quaternion entry 2, also denoted as c + x : float + Quaternion entry 1, also denoted as b - z : float - Quaternion entry 3, also denoted as d + y : float + Quaternion entry 2, also denoted as c - timestamp_us : uint64_t - Timestamp in microseconds + z : float + Quaternion entry 3, also denoted as d - """ + timestamp_us : uint64_t + Timestamp in microseconds - + """ - def __init__( - self, - w, - x, - y, - z, - timestamp_us): - """ Initializes the Quaternion object """ + def __init__(self, w, x, y, z, timestamp_us): + """Initializes the Quaternion object""" self.w = w self.x = x self.y = y @@ -700,435 +643,338 @@ def __init__( self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two Quaternion are the same """ + """Checks if two Quaternion are the same""" try: # Try to compare - this likely fails when it is compared to a non # Quaternion object - return \ - (self.w == to_compare.w) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.w == to_compare.w) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ Quaternion in string representation """ - struct_repr = ", ".join([ + """Quaternion in string representation""" + struct_repr = ", ".join( + [ "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), "z: " + str(self.z), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"Quaternion: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcQuaternion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Quaternion( - - rpcQuaternion.w, - - - rpcQuaternion.x, - - - rpcQuaternion.y, - - - rpcQuaternion.z, - - - rpcQuaternion.timestamp_us - ) + rpcQuaternion.w, + rpcQuaternion.x, + rpcQuaternion.y, + rpcQuaternion.z, + rpcQuaternion.timestamp_us, + ) def translate_to_rpc(self, rpcQuaternion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcQuaternion.w = self.w - - - - - + rpcQuaternion.x = self.x - - - - - + rpcQuaternion.y = self.y - - - - - + rpcQuaternion.z = self.z - - - - - + rpcQuaternion.timestamp_us = self.timestamp_us - - - class EulerAngle: """ - Euler angle type. - - All rotations and axis systems follow the right-hand rule. - The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. + Euler angle type. - For more info see https://en.wikipedia.org/wiki/Euler_angles + All rotations and axis systems follow the right-hand rule. + The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. - Parameters - ---------- - roll_deg : float - Roll angle in degrees, positive is banking to the right + For more info see https://en.wikipedia.org/wiki/Euler_angles - pitch_deg : float - Pitch angle in degrees, positive is pitching nose up + Parameters + ---------- + roll_deg : float + Roll angle in degrees, positive is banking to the right - yaw_deg : float - Yaw angle in degrees, positive is clock-wise seen from above + pitch_deg : float + Pitch angle in degrees, positive is pitching nose up - timestamp_us : uint64_t - Timestamp in microseconds + yaw_deg : float + Yaw angle in degrees, positive is clock-wise seen from above - """ + timestamp_us : uint64_t + Timestamp in microseconds - + """ - def __init__( - self, - roll_deg, - pitch_deg, - yaw_deg, - timestamp_us): - """ Initializes the EulerAngle object """ + def __init__(self, roll_deg, pitch_deg, yaw_deg, timestamp_us): + """Initializes the EulerAngle object""" self.roll_deg = roll_deg self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two EulerAngle are the same """ + """Checks if two EulerAngle are the same""" try: # Try to compare - this likely fails when it is compared to a non # EulerAngle object - return \ - (self.roll_deg == to_compare.roll_deg) and \ - (self.pitch_deg == to_compare.pitch_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.roll_deg == to_compare.roll_deg) + and (self.pitch_deg == to_compare.pitch_deg) + and (self.yaw_deg == to_compare.yaw_deg) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ EulerAngle in string representation """ - struct_repr = ", ".join([ + """EulerAngle in string representation""" + struct_repr = ", ".join( + [ "roll_deg: " + str(self.roll_deg), "pitch_deg: " + str(self.pitch_deg), "yaw_deg: " + str(self.yaw_deg), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"EulerAngle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEulerAngle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return EulerAngle( - - rpcEulerAngle.roll_deg, - - - rpcEulerAngle.pitch_deg, - - - rpcEulerAngle.yaw_deg, - - - rpcEulerAngle.timestamp_us - ) + rpcEulerAngle.roll_deg, + rpcEulerAngle.pitch_deg, + rpcEulerAngle.yaw_deg, + rpcEulerAngle.timestamp_us, + ) def translate_to_rpc(self, rpcEulerAngle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEulerAngle.roll_deg = self.roll_deg - - - - - + rpcEulerAngle.pitch_deg = self.pitch_deg - - - - - + rpcEulerAngle.yaw_deg = self.yaw_deg - - - - - + rpcEulerAngle.timestamp_us = self.timestamp_us - - - class AngularVelocityBody: """ - Angular velocity type. + Angular velocity type. - Parameters - ---------- - roll_rad_s : float - Roll angular velocity + Parameters + ---------- + roll_rad_s : float + Roll angular velocity - pitch_rad_s : float - Pitch angular velocity + pitch_rad_s : float + Pitch angular velocity - yaw_rad_s : float - Yaw angular velocity + yaw_rad_s : float + Yaw angular velocity - """ - - + """ - def __init__( - self, - roll_rad_s, - pitch_rad_s, - yaw_rad_s): - """ Initializes the AngularVelocityBody object """ + def __init__(self, roll_rad_s, pitch_rad_s, yaw_rad_s): + """Initializes the AngularVelocityBody object""" self.roll_rad_s = roll_rad_s self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s def __eq__(self, to_compare): - """ Checks if two AngularVelocityBody are the same """ + """Checks if two AngularVelocityBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngularVelocityBody object - return \ - (self.roll_rad_s == to_compare.roll_rad_s) and \ - (self.pitch_rad_s == to_compare.pitch_rad_s) and \ - (self.yaw_rad_s == to_compare.yaw_rad_s) + return ( + (self.roll_rad_s == to_compare.roll_rad_s) + and (self.pitch_rad_s == to_compare.pitch_rad_s) + and (self.yaw_rad_s == to_compare.yaw_rad_s) + ) except AttributeError: return False def __str__(self): - """ AngularVelocityBody in string representation """ - struct_repr = ", ".join([ + """AngularVelocityBody in string representation""" + struct_repr = ", ".join( + [ "roll_rad_s: " + str(self.roll_rad_s), "pitch_rad_s: " + str(self.pitch_rad_s), - "yaw_rad_s: " + str(self.yaw_rad_s) - ]) + "yaw_rad_s: " + str(self.yaw_rad_s), + ] + ) return f"AngularVelocityBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngularVelocityBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngularVelocityBody( - - rpcAngularVelocityBody.roll_rad_s, - - - rpcAngularVelocityBody.pitch_rad_s, - - - rpcAngularVelocityBody.yaw_rad_s - ) + rpcAngularVelocityBody.roll_rad_s, + rpcAngularVelocityBody.pitch_rad_s, + rpcAngularVelocityBody.yaw_rad_s, + ) def translate_to_rpc(self, rpcAngularVelocityBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngularVelocityBody.roll_rad_s = self.roll_rad_s - - - - - + rpcAngularVelocityBody.pitch_rad_s = self.pitch_rad_s - - - - - + rpcAngularVelocityBody.yaw_rad_s = self.yaw_rad_s - - - class GpsInfo: """ - GPS information type. - - Parameters - ---------- - num_satellites : int32_t - Number of visible satellites in use + GPS information type. - fix_type : FixType - Fix type + Parameters + ---------- + num_satellites : int32_t + Number of visible satellites in use - """ + fix_type : FixType + Fix type - + """ - def __init__( - self, - num_satellites, - fix_type): - """ Initializes the GpsInfo object """ + def __init__(self, num_satellites, fix_type): + """Initializes the GpsInfo object""" self.num_satellites = num_satellites self.fix_type = fix_type def __eq__(self, to_compare): - """ Checks if two GpsInfo are the same """ + """Checks if two GpsInfo are the same""" try: # Try to compare - this likely fails when it is compared to a non # GpsInfo object - return \ - (self.num_satellites == to_compare.num_satellites) and \ - (self.fix_type == to_compare.fix_type) + return (self.num_satellites == to_compare.num_satellites) and ( + self.fix_type == to_compare.fix_type + ) except AttributeError: return False def __str__(self): - """ GpsInfo in string representation """ - struct_repr = ", ".join([ + """GpsInfo in string representation""" + struct_repr = ", ".join( + [ "num_satellites: " + str(self.num_satellites), - "fix_type: " + str(self.fix_type) - ]) + "fix_type: " + str(self.fix_type), + ] + ) return f"GpsInfo: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGpsInfo): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GpsInfo( - - rpcGpsInfo.num_satellites, - - - FixType.translate_from_rpc(rpcGpsInfo.fix_type) - ) + rpcGpsInfo.num_satellites, FixType.translate_from_rpc(rpcGpsInfo.fix_type) + ) def translate_to_rpc(self, rpcGpsInfo): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGpsInfo.num_satellites = self.num_satellites - - - - - + rpcGpsInfo.fix_type = self.fix_type.translate_to_rpc() - - - class RawGps: """ - Raw GPS information type. - - Warning: this is an advanced type! If you want the location of the drone, use - the position instead. This message exposes the raw values of the GNSS sensor. + Raw GPS information type. - Parameters - ---------- - timestamp_us : uint64_t - Timestamp in microseconds (UNIX Epoch time or time since system boot, to be inferred) + Warning: this is an advanced type! If you want the location of the drone, use + the position instead. This message exposes the raw values of the GNSS sensor. - latitude_deg : double - Latitude in degrees (WGS84, EGM96 ellipsoid) + Parameters + ---------- + timestamp_us : uint64_t + Timestamp in microseconds (UNIX Epoch time or time since system boot, to be inferred) - longitude_deg : double - Longitude in degrees (WGS84, EGM96 ellipsoid) + latitude_deg : double + Latitude in degrees (WGS84, EGM96 ellipsoid) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + longitude_deg : double + Longitude in degrees (WGS84, EGM96 ellipsoid) - hdop : float - GPS HDOP horizontal dilution of position (unitless). If unknown, set to NaN + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - vdop : float - GPS VDOP vertical dilution of position (unitless). If unknown, set to NaN + hdop : float + GPS HDOP horizontal dilution of position (unitless). If unknown, set to NaN - velocity_m_s : float - Ground velocity in metres per second + vdop : float + GPS VDOP vertical dilution of position (unitless). If unknown, set to NaN - cog_deg : float - Course over ground (NOT heading, but direction of movement) in degrees. If unknown, set to NaN + velocity_m_s : float + Ground velocity in metres per second - altitude_ellipsoid_m : float - Altitude in metres (above WGS84, EGM96 ellipsoid) + cog_deg : float + Course over ground (NOT heading, but direction of movement) in degrees. If unknown, set to NaN - horizontal_uncertainty_m : float - Position uncertainty in metres + altitude_ellipsoid_m : float + Altitude in metres (above WGS84, EGM96 ellipsoid) - vertical_uncertainty_m : float - Altitude uncertainty in metres + horizontal_uncertainty_m : float + Position uncertainty in metres - velocity_uncertainty_m_s : float - Velocity uncertainty in metres per second + vertical_uncertainty_m : float + Altitude uncertainty in metres - heading_uncertainty_deg : float - Heading uncertainty in degrees + velocity_uncertainty_m_s : float + Velocity uncertainty in metres per second - yaw_deg : float - Yaw in earth frame from north. + heading_uncertainty_deg : float + Heading uncertainty in degrees - """ + yaw_deg : float + Yaw in earth frame from north. - + """ def __init__( - self, - timestamp_us, - latitude_deg, - longitude_deg, - absolute_altitude_m, - hdop, - vdop, - velocity_m_s, - cog_deg, - altitude_ellipsoid_m, - horizontal_uncertainty_m, - vertical_uncertainty_m, - velocity_uncertainty_m_s, - heading_uncertainty_deg, - yaw_deg): - """ Initializes the RawGps object """ + self, + timestamp_us, + latitude_deg, + longitude_deg, + absolute_altitude_m, + hdop, + vdop, + velocity_m_s, + cog_deg, + altitude_ellipsoid_m, + horizontal_uncertainty_m, + vertical_uncertainty_m, + velocity_uncertainty_m_s, + heading_uncertainty_deg, + yaw_deg, + ): + """Initializes the RawGps object""" self.timestamp_us = timestamp_us self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg @@ -1145,32 +991,38 @@ def __init__( self.yaw_deg = yaw_deg def __eq__(self, to_compare): - """ Checks if two RawGps are the same """ + """Checks if two RawGps are the same""" try: # Try to compare - this likely fails when it is compared to a non # RawGps object - return \ - (self.timestamp_us == to_compare.timestamp_us) and \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.hdop == to_compare.hdop) and \ - (self.vdop == to_compare.vdop) and \ - (self.velocity_m_s == to_compare.velocity_m_s) and \ - (self.cog_deg == to_compare.cog_deg) and \ - (self.altitude_ellipsoid_m == to_compare.altitude_ellipsoid_m) and \ - (self.horizontal_uncertainty_m == to_compare.horizontal_uncertainty_m) and \ - (self.vertical_uncertainty_m == to_compare.vertical_uncertainty_m) and \ - (self.velocity_uncertainty_m_s == to_compare.velocity_uncertainty_m_s) and \ - (self.heading_uncertainty_deg == to_compare.heading_uncertainty_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) + return ( + (self.timestamp_us == to_compare.timestamp_us) + and (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.hdop == to_compare.hdop) + and (self.vdop == to_compare.vdop) + and (self.velocity_m_s == to_compare.velocity_m_s) + and (self.cog_deg == to_compare.cog_deg) + and (self.altitude_ellipsoid_m == to_compare.altitude_ellipsoid_m) + and ( + self.horizontal_uncertainty_m == to_compare.horizontal_uncertainty_m + ) + and (self.vertical_uncertainty_m == to_compare.vertical_uncertainty_m) + and ( + self.velocity_uncertainty_m_s == to_compare.velocity_uncertainty_m_s + ) + and (self.heading_uncertainty_deg == to_compare.heading_uncertainty_deg) + and (self.yaw_deg == to_compare.yaw_deg) + ) except AttributeError: return False def __str__(self): - """ RawGps in string representation """ - struct_repr = ", ".join([ + """RawGps in string representation""" + struct_repr = ", ".join( + [ "timestamp_us: " + str(self.timestamp_us), "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), @@ -1184,193 +1036,108 @@ def __str__(self): "vertical_uncertainty_m: " + str(self.vertical_uncertainty_m), "velocity_uncertainty_m_s: " + str(self.velocity_uncertainty_m_s), "heading_uncertainty_deg: " + str(self.heading_uncertainty_deg), - "yaw_deg: " + str(self.yaw_deg) - ]) + "yaw_deg: " + str(self.yaw_deg), + ] + ) return f"RawGps: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcRawGps): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return RawGps( - - rpcRawGps.timestamp_us, - - - rpcRawGps.latitude_deg, - - - rpcRawGps.longitude_deg, - - - rpcRawGps.absolute_altitude_m, - - - rpcRawGps.hdop, - - - rpcRawGps.vdop, - - - rpcRawGps.velocity_m_s, - - - rpcRawGps.cog_deg, - - - rpcRawGps.altitude_ellipsoid_m, - - - rpcRawGps.horizontal_uncertainty_m, - - - rpcRawGps.vertical_uncertainty_m, - - - rpcRawGps.velocity_uncertainty_m_s, - - - rpcRawGps.heading_uncertainty_deg, - - - rpcRawGps.yaw_deg - ) + rpcRawGps.timestamp_us, + rpcRawGps.latitude_deg, + rpcRawGps.longitude_deg, + rpcRawGps.absolute_altitude_m, + rpcRawGps.hdop, + rpcRawGps.vdop, + rpcRawGps.velocity_m_s, + rpcRawGps.cog_deg, + rpcRawGps.altitude_ellipsoid_m, + rpcRawGps.horizontal_uncertainty_m, + rpcRawGps.vertical_uncertainty_m, + rpcRawGps.velocity_uncertainty_m_s, + rpcRawGps.heading_uncertainty_deg, + rpcRawGps.yaw_deg, + ) def translate_to_rpc(self, rpcRawGps): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcRawGps.timestamp_us = self.timestamp_us - - - - - + rpcRawGps.latitude_deg = self.latitude_deg - - - - - + rpcRawGps.longitude_deg = self.longitude_deg - - - - - + rpcRawGps.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcRawGps.hdop = self.hdop - - - - - + rpcRawGps.vdop = self.vdop - - - - - + rpcRawGps.velocity_m_s = self.velocity_m_s - - - - - + rpcRawGps.cog_deg = self.cog_deg - - - - - + rpcRawGps.altitude_ellipsoid_m = self.altitude_ellipsoid_m - - - - - + rpcRawGps.horizontal_uncertainty_m = self.horizontal_uncertainty_m - - - - - + rpcRawGps.vertical_uncertainty_m = self.vertical_uncertainty_m - - - - - + rpcRawGps.velocity_uncertainty_m_s = self.velocity_uncertainty_m_s - - - - - + rpcRawGps.heading_uncertainty_deg = self.heading_uncertainty_deg - - - - - + rpcRawGps.yaw_deg = self.yaw_deg - - - class Battery: """ - Battery type. - - Parameters - ---------- - id : uint32_t - Battery ID, for systems with multiple batteries + Battery type. - temperature_degc : float - Temperature of the battery in degrees Celsius. NAN for unknown temperature + Parameters + ---------- + id : uint32_t + Battery ID, for systems with multiple batteries - voltage_v : float - Voltage in volts + temperature_degc : float + Temperature of the battery in degrees Celsius. NAN for unknown temperature - current_battery_a : float - Battery current in Amps, NAN if autopilot does not measure the current + voltage_v : float + Voltage in volts - capacity_consumed_ah : float - Consumed charge in Amp hours, NAN if autopilot does not provide consumption estimate + current_battery_a : float + Battery current in Amps, NAN if autopilot does not measure the current - remaining_percent : float - Estimated battery remaining (range: 0 to 100) + capacity_consumed_ah : float + Consumed charge in Amp hours, NAN if autopilot does not provide consumption estimate - time_remaining_s : float - Estimated battery usage time remaining + remaining_percent : float + Estimated battery remaining (range: 0 to 100) - battery_function : BatteryFunction - Function of the battery + time_remaining_s : float + Estimated battery usage time remaining - """ + battery_function : BatteryFunction + Function of the battery - + """ def __init__( - self, - id, - temperature_degc, - voltage_v, - current_battery_a, - capacity_consumed_ah, - remaining_percent, - time_remaining_s, - battery_function): - """ Initializes the Battery object """ + self, + id, + temperature_degc, + voltage_v, + current_battery_a, + capacity_consumed_ah, + remaining_percent, + time_remaining_s, + battery_function, + ): + """Initializes the Battery object""" self.id = id self.temperature_degc = temperature_degc self.voltage_v = voltage_v @@ -1381,26 +1148,28 @@ def __init__( self.battery_function = battery_function def __eq__(self, to_compare): - """ Checks if two Battery are the same """ + """Checks if two Battery are the same""" try: # Try to compare - this likely fails when it is compared to a non # Battery object - return \ - (self.id == to_compare.id) and \ - (self.temperature_degc == to_compare.temperature_degc) and \ - (self.voltage_v == to_compare.voltage_v) and \ - (self.current_battery_a == to_compare.current_battery_a) and \ - (self.capacity_consumed_ah == to_compare.capacity_consumed_ah) and \ - (self.remaining_percent == to_compare.remaining_percent) and \ - (self.time_remaining_s == to_compare.time_remaining_s) and \ - (self.battery_function == to_compare.battery_function) + return ( + (self.id == to_compare.id) + and (self.temperature_degc == to_compare.temperature_degc) + and (self.voltage_v == to_compare.voltage_v) + and (self.current_battery_a == to_compare.current_battery_a) + and (self.capacity_consumed_ah == to_compare.capacity_consumed_ah) + and (self.remaining_percent == to_compare.remaining_percent) + and (self.time_remaining_s == to_compare.time_remaining_s) + and (self.battery_function == to_compare.battery_function) + ) except AttributeError: return False def __str__(self): - """ Battery in string representation """ - struct_repr = ", ".join([ + """Battery in string representation""" + struct_repr = ", ".join( + [ "id: " + str(self.id), "temperature_degc: " + str(self.temperature_degc), "voltage_v: " + str(self.voltage_v), @@ -1408,135 +1177,86 @@ def __str__(self): "capacity_consumed_ah: " + str(self.capacity_consumed_ah), "remaining_percent: " + str(self.remaining_percent), "time_remaining_s: " + str(self.time_remaining_s), - "battery_function: " + str(self.battery_function) - ]) + "battery_function: " + str(self.battery_function), + ] + ) return f"Battery: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcBattery): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Battery( - - rpcBattery.id, - - - rpcBattery.temperature_degc, - - - rpcBattery.voltage_v, - - - rpcBattery.current_battery_a, - - - rpcBattery.capacity_consumed_ah, - - - rpcBattery.remaining_percent, - - - rpcBattery.time_remaining_s, - - - BatteryFunction.translate_from_rpc(rpcBattery.battery_function) - ) + rpcBattery.id, + rpcBattery.temperature_degc, + rpcBattery.voltage_v, + rpcBattery.current_battery_a, + rpcBattery.capacity_consumed_ah, + rpcBattery.remaining_percent, + rpcBattery.time_remaining_s, + BatteryFunction.translate_from_rpc(rpcBattery.battery_function), + ) def translate_to_rpc(self, rpcBattery): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcBattery.id = self.id - - - - - + rpcBattery.temperature_degc = self.temperature_degc - - - - - + rpcBattery.voltage_v = self.voltage_v - - - - - + rpcBattery.current_battery_a = self.current_battery_a - - - - - + rpcBattery.capacity_consumed_ah = self.capacity_consumed_ah - - - - - + rpcBattery.remaining_percent = self.remaining_percent - - - - - + rpcBattery.time_remaining_s = self.time_remaining_s - - - - - + rpcBattery.battery_function = self.battery_function.translate_to_rpc() - - - class Health: """ - Health type. - - Parameters - ---------- - is_gyrometer_calibration_ok : bool - True if the gyrometer is calibrated + Health type. - is_accelerometer_calibration_ok : bool - True if the accelerometer is calibrated + Parameters + ---------- + is_gyrometer_calibration_ok : bool + True if the gyrometer is calibrated - is_magnetometer_calibration_ok : bool - True if the magnetometer is calibrated + is_accelerometer_calibration_ok : bool + True if the accelerometer is calibrated - is_local_position_ok : bool - True if the local position estimate is good enough to fly in 'position control' mode + is_magnetometer_calibration_ok : bool + True if the magnetometer is calibrated - is_global_position_ok : bool - True if the global position estimate is good enough to fly in 'position control' mode + is_local_position_ok : bool + True if the local position estimate is good enough to fly in 'position control' mode - is_home_position_ok : bool - True if the home position has been initialized properly + is_global_position_ok : bool + True if the global position estimate is good enough to fly in 'position control' mode - is_armable : bool - True if system can be armed + is_home_position_ok : bool + True if the home position has been initialized properly - """ + is_armable : bool + True if system can be armed - + """ def __init__( - self, - is_gyrometer_calibration_ok, - is_accelerometer_calibration_ok, - is_magnetometer_calibration_ok, - is_local_position_ok, - is_global_position_ok, - is_home_position_ok, - is_armable): - """ Initializes the Health object """ + self, + is_gyrometer_calibration_ok, + is_accelerometer_calibration_ok, + is_magnetometer_calibration_ok, + is_local_position_ok, + is_global_position_ok, + is_home_position_ok, + is_armable, + ): + """Initializes the Health object""" self.is_gyrometer_calibration_ok = is_gyrometer_calibration_ok self.is_accelerometer_calibration_ok = is_accelerometer_calibration_ok self.is_magnetometer_calibration_ok = is_magnetometer_calibration_ok @@ -1546,725 +1266,539 @@ def __init__( self.is_armable = is_armable def __eq__(self, to_compare): - """ Checks if two Health are the same """ + """Checks if two Health are the same""" try: # Try to compare - this likely fails when it is compared to a non # Health object - return \ - (self.is_gyrometer_calibration_ok == to_compare.is_gyrometer_calibration_ok) and \ - (self.is_accelerometer_calibration_ok == to_compare.is_accelerometer_calibration_ok) and \ - (self.is_magnetometer_calibration_ok == to_compare.is_magnetometer_calibration_ok) and \ - (self.is_local_position_ok == to_compare.is_local_position_ok) and \ - (self.is_global_position_ok == to_compare.is_global_position_ok) and \ - (self.is_home_position_ok == to_compare.is_home_position_ok) and \ - (self.is_armable == to_compare.is_armable) + return ( + ( + self.is_gyrometer_calibration_ok + == to_compare.is_gyrometer_calibration_ok + ) + and ( + self.is_accelerometer_calibration_ok + == to_compare.is_accelerometer_calibration_ok + ) + and ( + self.is_magnetometer_calibration_ok + == to_compare.is_magnetometer_calibration_ok + ) + and (self.is_local_position_ok == to_compare.is_local_position_ok) + and (self.is_global_position_ok == to_compare.is_global_position_ok) + and (self.is_home_position_ok == to_compare.is_home_position_ok) + and (self.is_armable == to_compare.is_armable) + ) except AttributeError: return False def __str__(self): - """ Health in string representation """ - struct_repr = ", ".join([ + """Health in string representation""" + struct_repr = ", ".join( + [ "is_gyrometer_calibration_ok: " + str(self.is_gyrometer_calibration_ok), - "is_accelerometer_calibration_ok: " + str(self.is_accelerometer_calibration_ok), - "is_magnetometer_calibration_ok: " + str(self.is_magnetometer_calibration_ok), + "is_accelerometer_calibration_ok: " + + str(self.is_accelerometer_calibration_ok), + "is_magnetometer_calibration_ok: " + + str(self.is_magnetometer_calibration_ok), "is_local_position_ok: " + str(self.is_local_position_ok), "is_global_position_ok: " + str(self.is_global_position_ok), "is_home_position_ok: " + str(self.is_home_position_ok), - "is_armable: " + str(self.is_armable) - ]) + "is_armable: " + str(self.is_armable), + ] + ) return f"Health: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHealth): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Health( - - rpcHealth.is_gyrometer_calibration_ok, - - - rpcHealth.is_accelerometer_calibration_ok, - - - rpcHealth.is_magnetometer_calibration_ok, - - - rpcHealth.is_local_position_ok, - - - rpcHealth.is_global_position_ok, - - - rpcHealth.is_home_position_ok, - - - rpcHealth.is_armable - ) + rpcHealth.is_gyrometer_calibration_ok, + rpcHealth.is_accelerometer_calibration_ok, + rpcHealth.is_magnetometer_calibration_ok, + rpcHealth.is_local_position_ok, + rpcHealth.is_global_position_ok, + rpcHealth.is_home_position_ok, + rpcHealth.is_armable, + ) def translate_to_rpc(self, rpcHealth): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcHealth.is_gyrometer_calibration_ok = self.is_gyrometer_calibration_ok - - - - - + rpcHealth.is_accelerometer_calibration_ok = self.is_accelerometer_calibration_ok - - - - - + rpcHealth.is_magnetometer_calibration_ok = self.is_magnetometer_calibration_ok - - - - - + rpcHealth.is_local_position_ok = self.is_local_position_ok - - - - - + rpcHealth.is_global_position_ok = self.is_global_position_ok - - - - - + rpcHealth.is_home_position_ok = self.is_home_position_ok - - - - - + rpcHealth.is_armable = self.is_armable - - - class RcStatus: """ - Remote control status type. + Remote control status type. - Parameters - ---------- - was_available_once : bool - True if an RC signal has been available once + Parameters + ---------- + was_available_once : bool + True if an RC signal has been available once - is_available : bool - True if the RC signal is available now + is_available : bool + True if the RC signal is available now - signal_strength_percent : float - Signal strength (range: 0 to 100, NaN if unknown) + signal_strength_percent : float + Signal strength (range: 0 to 100, NaN if unknown) - """ - - + """ - def __init__( - self, - was_available_once, - is_available, - signal_strength_percent): - """ Initializes the RcStatus object """ + def __init__(self, was_available_once, is_available, signal_strength_percent): + """Initializes the RcStatus object""" self.was_available_once = was_available_once self.is_available = is_available self.signal_strength_percent = signal_strength_percent def __eq__(self, to_compare): - """ Checks if two RcStatus are the same """ + """Checks if two RcStatus are the same""" try: # Try to compare - this likely fails when it is compared to a non # RcStatus object - return \ - (self.was_available_once == to_compare.was_available_once) and \ - (self.is_available == to_compare.is_available) and \ - (self.signal_strength_percent == to_compare.signal_strength_percent) + return ( + (self.was_available_once == to_compare.was_available_once) + and (self.is_available == to_compare.is_available) + and (self.signal_strength_percent == to_compare.signal_strength_percent) + ) except AttributeError: return False def __str__(self): - """ RcStatus in string representation """ - struct_repr = ", ".join([ + """RcStatus in string representation""" + struct_repr = ", ".join( + [ "was_available_once: " + str(self.was_available_once), "is_available: " + str(self.is_available), - "signal_strength_percent: " + str(self.signal_strength_percent) - ]) + "signal_strength_percent: " + str(self.signal_strength_percent), + ] + ) return f"RcStatus: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcRcStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return RcStatus( - - rpcRcStatus.was_available_once, - - - rpcRcStatus.is_available, - - - rpcRcStatus.signal_strength_percent - ) + rpcRcStatus.was_available_once, + rpcRcStatus.is_available, + rpcRcStatus.signal_strength_percent, + ) def translate_to_rpc(self, rpcRcStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcRcStatus.was_available_once = self.was_available_once - - - - - + rpcRcStatus.is_available = self.is_available - - - - - + rpcRcStatus.signal_strength_percent = self.signal_strength_percent - - - class StatusText: """ - StatusText information type. - - Parameters - ---------- - type : StatusTextType - Message type + StatusText information type. - text : std::string - MAVLink status message + Parameters + ---------- + type : StatusTextType + Message type - """ + text : std::string + MAVLink status message - + """ - def __init__( - self, - type, - text): - """ Initializes the StatusText object """ + def __init__(self, type, text): + """Initializes the StatusText object""" self.type = type self.text = text def __eq__(self, to_compare): - """ Checks if two StatusText are the same """ + """Checks if two StatusText are the same""" try: # Try to compare - this likely fails when it is compared to a non # StatusText object - return \ - (self.type == to_compare.type) and \ - (self.text == to_compare.text) + return (self.type == to_compare.type) and (self.text == to_compare.text) except AttributeError: return False def __str__(self): - """ StatusText in string representation """ - struct_repr = ", ".join([ - "type: " + str(self.type), - "text: " + str(self.text) - ]) + """StatusText in string representation""" + struct_repr = ", ".join(["type: " + str(self.type), "text: " + str(self.text)]) return f"StatusText: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStatusText): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return StatusText( - - StatusTextType.translate_from_rpc(rpcStatusText.type), - - - rpcStatusText.text - ) + StatusTextType.translate_from_rpc(rpcStatusText.type), rpcStatusText.text + ) def translate_to_rpc(self, rpcStatusText): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStatusText.type = self.type.translate_to_rpc() - - - - - + rpcStatusText.text = self.text - - - class ActuatorControlTarget: """ - Actuator control target type. - - Parameters - ---------- - group : int32_t - An actuator control group is e.g. 'attitude' for the core flight controls, or 'gimbal' for a payload. + Actuator control target type. - controls : [float] - Controls normed from -1 to 1, where 0 is neutral position. + Parameters + ---------- + group : int32_t + An actuator control group is e.g. 'attitude' for the core flight controls, or 'gimbal' for a payload. - """ + controls : [float] + Controls normed from -1 to 1, where 0 is neutral position. - + """ - def __init__( - self, - group, - controls): - """ Initializes the ActuatorControlTarget object """ + def __init__(self, group, controls): + """Initializes the ActuatorControlTarget object""" self.group = group self.controls = controls def __eq__(self, to_compare): - """ Checks if two ActuatorControlTarget are the same """ + """Checks if two ActuatorControlTarget are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActuatorControlTarget object - return \ - (self.group == to_compare.group) and \ - (self.controls == to_compare.controls) + return (self.group == to_compare.group) and ( + self.controls == to_compare.controls + ) except AttributeError: return False def __str__(self): - """ ActuatorControlTarget in string representation """ - struct_repr = ", ".join([ - "group: " + str(self.group), - "controls: " + str(self.controls) - ]) + """ActuatorControlTarget in string representation""" + struct_repr = ", ".join( + ["group: " + str(self.group), "controls: " + str(self.controls)] + ) return f"ActuatorControlTarget: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActuatorControlTarget): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActuatorControlTarget( - - rpcActuatorControlTarget.group, - - - rpcActuatorControlTarget.controls - ) + rpcActuatorControlTarget.group, rpcActuatorControlTarget.controls + ) def translate_to_rpc(self, rpcActuatorControlTarget): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcActuatorControlTarget.group = self.group - - - - - + for elem in self.controls: - rpcActuatorControlTarget.controls.append(elem) - - - + rpcActuatorControlTarget.controls.append(elem) class ActuatorOutputStatus: """ - Actuator output status type. - - Parameters - ---------- - active : uint32_t - Active outputs + Actuator output status type. - actuator : [float] - Servo/motor output values + Parameters + ---------- + active : uint32_t + Active outputs - """ + actuator : [float] + Servo/motor output values - + """ - def __init__( - self, - active, - actuator): - """ Initializes the ActuatorOutputStatus object """ + def __init__(self, active, actuator): + """Initializes the ActuatorOutputStatus object""" self.active = active self.actuator = actuator def __eq__(self, to_compare): - """ Checks if two ActuatorOutputStatus are the same """ + """Checks if two ActuatorOutputStatus are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActuatorOutputStatus object - return \ - (self.active == to_compare.active) and \ - (self.actuator == to_compare.actuator) + return (self.active == to_compare.active) and ( + self.actuator == to_compare.actuator + ) except AttributeError: return False def __str__(self): - """ ActuatorOutputStatus in string representation """ - struct_repr = ", ".join([ - "active: " + str(self.active), - "actuator: " + str(self.actuator) - ]) + """ActuatorOutputStatus in string representation""" + struct_repr = ", ".join( + ["active: " + str(self.active), "actuator: " + str(self.actuator)] + ) return f"ActuatorOutputStatus: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActuatorOutputStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActuatorOutputStatus( - - rpcActuatorOutputStatus.active, - - - rpcActuatorOutputStatus.actuator - ) + rpcActuatorOutputStatus.active, rpcActuatorOutputStatus.actuator + ) def translate_to_rpc(self, rpcActuatorOutputStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcActuatorOutputStatus.active = self.active - - - - - + for elem in self.actuator: - rpcActuatorOutputStatus.actuator.append(elem) - - - + rpcActuatorOutputStatus.actuator.append(elem) class Covariance: """ - Covariance type. - - Row-major representation of a 6x6 cross-covariance matrix - upper right triangle. - Set first to NaN if unknown. + Covariance type. - Parameters - ---------- - covariance_matrix : [float] - Representation of a covariance matrix. + Row-major representation of a 6x6 cross-covariance matrix + upper right triangle. + Set first to NaN if unknown. - """ + Parameters + ---------- + covariance_matrix : [float] + Representation of a covariance matrix. - + """ - def __init__( - self, - covariance_matrix): - """ Initializes the Covariance object """ + def __init__(self, covariance_matrix): + """Initializes the Covariance object""" self.covariance_matrix = covariance_matrix def __eq__(self, to_compare): - """ Checks if two Covariance are the same """ + """Checks if two Covariance are the same""" try: # Try to compare - this likely fails when it is compared to a non # Covariance object - return \ - (self.covariance_matrix == to_compare.covariance_matrix) + return self.covariance_matrix == to_compare.covariance_matrix except AttributeError: return False def __str__(self): - """ Covariance in string representation """ - struct_repr = ", ".join([ - "covariance_matrix: " + str(self.covariance_matrix) - ]) + """Covariance in string representation""" + struct_repr = ", ".join(["covariance_matrix: " + str(self.covariance_matrix)]) return f"Covariance: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCovariance): - """ Translates a gRPC struct to the SDK equivalent """ - return Covariance( - - rpcCovariance.covariance_matrix - ) + """Translates a gRPC struct to the SDK equivalent""" + return Covariance(rpcCovariance.covariance_matrix) def translate_to_rpc(self, rpcCovariance): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - for elem in self.covariance_matrix: - rpcCovariance.covariance_matrix.append(elem) - - - + rpcCovariance.covariance_matrix.append(elem) class VelocityBody: """ - Velocity type, represented in the Body (X Y Z) frame and in metres/second. + Velocity type, represented in the Body (X Y Z) frame and in metres/second. - Parameters - ---------- - x_m_s : float - Velocity in X in metres/second + Parameters + ---------- + x_m_s : float + Velocity in X in metres/second - y_m_s : float - Velocity in Y in metres/second + y_m_s : float + Velocity in Y in metres/second - z_m_s : float - Velocity in Z in metres/second + z_m_s : float + Velocity in Z in metres/second - """ - - + """ - def __init__( - self, - x_m_s, - y_m_s, - z_m_s): - """ Initializes the VelocityBody object """ + def __init__(self, x_m_s, y_m_s, z_m_s): + """Initializes the VelocityBody object""" self.x_m_s = x_m_s self.y_m_s = y_m_s self.z_m_s = z_m_s def __eq__(self, to_compare): - """ Checks if two VelocityBody are the same """ + """Checks if two VelocityBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # VelocityBody object - return \ - (self.x_m_s == to_compare.x_m_s) and \ - (self.y_m_s == to_compare.y_m_s) and \ - (self.z_m_s == to_compare.z_m_s) + return ( + (self.x_m_s == to_compare.x_m_s) + and (self.y_m_s == to_compare.y_m_s) + and (self.z_m_s == to_compare.z_m_s) + ) except AttributeError: return False def __str__(self): - """ VelocityBody in string representation """ - struct_repr = ", ".join([ + """VelocityBody in string representation""" + struct_repr = ", ".join( + [ "x_m_s: " + str(self.x_m_s), "y_m_s: " + str(self.y_m_s), - "z_m_s: " + str(self.z_m_s) - ]) + "z_m_s: " + str(self.z_m_s), + ] + ) return f"VelocityBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVelocityBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VelocityBody( - - rpcVelocityBody.x_m_s, - - - rpcVelocityBody.y_m_s, - - - rpcVelocityBody.z_m_s - ) + rpcVelocityBody.x_m_s, rpcVelocityBody.y_m_s, rpcVelocityBody.z_m_s + ) def translate_to_rpc(self, rpcVelocityBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVelocityBody.x_m_s = self.x_m_s - - - - - + rpcVelocityBody.y_m_s = self.y_m_s - - - - - + rpcVelocityBody.z_m_s = self.z_m_s - - - class PositionBody: """ - Position type, represented in the Body (X Y Z) frame - - Parameters - ---------- - x_m : float - X Position in metres. + Position type, represented in the Body (X Y Z) frame - y_m : float - Y Position in metres. + Parameters + ---------- + x_m : float + X Position in metres. - z_m : float - Z Position in metres. + y_m : float + Y Position in metres. - """ + z_m : float + Z Position in metres. - + """ - def __init__( - self, - x_m, - y_m, - z_m): - """ Initializes the PositionBody object """ + def __init__(self, x_m, y_m, z_m): + """Initializes the PositionBody object""" self.x_m = x_m self.y_m = y_m self.z_m = z_m def __eq__(self, to_compare): - """ Checks if two PositionBody are the same """ + """Checks if two PositionBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionBody object - return \ - (self.x_m == to_compare.x_m) and \ - (self.y_m == to_compare.y_m) and \ - (self.z_m == to_compare.z_m) + return ( + (self.x_m == to_compare.x_m) + and (self.y_m == to_compare.y_m) + and (self.z_m == to_compare.z_m) + ) except AttributeError: return False def __str__(self): - """ PositionBody in string representation """ - struct_repr = ", ".join([ - "x_m: " + str(self.x_m), - "y_m: " + str(self.y_m), - "z_m: " + str(self.z_m) - ]) + """PositionBody in string representation""" + struct_repr = ", ".join( + ["x_m: " + str(self.x_m), "y_m: " + str(self.y_m), "z_m: " + str(self.z_m)] + ) return f"PositionBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionBody( - - rpcPositionBody.x_m, - - - rpcPositionBody.y_m, - - - rpcPositionBody.z_m - ) + rpcPositionBody.x_m, rpcPositionBody.y_m, rpcPositionBody.z_m + ) def translate_to_rpc(self, rpcPositionBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionBody.x_m = self.x_m - - - - - + rpcPositionBody.y_m = self.y_m - - - - - + rpcPositionBody.z_m = self.z_m - - - class Odometry: """ - Odometry message type. + Odometry message type. - Parameters - ---------- - time_usec : uint64_t - Timestamp (0 to use Backend timestamp). + Parameters + ---------- + time_usec : uint64_t + Timestamp (0 to use Backend timestamp). - frame_id : MavFrame - Coordinate frame of reference for the pose data. + frame_id : MavFrame + Coordinate frame of reference for the pose data. - child_frame_id : MavFrame - Coordinate frame of reference for the velocity in free space (twist) data. + child_frame_id : MavFrame + Coordinate frame of reference for the velocity in free space (twist) data. - position_body : PositionBody - Position. + position_body : PositionBody + Position. - q : Quaternion - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). + q : Quaternion + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). - velocity_body : VelocityBody - Linear velocity (m/s). + velocity_body : VelocityBody + Linear velocity (m/s). - angular_velocity_body : AngularVelocityBody - Angular velocity (rad/s). + angular_velocity_body : AngularVelocityBody + Angular velocity (rad/s). - pose_covariance : Covariance - Pose cross-covariance matrix. + pose_covariance : Covariance + Pose cross-covariance matrix. - velocity_covariance : Covariance - Velocity cross-covariance matrix. + velocity_covariance : Covariance + Velocity cross-covariance matrix. - """ + """ - - class MavFrame(Enum): """ - Mavlink frame id + Mavlink frame id - Values - ------ - UNDEF - Frame is undefined. + Values + ------ + UNDEF + Frame is undefined. - BODY_NED - Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + BODY_NED + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. - VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down). + VISION_NED + Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down). - ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down). + ESTIM_NED + Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down). - """ + """ - UNDEF = 0 BODY_NED = 1 VISION_NED = 2 @@ -2282,7 +1816,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.Odometry.MAV_FRAME_UNDEF: return Odometry.MavFrame.UNDEF if rpc_enum_value == telemetry_pb2.Odometry.MAV_FRAME_BODY_NED: @@ -2294,20 +1828,20 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - def __init__( - self, - time_usec, - frame_id, - child_frame_id, - position_body, - q, - velocity_body, - angular_velocity_body, - pose_covariance, - velocity_covariance): - """ Initializes the Odometry object """ + self, + time_usec, + frame_id, + child_frame_id, + position_body, + q, + velocity_body, + angular_velocity_body, + pose_covariance, + velocity_covariance, + ): + """Initializes the Odometry object""" self.time_usec = time_usec self.frame_id = frame_id self.child_frame_id = child_frame_id @@ -2319,27 +1853,29 @@ def __init__( self.velocity_covariance = velocity_covariance def __eq__(self, to_compare): - """ Checks if two Odometry are the same """ + """Checks if two Odometry are the same""" try: # Try to compare - this likely fails when it is compared to a non # Odometry object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.frame_id == to_compare.frame_id) and \ - (self.child_frame_id == to_compare.child_frame_id) and \ - (self.position_body == to_compare.position_body) and \ - (self.q == to_compare.q) and \ - (self.velocity_body == to_compare.velocity_body) and \ - (self.angular_velocity_body == to_compare.angular_velocity_body) and \ - (self.pose_covariance == to_compare.pose_covariance) and \ - (self.velocity_covariance == to_compare.velocity_covariance) + return ( + (self.time_usec == to_compare.time_usec) + and (self.frame_id == to_compare.frame_id) + and (self.child_frame_id == to_compare.child_frame_id) + and (self.position_body == to_compare.position_body) + and (self.q == to_compare.q) + and (self.velocity_body == to_compare.velocity_body) + and (self.angular_velocity_body == to_compare.angular_velocity_body) + and (self.pose_covariance == to_compare.pose_covariance) + and (self.velocity_covariance == to_compare.velocity_covariance) + ) except AttributeError: return False def __str__(self): - """ Odometry in string representation """ - struct_repr = ", ".join([ + """Odometry in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "frame_id: " + str(self.frame_id), "child_frame_id: " + str(self.child_frame_id), @@ -2348,712 +1884,523 @@ def __str__(self): "velocity_body: " + str(self.velocity_body), "angular_velocity_body: " + str(self.angular_velocity_body), "pose_covariance: " + str(self.pose_covariance), - "velocity_covariance: " + str(self.velocity_covariance) - ]) + "velocity_covariance: " + str(self.velocity_covariance), + ] + ) return f"Odometry: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcOdometry): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Odometry( - - rpcOdometry.time_usec, - - - Odometry.MavFrame.translate_from_rpc(rpcOdometry.frame_id), - - - Odometry.MavFrame.translate_from_rpc(rpcOdometry.child_frame_id), - - - PositionBody.translate_from_rpc(rpcOdometry.position_body), - - - Quaternion.translate_from_rpc(rpcOdometry.q), - - - VelocityBody.translate_from_rpc(rpcOdometry.velocity_body), - - - AngularVelocityBody.translate_from_rpc(rpcOdometry.angular_velocity_body), - - - Covariance.translate_from_rpc(rpcOdometry.pose_covariance), - - - Covariance.translate_from_rpc(rpcOdometry.velocity_covariance) - ) + rpcOdometry.time_usec, + Odometry.MavFrame.translate_from_rpc(rpcOdometry.frame_id), + Odometry.MavFrame.translate_from_rpc(rpcOdometry.child_frame_id), + PositionBody.translate_from_rpc(rpcOdometry.position_body), + Quaternion.translate_from_rpc(rpcOdometry.q), + VelocityBody.translate_from_rpc(rpcOdometry.velocity_body), + AngularVelocityBody.translate_from_rpc(rpcOdometry.angular_velocity_body), + Covariance.translate_from_rpc(rpcOdometry.pose_covariance), + Covariance.translate_from_rpc(rpcOdometry.velocity_covariance), + ) def translate_to_rpc(self, rpcOdometry): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcOdometry.time_usec = self.time_usec - - - - - + rpcOdometry.frame_id = self.frame_id.translate_to_rpc() - - - - - + rpcOdometry.child_frame_id = self.child_frame_id.translate_to_rpc() - - - - - + self.position_body.translate_to_rpc(rpcOdometry.position_body) - - - - - + self.q.translate_to_rpc(rpcOdometry.q) - - - - - + self.velocity_body.translate_to_rpc(rpcOdometry.velocity_body) - - - - - + self.angular_velocity_body.translate_to_rpc(rpcOdometry.angular_velocity_body) - - - - - + self.pose_covariance.translate_to_rpc(rpcOdometry.pose_covariance) - - - - - + self.velocity_covariance.translate_to_rpc(rpcOdometry.velocity_covariance) - - - class DistanceSensor: """ - DistanceSensor message type. - - Parameters - ---------- - minimum_distance_m : float - Minimum distance the sensor can measure, NaN if unknown. + DistanceSensor message type. - maximum_distance_m : float - Maximum distance the sensor can measure, NaN if unknown. + Parameters + ---------- + minimum_distance_m : float + Minimum distance the sensor can measure, NaN if unknown. - current_distance_m : float - Current distance reading, NaN if unknown. + maximum_distance_m : float + Maximum distance the sensor can measure, NaN if unknown. - orientation : EulerAngle - Sensor Orientation reading. + current_distance_m : float + Current distance reading, NaN if unknown. - """ + orientation : EulerAngle + Sensor Orientation reading. - + """ def __init__( - self, - minimum_distance_m, - maximum_distance_m, - current_distance_m, - orientation): - """ Initializes the DistanceSensor object """ + self, minimum_distance_m, maximum_distance_m, current_distance_m, orientation + ): + """Initializes the DistanceSensor object""" self.minimum_distance_m = minimum_distance_m self.maximum_distance_m = maximum_distance_m self.current_distance_m = current_distance_m self.orientation = orientation def __eq__(self, to_compare): - """ Checks if two DistanceSensor are the same """ + """Checks if two DistanceSensor are the same""" try: # Try to compare - this likely fails when it is compared to a non # DistanceSensor object - return \ - (self.minimum_distance_m == to_compare.minimum_distance_m) and \ - (self.maximum_distance_m == to_compare.maximum_distance_m) and \ - (self.current_distance_m == to_compare.current_distance_m) and \ - (self.orientation == to_compare.orientation) + return ( + (self.minimum_distance_m == to_compare.minimum_distance_m) + and (self.maximum_distance_m == to_compare.maximum_distance_m) + and (self.current_distance_m == to_compare.current_distance_m) + and (self.orientation == to_compare.orientation) + ) except AttributeError: return False def __str__(self): - """ DistanceSensor in string representation """ - struct_repr = ", ".join([ + """DistanceSensor in string representation""" + struct_repr = ", ".join( + [ "minimum_distance_m: " + str(self.minimum_distance_m), "maximum_distance_m: " + str(self.maximum_distance_m), "current_distance_m: " + str(self.current_distance_m), - "orientation: " + str(self.orientation) - ]) + "orientation: " + str(self.orientation), + ] + ) return f"DistanceSensor: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcDistanceSensor): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return DistanceSensor( - - rpcDistanceSensor.minimum_distance_m, - - - rpcDistanceSensor.maximum_distance_m, - - - rpcDistanceSensor.current_distance_m, - - - EulerAngle.translate_from_rpc(rpcDistanceSensor.orientation) - ) + rpcDistanceSensor.minimum_distance_m, + rpcDistanceSensor.maximum_distance_m, + rpcDistanceSensor.current_distance_m, + EulerAngle.translate_from_rpc(rpcDistanceSensor.orientation), + ) def translate_to_rpc(self, rpcDistanceSensor): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcDistanceSensor.minimum_distance_m = self.minimum_distance_m - - - - - + rpcDistanceSensor.maximum_distance_m = self.maximum_distance_m - - - - - + rpcDistanceSensor.current_distance_m = self.current_distance_m - - - - - + self.orientation.translate_to_rpc(rpcDistanceSensor.orientation) - - - class ScaledPressure: """ - Scaled Pressure message type. - - Parameters - ---------- - timestamp_us : uint64_t - Timestamp (time since system boot) + Scaled Pressure message type. - absolute_pressure_hpa : float - Absolute pressure in hPa + Parameters + ---------- + timestamp_us : uint64_t + Timestamp (time since system boot) - differential_pressure_hpa : float - Differential pressure 1 in hPa + absolute_pressure_hpa : float + Absolute pressure in hPa - temperature_deg : float - Absolute pressure temperature (in celsius) + differential_pressure_hpa : float + Differential pressure 1 in hPa - differential_pressure_temperature_deg : float - Differential pressure temperature (in celsius, 0 if not available) + temperature_deg : float + Absolute pressure temperature (in celsius) - """ + differential_pressure_temperature_deg : float + Differential pressure temperature (in celsius, 0 if not available) - + """ def __init__( - self, - timestamp_us, - absolute_pressure_hpa, - differential_pressure_hpa, - temperature_deg, - differential_pressure_temperature_deg): - """ Initializes the ScaledPressure object """ + self, + timestamp_us, + absolute_pressure_hpa, + differential_pressure_hpa, + temperature_deg, + differential_pressure_temperature_deg, + ): + """Initializes the ScaledPressure object""" self.timestamp_us = timestamp_us self.absolute_pressure_hpa = absolute_pressure_hpa self.differential_pressure_hpa = differential_pressure_hpa self.temperature_deg = temperature_deg - self.differential_pressure_temperature_deg = differential_pressure_temperature_deg + self.differential_pressure_temperature_deg = ( + differential_pressure_temperature_deg + ) def __eq__(self, to_compare): - """ Checks if two ScaledPressure are the same """ + """Checks if two ScaledPressure are the same""" try: # Try to compare - this likely fails when it is compared to a non # ScaledPressure object - return \ - (self.timestamp_us == to_compare.timestamp_us) and \ - (self.absolute_pressure_hpa == to_compare.absolute_pressure_hpa) and \ - (self.differential_pressure_hpa == to_compare.differential_pressure_hpa) and \ - (self.temperature_deg == to_compare.temperature_deg) and \ - (self.differential_pressure_temperature_deg == to_compare.differential_pressure_temperature_deg) + return ( + (self.timestamp_us == to_compare.timestamp_us) + and (self.absolute_pressure_hpa == to_compare.absolute_pressure_hpa) + and ( + self.differential_pressure_hpa + == to_compare.differential_pressure_hpa + ) + and (self.temperature_deg == to_compare.temperature_deg) + and ( + self.differential_pressure_temperature_deg + == to_compare.differential_pressure_temperature_deg + ) + ) except AttributeError: return False def __str__(self): - """ ScaledPressure in string representation """ - struct_repr = ", ".join([ + """ScaledPressure in string representation""" + struct_repr = ", ".join( + [ "timestamp_us: " + str(self.timestamp_us), "absolute_pressure_hpa: " + str(self.absolute_pressure_hpa), "differential_pressure_hpa: " + str(self.differential_pressure_hpa), "temperature_deg: " + str(self.temperature_deg), - "differential_pressure_temperature_deg: " + str(self.differential_pressure_temperature_deg) - ]) + "differential_pressure_temperature_deg: " + + str(self.differential_pressure_temperature_deg), + ] + ) return f"ScaledPressure: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcScaledPressure): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ScaledPressure( - - rpcScaledPressure.timestamp_us, - - - rpcScaledPressure.absolute_pressure_hpa, - - - rpcScaledPressure.differential_pressure_hpa, - - - rpcScaledPressure.temperature_deg, - - - rpcScaledPressure.differential_pressure_temperature_deg - ) + rpcScaledPressure.timestamp_us, + rpcScaledPressure.absolute_pressure_hpa, + rpcScaledPressure.differential_pressure_hpa, + rpcScaledPressure.temperature_deg, + rpcScaledPressure.differential_pressure_temperature_deg, + ) def translate_to_rpc(self, rpcScaledPressure): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcScaledPressure.timestamp_us = self.timestamp_us - - - - - + rpcScaledPressure.absolute_pressure_hpa = self.absolute_pressure_hpa - - - - - + rpcScaledPressure.differential_pressure_hpa = self.differential_pressure_hpa - - - - - + rpcScaledPressure.temperature_deg = self.temperature_deg - - - - - - rpcScaledPressure.differential_pressure_temperature_deg = self.differential_pressure_temperature_deg - - - + + rpcScaledPressure.differential_pressure_temperature_deg = ( + self.differential_pressure_temperature_deg + ) class PositionNed: """ - PositionNed message type. - - Parameters - ---------- - north_m : float - Position along north direction in metres + PositionNed message type. - east_m : float - Position along east direction in metres + Parameters + ---------- + north_m : float + Position along north direction in metres - down_m : float - Position along down direction in metres + east_m : float + Position along east direction in metres - """ + down_m : float + Position along down direction in metres - + """ - def __init__( - self, - north_m, - east_m, - down_m): - """ Initializes the PositionNed object """ + def __init__(self, north_m, east_m, down_m): + """Initializes the PositionNed object""" self.north_m = north_m self.east_m = east_m self.down_m = down_m def __eq__(self, to_compare): - """ Checks if two PositionNed are the same """ + """Checks if two PositionNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionNed object - return \ - (self.north_m == to_compare.north_m) and \ - (self.east_m == to_compare.east_m) and \ - (self.down_m == to_compare.down_m) + return ( + (self.north_m == to_compare.north_m) + and (self.east_m == to_compare.east_m) + and (self.down_m == to_compare.down_m) + ) except AttributeError: return False def __str__(self): - """ PositionNed in string representation """ - struct_repr = ", ".join([ + """PositionNed in string representation""" + struct_repr = ", ".join( + [ "north_m: " + str(self.north_m), "east_m: " + str(self.east_m), - "down_m: " + str(self.down_m) - ]) + "down_m: " + str(self.down_m), + ] + ) return f"PositionNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionNed( - - rpcPositionNed.north_m, - - - rpcPositionNed.east_m, - - - rpcPositionNed.down_m - ) + rpcPositionNed.north_m, rpcPositionNed.east_m, rpcPositionNed.down_m + ) def translate_to_rpc(self, rpcPositionNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionNed.north_m = self.north_m - - - - - + rpcPositionNed.east_m = self.east_m - - - - - + rpcPositionNed.down_m = self.down_m - - - class VelocityNed: """ - VelocityNed message type. - - Parameters - ---------- - north_m_s : float - Velocity along north direction in metres per second + VelocityNed message type. - east_m_s : float - Velocity along east direction in metres per second + Parameters + ---------- + north_m_s : float + Velocity along north direction in metres per second - down_m_s : float - Velocity along down direction in metres per second + east_m_s : float + Velocity along east direction in metres per second - """ + down_m_s : float + Velocity along down direction in metres per second - + """ - def __init__( - self, - north_m_s, - east_m_s, - down_m_s): - """ Initializes the VelocityNed object """ + def __init__(self, north_m_s, east_m_s, down_m_s): + """Initializes the VelocityNed object""" self.north_m_s = north_m_s self.east_m_s = east_m_s self.down_m_s = down_m_s def __eq__(self, to_compare): - """ Checks if two VelocityNed are the same """ + """Checks if two VelocityNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # VelocityNed object - return \ - (self.north_m_s == to_compare.north_m_s) and \ - (self.east_m_s == to_compare.east_m_s) and \ - (self.down_m_s == to_compare.down_m_s) + return ( + (self.north_m_s == to_compare.north_m_s) + and (self.east_m_s == to_compare.east_m_s) + and (self.down_m_s == to_compare.down_m_s) + ) except AttributeError: return False def __str__(self): - """ VelocityNed in string representation """ - struct_repr = ", ".join([ + """VelocityNed in string representation""" + struct_repr = ", ".join( + [ "north_m_s: " + str(self.north_m_s), "east_m_s: " + str(self.east_m_s), - "down_m_s: " + str(self.down_m_s) - ]) + "down_m_s: " + str(self.down_m_s), + ] + ) return f"VelocityNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVelocityNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VelocityNed( - - rpcVelocityNed.north_m_s, - - - rpcVelocityNed.east_m_s, - - - rpcVelocityNed.down_m_s - ) + rpcVelocityNed.north_m_s, rpcVelocityNed.east_m_s, rpcVelocityNed.down_m_s + ) def translate_to_rpc(self, rpcVelocityNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVelocityNed.north_m_s = self.north_m_s - - - - - + rpcVelocityNed.east_m_s = self.east_m_s - - - - - + rpcVelocityNed.down_m_s = self.down_m_s - - - class PositionVelocityNed: """ - PositionVelocityNed message type. + PositionVelocityNed message type. - Parameters - ---------- - position : PositionNed - Position (NED) + Parameters + ---------- + position : PositionNed + Position (NED) - velocity : VelocityNed - Velocity (NED) + velocity : VelocityNed + Velocity (NED) - """ - - + """ - def __init__( - self, - position, - velocity): - """ Initializes the PositionVelocityNed object """ + def __init__(self, position, velocity): + """Initializes the PositionVelocityNed object""" self.position = position self.velocity = velocity def __eq__(self, to_compare): - """ Checks if two PositionVelocityNed are the same """ + """Checks if two PositionVelocityNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionVelocityNed object - return \ - (self.position == to_compare.position) and \ - (self.velocity == to_compare.velocity) + return (self.position == to_compare.position) and ( + self.velocity == to_compare.velocity + ) except AttributeError: return False def __str__(self): - """ PositionVelocityNed in string representation """ - struct_repr = ", ".join([ - "position: " + str(self.position), - "velocity: " + str(self.velocity) - ]) + """PositionVelocityNed in string representation""" + struct_repr = ", ".join( + ["position: " + str(self.position), "velocity: " + str(self.velocity)] + ) return f"PositionVelocityNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionVelocityNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionVelocityNed( - - PositionNed.translate_from_rpc(rpcPositionVelocityNed.position), - - - VelocityNed.translate_from_rpc(rpcPositionVelocityNed.velocity) - ) + PositionNed.translate_from_rpc(rpcPositionVelocityNed.position), + VelocityNed.translate_from_rpc(rpcPositionVelocityNed.velocity), + ) def translate_to_rpc(self, rpcPositionVelocityNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - self.position.translate_to_rpc(rpcPositionVelocityNed.position) - - - - - + self.velocity.translate_to_rpc(rpcPositionVelocityNed.velocity) - - - class GroundTruth: """ - GroundTruth message type. + GroundTruth message type. - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - longitude_deg : double - Longitude in degrees (range: -180 to 180) + longitude_deg : double + Longitude in degrees (range: -180 to 180) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - """ - - + """ - def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m): - """ Initializes the GroundTruth object """ + def __init__(self, latitude_deg, longitude_deg, absolute_altitude_m): + """Initializes the GroundTruth object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m def __eq__(self, to_compare): - """ Checks if two GroundTruth are the same """ + """Checks if two GroundTruth are the same""" try: # Try to compare - this likely fails when it is compared to a non # GroundTruth object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + ) except AttributeError: return False def __str__(self): - """ GroundTruth in string representation """ - struct_repr = ", ".join([ + """GroundTruth in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), - "absolute_altitude_m: " + str(self.absolute_altitude_m) - ]) + "absolute_altitude_m: " + str(self.absolute_altitude_m), + ] + ) return f"GroundTruth: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGroundTruth): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GroundTruth( - - rpcGroundTruth.latitude_deg, - - - rpcGroundTruth.longitude_deg, - - - rpcGroundTruth.absolute_altitude_m - ) + rpcGroundTruth.latitude_deg, + rpcGroundTruth.longitude_deg, + rpcGroundTruth.absolute_altitude_m, + ) def translate_to_rpc(self, rpcGroundTruth): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGroundTruth.latitude_deg = self.latitude_deg - - - - - + rpcGroundTruth.longitude_deg = self.longitude_deg - - - - - + rpcGroundTruth.absolute_altitude_m = self.absolute_altitude_m - - - class FixedwingMetrics: """ - FixedwingMetrics message type. - - Parameters - ---------- - airspeed_m_s : float - Current indicated airspeed (IAS) in metres per second + FixedwingMetrics message type. - throttle_percentage : float - Current throttle setting (0 to 100) + Parameters + ---------- + airspeed_m_s : float + Current indicated airspeed (IAS) in metres per second - climb_rate_m_s : float - Current climb rate in metres per second + throttle_percentage : float + Current throttle setting (0 to 100) - groundspeed_m_s : float - Current groundspeed metres per second + climb_rate_m_s : float + Current climb rate in metres per second - heading_deg : float - Current heading in compass units (0-360, 0=north) + groundspeed_m_s : float + Current groundspeed metres per second - absolute_altitude_m : float - Current altitude in metres (MSL) + heading_deg : float + Current heading in compass units (0-360, 0=north) - """ + absolute_altitude_m : float + Current altitude in metres (MSL) - + """ def __init__( - self, - airspeed_m_s, - throttle_percentage, - climb_rate_m_s, - groundspeed_m_s, - heading_deg, - absolute_altitude_m): - """ Initializes the FixedwingMetrics object """ + self, + airspeed_m_s, + throttle_percentage, + climb_rate_m_s, + groundspeed_m_s, + heading_deg, + absolute_altitude_m, + ): + """Initializes the FixedwingMetrics object""" self.airspeed_m_s = airspeed_m_s self.throttle_percentage = throttle_percentage self.climb_rate_m_s = climb_rate_m_s @@ -3062,402 +2409,301 @@ def __init__( self.absolute_altitude_m = absolute_altitude_m def __eq__(self, to_compare): - """ Checks if two FixedwingMetrics are the same """ + """Checks if two FixedwingMetrics are the same""" try: # Try to compare - this likely fails when it is compared to a non # FixedwingMetrics object - return \ - (self.airspeed_m_s == to_compare.airspeed_m_s) and \ - (self.throttle_percentage == to_compare.throttle_percentage) and \ - (self.climb_rate_m_s == to_compare.climb_rate_m_s) and \ - (self.groundspeed_m_s == to_compare.groundspeed_m_s) and \ - (self.heading_deg == to_compare.heading_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) + return ( + (self.airspeed_m_s == to_compare.airspeed_m_s) + and (self.throttle_percentage == to_compare.throttle_percentage) + and (self.climb_rate_m_s == to_compare.climb_rate_m_s) + and (self.groundspeed_m_s == to_compare.groundspeed_m_s) + and (self.heading_deg == to_compare.heading_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + ) except AttributeError: return False def __str__(self): - """ FixedwingMetrics in string representation """ - struct_repr = ", ".join([ + """FixedwingMetrics in string representation""" + struct_repr = ", ".join( + [ "airspeed_m_s: " + str(self.airspeed_m_s), "throttle_percentage: " + str(self.throttle_percentage), "climb_rate_m_s: " + str(self.climb_rate_m_s), "groundspeed_m_s: " + str(self.groundspeed_m_s), "heading_deg: " + str(self.heading_deg), - "absolute_altitude_m: " + str(self.absolute_altitude_m) - ]) + "absolute_altitude_m: " + str(self.absolute_altitude_m), + ] + ) return f"FixedwingMetrics: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFixedwingMetrics): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FixedwingMetrics( - - rpcFixedwingMetrics.airspeed_m_s, - - - rpcFixedwingMetrics.throttle_percentage, - - - rpcFixedwingMetrics.climb_rate_m_s, - - - rpcFixedwingMetrics.groundspeed_m_s, - - - rpcFixedwingMetrics.heading_deg, - - - rpcFixedwingMetrics.absolute_altitude_m - ) + rpcFixedwingMetrics.airspeed_m_s, + rpcFixedwingMetrics.throttle_percentage, + rpcFixedwingMetrics.climb_rate_m_s, + rpcFixedwingMetrics.groundspeed_m_s, + rpcFixedwingMetrics.heading_deg, + rpcFixedwingMetrics.absolute_altitude_m, + ) def translate_to_rpc(self, rpcFixedwingMetrics): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFixedwingMetrics.airspeed_m_s = self.airspeed_m_s - - - - - + rpcFixedwingMetrics.throttle_percentage = self.throttle_percentage - - - - - + rpcFixedwingMetrics.climb_rate_m_s = self.climb_rate_m_s - - - - - + rpcFixedwingMetrics.groundspeed_m_s = self.groundspeed_m_s - - - - - + rpcFixedwingMetrics.heading_deg = self.heading_deg - - - - - + rpcFixedwingMetrics.absolute_altitude_m = self.absolute_altitude_m - - - class AccelerationFrd: """ - AccelerationFrd message type. - - Parameters - ---------- - forward_m_s2 : float - Acceleration in forward direction in metres per second^2 + AccelerationFrd message type. - right_m_s2 : float - Acceleration in right direction in metres per second^2 + Parameters + ---------- + forward_m_s2 : float + Acceleration in forward direction in metres per second^2 - down_m_s2 : float - Acceleration in down direction in metres per second^2 + right_m_s2 : float + Acceleration in right direction in metres per second^2 - """ + down_m_s2 : float + Acceleration in down direction in metres per second^2 - + """ - def __init__( - self, - forward_m_s2, - right_m_s2, - down_m_s2): - """ Initializes the AccelerationFrd object """ + def __init__(self, forward_m_s2, right_m_s2, down_m_s2): + """Initializes the AccelerationFrd object""" self.forward_m_s2 = forward_m_s2 self.right_m_s2 = right_m_s2 self.down_m_s2 = down_m_s2 def __eq__(self, to_compare): - """ Checks if two AccelerationFrd are the same """ + """Checks if two AccelerationFrd are the same""" try: # Try to compare - this likely fails when it is compared to a non # AccelerationFrd object - return \ - (self.forward_m_s2 == to_compare.forward_m_s2) and \ - (self.right_m_s2 == to_compare.right_m_s2) and \ - (self.down_m_s2 == to_compare.down_m_s2) + return ( + (self.forward_m_s2 == to_compare.forward_m_s2) + and (self.right_m_s2 == to_compare.right_m_s2) + and (self.down_m_s2 == to_compare.down_m_s2) + ) except AttributeError: return False def __str__(self): - """ AccelerationFrd in string representation """ - struct_repr = ", ".join([ + """AccelerationFrd in string representation""" + struct_repr = ", ".join( + [ "forward_m_s2: " + str(self.forward_m_s2), "right_m_s2: " + str(self.right_m_s2), - "down_m_s2: " + str(self.down_m_s2) - ]) + "down_m_s2: " + str(self.down_m_s2), + ] + ) return f"AccelerationFrd: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAccelerationFrd): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AccelerationFrd( - - rpcAccelerationFrd.forward_m_s2, - - - rpcAccelerationFrd.right_m_s2, - - - rpcAccelerationFrd.down_m_s2 - ) + rpcAccelerationFrd.forward_m_s2, + rpcAccelerationFrd.right_m_s2, + rpcAccelerationFrd.down_m_s2, + ) def translate_to_rpc(self, rpcAccelerationFrd): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAccelerationFrd.forward_m_s2 = self.forward_m_s2 - - - - - + rpcAccelerationFrd.right_m_s2 = self.right_m_s2 - - - - - + rpcAccelerationFrd.down_m_s2 = self.down_m_s2 - - - class AngularVelocityFrd: """ - AngularVelocityFrd message type. - - Parameters - ---------- - forward_rad_s : float - Angular velocity in forward direction in radians per second + AngularVelocityFrd message type. - right_rad_s : float - Angular velocity in right direction in radians per second + Parameters + ---------- + forward_rad_s : float + Angular velocity in forward direction in radians per second - down_rad_s : float - Angular velocity in Down direction in radians per second + right_rad_s : float + Angular velocity in right direction in radians per second - """ + down_rad_s : float + Angular velocity in Down direction in radians per second - + """ - def __init__( - self, - forward_rad_s, - right_rad_s, - down_rad_s): - """ Initializes the AngularVelocityFrd object """ + def __init__(self, forward_rad_s, right_rad_s, down_rad_s): + """Initializes the AngularVelocityFrd object""" self.forward_rad_s = forward_rad_s self.right_rad_s = right_rad_s self.down_rad_s = down_rad_s def __eq__(self, to_compare): - """ Checks if two AngularVelocityFrd are the same """ + """Checks if two AngularVelocityFrd are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngularVelocityFrd object - return \ - (self.forward_rad_s == to_compare.forward_rad_s) and \ - (self.right_rad_s == to_compare.right_rad_s) and \ - (self.down_rad_s == to_compare.down_rad_s) + return ( + (self.forward_rad_s == to_compare.forward_rad_s) + and (self.right_rad_s == to_compare.right_rad_s) + and (self.down_rad_s == to_compare.down_rad_s) + ) except AttributeError: return False def __str__(self): - """ AngularVelocityFrd in string representation """ - struct_repr = ", ".join([ + """AngularVelocityFrd in string representation""" + struct_repr = ", ".join( + [ "forward_rad_s: " + str(self.forward_rad_s), "right_rad_s: " + str(self.right_rad_s), - "down_rad_s: " + str(self.down_rad_s) - ]) + "down_rad_s: " + str(self.down_rad_s), + ] + ) return f"AngularVelocityFrd: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngularVelocityFrd): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngularVelocityFrd( - - rpcAngularVelocityFrd.forward_rad_s, - - - rpcAngularVelocityFrd.right_rad_s, - - - rpcAngularVelocityFrd.down_rad_s - ) + rpcAngularVelocityFrd.forward_rad_s, + rpcAngularVelocityFrd.right_rad_s, + rpcAngularVelocityFrd.down_rad_s, + ) def translate_to_rpc(self, rpcAngularVelocityFrd): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngularVelocityFrd.forward_rad_s = self.forward_rad_s - - - - - + rpcAngularVelocityFrd.right_rad_s = self.right_rad_s - - - - - + rpcAngularVelocityFrd.down_rad_s = self.down_rad_s - - - class MagneticFieldFrd: """ - MagneticFieldFrd message type. + MagneticFieldFrd message type. - Parameters - ---------- - forward_gauss : float - Magnetic field in forward direction measured in Gauss + Parameters + ---------- + forward_gauss : float + Magnetic field in forward direction measured in Gauss - right_gauss : float - Magnetic field in East direction measured in Gauss + right_gauss : float + Magnetic field in East direction measured in Gauss - down_gauss : float - Magnetic field in Down direction measured in Gauss + down_gauss : float + Magnetic field in Down direction measured in Gauss - """ - - + """ - def __init__( - self, - forward_gauss, - right_gauss, - down_gauss): - """ Initializes the MagneticFieldFrd object """ + def __init__(self, forward_gauss, right_gauss, down_gauss): + """Initializes the MagneticFieldFrd object""" self.forward_gauss = forward_gauss self.right_gauss = right_gauss self.down_gauss = down_gauss def __eq__(self, to_compare): - """ Checks if two MagneticFieldFrd are the same """ + """Checks if two MagneticFieldFrd are the same""" try: # Try to compare - this likely fails when it is compared to a non # MagneticFieldFrd object - return \ - (self.forward_gauss == to_compare.forward_gauss) and \ - (self.right_gauss == to_compare.right_gauss) and \ - (self.down_gauss == to_compare.down_gauss) + return ( + (self.forward_gauss == to_compare.forward_gauss) + and (self.right_gauss == to_compare.right_gauss) + and (self.down_gauss == to_compare.down_gauss) + ) except AttributeError: return False def __str__(self): - """ MagneticFieldFrd in string representation """ - struct_repr = ", ".join([ + """MagneticFieldFrd in string representation""" + struct_repr = ", ".join( + [ "forward_gauss: " + str(self.forward_gauss), "right_gauss: " + str(self.right_gauss), - "down_gauss: " + str(self.down_gauss) - ]) + "down_gauss: " + str(self.down_gauss), + ] + ) return f"MagneticFieldFrd: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMagneticFieldFrd): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MagneticFieldFrd( - - rpcMagneticFieldFrd.forward_gauss, - - - rpcMagneticFieldFrd.right_gauss, - - - rpcMagneticFieldFrd.down_gauss - ) + rpcMagneticFieldFrd.forward_gauss, + rpcMagneticFieldFrd.right_gauss, + rpcMagneticFieldFrd.down_gauss, + ) def translate_to_rpc(self, rpcMagneticFieldFrd): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMagneticFieldFrd.forward_gauss = self.forward_gauss - - - - - + rpcMagneticFieldFrd.right_gauss = self.right_gauss - - - - - + rpcMagneticFieldFrd.down_gauss = self.down_gauss - - - class Imu: """ - Imu message type. - - Parameters - ---------- - acceleration_frd : AccelerationFrd - Acceleration + Imu message type. - angular_velocity_frd : AngularVelocityFrd - Angular velocity + Parameters + ---------- + acceleration_frd : AccelerationFrd + Acceleration - magnetic_field_frd : MagneticFieldFrd - Magnetic field + angular_velocity_frd : AngularVelocityFrd + Angular velocity - temperature_degc : float - Temperature + magnetic_field_frd : MagneticFieldFrd + Magnetic field - timestamp_us : uint64_t - Timestamp in microseconds + temperature_degc : float + Temperature - """ + timestamp_us : uint64_t + Timestamp in microseconds - + """ def __init__( - self, - acceleration_frd, - angular_velocity_frd, - magnetic_field_frd, - temperature_degc, - timestamp_us): - """ Initializes the Imu object """ + self, + acceleration_frd, + angular_velocity_frd, + magnetic_field_frd, + temperature_degc, + timestamp_us, + ): + """Initializes the Imu object""" self.acceleration_frd = acceleration_frd self.angular_velocity_frd = angular_velocity_frd self.magnetic_field_frd = magnetic_field_frd @@ -3465,215 +2711,164 @@ def __init__( self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two Imu are the same """ + """Checks if two Imu are the same""" try: # Try to compare - this likely fails when it is compared to a non # Imu object - return \ - (self.acceleration_frd == to_compare.acceleration_frd) and \ - (self.angular_velocity_frd == to_compare.angular_velocity_frd) and \ - (self.magnetic_field_frd == to_compare.magnetic_field_frd) and \ - (self.temperature_degc == to_compare.temperature_degc) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.acceleration_frd == to_compare.acceleration_frd) + and (self.angular_velocity_frd == to_compare.angular_velocity_frd) + and (self.magnetic_field_frd == to_compare.magnetic_field_frd) + and (self.temperature_degc == to_compare.temperature_degc) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ Imu in string representation """ - struct_repr = ", ".join([ + """Imu in string representation""" + struct_repr = ", ".join( + [ "acceleration_frd: " + str(self.acceleration_frd), "angular_velocity_frd: " + str(self.angular_velocity_frd), "magnetic_field_frd: " + str(self.magnetic_field_frd), "temperature_degc: " + str(self.temperature_degc), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"Imu: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcImu): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Imu( - - AccelerationFrd.translate_from_rpc(rpcImu.acceleration_frd), - - - AngularVelocityFrd.translate_from_rpc(rpcImu.angular_velocity_frd), - - - MagneticFieldFrd.translate_from_rpc(rpcImu.magnetic_field_frd), - - - rpcImu.temperature_degc, - - - rpcImu.timestamp_us - ) + AccelerationFrd.translate_from_rpc(rpcImu.acceleration_frd), + AngularVelocityFrd.translate_from_rpc(rpcImu.angular_velocity_frd), + MagneticFieldFrd.translate_from_rpc(rpcImu.magnetic_field_frd), + rpcImu.temperature_degc, + rpcImu.timestamp_us, + ) def translate_to_rpc(self, rpcImu): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - self.acceleration_frd.translate_to_rpc(rpcImu.acceleration_frd) - - - - - + self.angular_velocity_frd.translate_to_rpc(rpcImu.angular_velocity_frd) - - - - - + self.magnetic_field_frd.translate_to_rpc(rpcImu.magnetic_field_frd) - - - - - + rpcImu.temperature_degc = self.temperature_degc - - - - - + rpcImu.timestamp_us = self.timestamp_us - - - class GpsGlobalOrigin: """ - Gps global origin type. + Gps global origin type. - Parameters - ---------- - latitude_deg : double - Latitude of the origin + Parameters + ---------- + latitude_deg : double + Latitude of the origin - longitude_deg : double - Longitude of the origin + longitude_deg : double + Longitude of the origin - altitude_m : float - Altitude AMSL (above mean sea level) in metres + altitude_m : float + Altitude AMSL (above mean sea level) in metres - """ - - + """ - def __init__( - self, - latitude_deg, - longitude_deg, - altitude_m): - """ Initializes the GpsGlobalOrigin object """ + def __init__(self, latitude_deg, longitude_deg, altitude_m): + """Initializes the GpsGlobalOrigin object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.altitude_m = altitude_m def __eq__(self, to_compare): - """ Checks if two GpsGlobalOrigin are the same """ + """Checks if two GpsGlobalOrigin are the same""" try: # Try to compare - this likely fails when it is compared to a non # GpsGlobalOrigin object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.altitude_m == to_compare.altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.altitude_m == to_compare.altitude_m) + ) except AttributeError: return False def __str__(self): - """ GpsGlobalOrigin in string representation """ - struct_repr = ", ".join([ + """GpsGlobalOrigin in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), - "altitude_m: " + str(self.altitude_m) - ]) + "altitude_m: " + str(self.altitude_m), + ] + ) return f"GpsGlobalOrigin: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGpsGlobalOrigin): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GpsGlobalOrigin( - - rpcGpsGlobalOrigin.latitude_deg, - - - rpcGpsGlobalOrigin.longitude_deg, - - - rpcGpsGlobalOrigin.altitude_m - ) + rpcGpsGlobalOrigin.latitude_deg, + rpcGpsGlobalOrigin.longitude_deg, + rpcGpsGlobalOrigin.altitude_m, + ) def translate_to_rpc(self, rpcGpsGlobalOrigin): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGpsGlobalOrigin.latitude_deg = self.latitude_deg - - - - - + rpcGpsGlobalOrigin.longitude_deg = self.longitude_deg - - - - - + rpcGpsGlobalOrigin.altitude_m = self.altitude_m - - - class Altitude: """ - Altitude message type - - Parameters - ---------- - altitude_monotonic_m : float - Altitude in meters is initialized on system boot and monotonic + Altitude message type - altitude_amsl_m : float - Altitude AMSL (above mean sea level) in meters + Parameters + ---------- + altitude_monotonic_m : float + Altitude in meters is initialized on system boot and monotonic - altitude_local_m : float - Local altitude in meters + altitude_amsl_m : float + Altitude AMSL (above mean sea level) in meters - altitude_relative_m : float - Altitude above home position in meters + altitude_local_m : float + Local altitude in meters - altitude_terrain_m : float - Altitude above terrain in meters + altitude_relative_m : float + Altitude above home position in meters - bottom_clearance_m : float - This is not the altitude, but the clear space below the system according to the fused clearance estimate in meters. + altitude_terrain_m : float + Altitude above terrain in meters - """ + bottom_clearance_m : float + This is not the altitude, but the clear space below the system according to the fused clearance estimate in meters. - + """ def __init__( - self, - altitude_monotonic_m, - altitude_amsl_m, - altitude_local_m, - altitude_relative_m, - altitude_terrain_m, - bottom_clearance_m): - """ Initializes the Altitude object """ + self, + altitude_monotonic_m, + altitude_amsl_m, + altitude_local_m, + altitude_relative_m, + altitude_terrain_m, + bottom_clearance_m, + ): + """Initializes the Altitude object""" self.altitude_monotonic_m = altitude_monotonic_m self.altitude_amsl_m = altitude_amsl_m self.altitude_local_m = altitude_local_m @@ -3682,144 +2877,109 @@ def __init__( self.bottom_clearance_m = bottom_clearance_m def __eq__(self, to_compare): - """ Checks if two Altitude are the same """ + """Checks if two Altitude are the same""" try: # Try to compare - this likely fails when it is compared to a non # Altitude object - return \ - (self.altitude_monotonic_m == to_compare.altitude_monotonic_m) and \ - (self.altitude_amsl_m == to_compare.altitude_amsl_m) and \ - (self.altitude_local_m == to_compare.altitude_local_m) and \ - (self.altitude_relative_m == to_compare.altitude_relative_m) and \ - (self.altitude_terrain_m == to_compare.altitude_terrain_m) and \ - (self.bottom_clearance_m == to_compare.bottom_clearance_m) + return ( + (self.altitude_monotonic_m == to_compare.altitude_monotonic_m) + and (self.altitude_amsl_m == to_compare.altitude_amsl_m) + and (self.altitude_local_m == to_compare.altitude_local_m) + and (self.altitude_relative_m == to_compare.altitude_relative_m) + and (self.altitude_terrain_m == to_compare.altitude_terrain_m) + and (self.bottom_clearance_m == to_compare.bottom_clearance_m) + ) except AttributeError: return False def __str__(self): - """ Altitude in string representation """ - struct_repr = ", ".join([ + """Altitude in string representation""" + struct_repr = ", ".join( + [ "altitude_monotonic_m: " + str(self.altitude_monotonic_m), "altitude_amsl_m: " + str(self.altitude_amsl_m), "altitude_local_m: " + str(self.altitude_local_m), "altitude_relative_m: " + str(self.altitude_relative_m), "altitude_terrain_m: " + str(self.altitude_terrain_m), - "bottom_clearance_m: " + str(self.bottom_clearance_m) - ]) + "bottom_clearance_m: " + str(self.bottom_clearance_m), + ] + ) return f"Altitude: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAltitude): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Altitude( - - rpcAltitude.altitude_monotonic_m, - - - rpcAltitude.altitude_amsl_m, - - - rpcAltitude.altitude_local_m, - - - rpcAltitude.altitude_relative_m, - - - rpcAltitude.altitude_terrain_m, - - - rpcAltitude.bottom_clearance_m - ) + rpcAltitude.altitude_monotonic_m, + rpcAltitude.altitude_amsl_m, + rpcAltitude.altitude_local_m, + rpcAltitude.altitude_relative_m, + rpcAltitude.altitude_terrain_m, + rpcAltitude.bottom_clearance_m, + ) def translate_to_rpc(self, rpcAltitude): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAltitude.altitude_monotonic_m = self.altitude_monotonic_m - - - - - + rpcAltitude.altitude_amsl_m = self.altitude_amsl_m - - - - - + rpcAltitude.altitude_local_m = self.altitude_local_m - - - - - + rpcAltitude.altitude_relative_m = self.altitude_relative_m - - - - - + rpcAltitude.altitude_terrain_m = self.altitude_terrain_m - - - - - + rpcAltitude.bottom_clearance_m = self.bottom_clearance_m - - - class Wind: """ - Wind message type - - Parameters - ---------- - wind_x_ned_m_s : float - Wind in North (NED) direction + Wind message type - wind_y_ned_m_s : float - Wind in East (NED) direction + Parameters + ---------- + wind_x_ned_m_s : float + Wind in North (NED) direction - wind_z_ned_m_s : float - Wind in down (NED) direction + wind_y_ned_m_s : float + Wind in East (NED) direction - horizontal_variability_stddev_m_s : float - Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate + wind_z_ned_m_s : float + Wind in down (NED) direction - vertical_variability_stddev_m_s : float - Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate + horizontal_variability_stddev_m_s : float + Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate - wind_altitude_msl_m : float - Altitude (MSL) that this measurement was taken at + vertical_variability_stddev_m_s : float + Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate - horizontal_wind_speed_accuracy_m_s : float - Horizontal speed 1-STD accuracy + wind_altitude_msl_m : float + Altitude (MSL) that this measurement was taken at - vertical_wind_speed_accuracy_m_s : float - Vertical speed 1-STD accuracy + horizontal_wind_speed_accuracy_m_s : float + Horizontal speed 1-STD accuracy - """ + vertical_wind_speed_accuracy_m_s : float + Vertical speed 1-STD accuracy - + """ def __init__( - self, - wind_x_ned_m_s, - wind_y_ned_m_s, - wind_z_ned_m_s, - horizontal_variability_stddev_m_s, - vertical_variability_stddev_m_s, - wind_altitude_msl_m, - horizontal_wind_speed_accuracy_m_s, - vertical_wind_speed_accuracy_m_s): - """ Initializes the Wind object """ + self, + wind_x_ned_m_s, + wind_y_ned_m_s, + wind_z_ned_m_s, + horizontal_variability_stddev_m_s, + vertical_variability_stddev_m_s, + wind_altitude_msl_m, + horizontal_wind_speed_accuracy_m_s, + vertical_wind_speed_accuracy_m_s, + ): + """Initializes the Wind object""" self.wind_x_ned_m_s = wind_x_ned_m_s self.wind_y_ned_m_s = wind_y_ned_m_s self.wind_z_ned_m_s = wind_z_ned_m_s @@ -3830,170 +2990,141 @@ def __init__( self.vertical_wind_speed_accuracy_m_s = vertical_wind_speed_accuracy_m_s def __eq__(self, to_compare): - """ Checks if two Wind are the same """ + """Checks if two Wind are the same""" try: # Try to compare - this likely fails when it is compared to a non # Wind object - return \ - (self.wind_x_ned_m_s == to_compare.wind_x_ned_m_s) and \ - (self.wind_y_ned_m_s == to_compare.wind_y_ned_m_s) and \ - (self.wind_z_ned_m_s == to_compare.wind_z_ned_m_s) and \ - (self.horizontal_variability_stddev_m_s == to_compare.horizontal_variability_stddev_m_s) and \ - (self.vertical_variability_stddev_m_s == to_compare.vertical_variability_stddev_m_s) and \ - (self.wind_altitude_msl_m == to_compare.wind_altitude_msl_m) and \ - (self.horizontal_wind_speed_accuracy_m_s == to_compare.horizontal_wind_speed_accuracy_m_s) and \ - (self.vertical_wind_speed_accuracy_m_s == to_compare.vertical_wind_speed_accuracy_m_s) + return ( + (self.wind_x_ned_m_s == to_compare.wind_x_ned_m_s) + and (self.wind_y_ned_m_s == to_compare.wind_y_ned_m_s) + and (self.wind_z_ned_m_s == to_compare.wind_z_ned_m_s) + and ( + self.horizontal_variability_stddev_m_s + == to_compare.horizontal_variability_stddev_m_s + ) + and ( + self.vertical_variability_stddev_m_s + == to_compare.vertical_variability_stddev_m_s + ) + and (self.wind_altitude_msl_m == to_compare.wind_altitude_msl_m) + and ( + self.horizontal_wind_speed_accuracy_m_s + == to_compare.horizontal_wind_speed_accuracy_m_s + ) + and ( + self.vertical_wind_speed_accuracy_m_s + == to_compare.vertical_wind_speed_accuracy_m_s + ) + ) except AttributeError: return False def __str__(self): - """ Wind in string representation """ - struct_repr = ", ".join([ + """Wind in string representation""" + struct_repr = ", ".join( + [ "wind_x_ned_m_s: " + str(self.wind_x_ned_m_s), "wind_y_ned_m_s: " + str(self.wind_y_ned_m_s), "wind_z_ned_m_s: " + str(self.wind_z_ned_m_s), - "horizontal_variability_stddev_m_s: " + str(self.horizontal_variability_stddev_m_s), - "vertical_variability_stddev_m_s: " + str(self.vertical_variability_stddev_m_s), + "horizontal_variability_stddev_m_s: " + + str(self.horizontal_variability_stddev_m_s), + "vertical_variability_stddev_m_s: " + + str(self.vertical_variability_stddev_m_s), "wind_altitude_msl_m: " + str(self.wind_altitude_msl_m), - "horizontal_wind_speed_accuracy_m_s: " + str(self.horizontal_wind_speed_accuracy_m_s), - "vertical_wind_speed_accuracy_m_s: " + str(self.vertical_wind_speed_accuracy_m_s) - ]) + "horizontal_wind_speed_accuracy_m_s: " + + str(self.horizontal_wind_speed_accuracy_m_s), + "vertical_wind_speed_accuracy_m_s: " + + str(self.vertical_wind_speed_accuracy_m_s), + ] + ) return f"Wind: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcWind): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Wind( - - rpcWind.wind_x_ned_m_s, - - - rpcWind.wind_y_ned_m_s, - - - rpcWind.wind_z_ned_m_s, - - - rpcWind.horizontal_variability_stddev_m_s, - - - rpcWind.vertical_variability_stddev_m_s, - - - rpcWind.wind_altitude_msl_m, - - - rpcWind.horizontal_wind_speed_accuracy_m_s, - - - rpcWind.vertical_wind_speed_accuracy_m_s - ) + rpcWind.wind_x_ned_m_s, + rpcWind.wind_y_ned_m_s, + rpcWind.wind_z_ned_m_s, + rpcWind.horizontal_variability_stddev_m_s, + rpcWind.vertical_variability_stddev_m_s, + rpcWind.wind_altitude_msl_m, + rpcWind.horizontal_wind_speed_accuracy_m_s, + rpcWind.vertical_wind_speed_accuracy_m_s, + ) def translate_to_rpc(self, rpcWind): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcWind.wind_x_ned_m_s = self.wind_x_ned_m_s - - - - - + rpcWind.wind_y_ned_m_s = self.wind_y_ned_m_s - - - - - + rpcWind.wind_z_ned_m_s = self.wind_z_ned_m_s - - - - - - rpcWind.horizontal_variability_stddev_m_s = self.horizontal_variability_stddev_m_s - - - - - + + rpcWind.horizontal_variability_stddev_m_s = ( + self.horizontal_variability_stddev_m_s + ) + rpcWind.vertical_variability_stddev_m_s = self.vertical_variability_stddev_m_s - - - - - + rpcWind.wind_altitude_msl_m = self.wind_altitude_msl_m - - - - - - rpcWind.horizontal_wind_speed_accuracy_m_s = self.horizontal_wind_speed_accuracy_m_s - - - - - + + rpcWind.horizontal_wind_speed_accuracy_m_s = ( + self.horizontal_wind_speed_accuracy_m_s + ) + rpcWind.vertical_wind_speed_accuracy_m_s = self.vertical_wind_speed_accuracy_m_s - - - class TelemetryResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for telemetry requests. + Possible results returned for telemetry requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Success: the telemetry command was accepted by the vehicle + SUCCESS + Success: the telemetry command was accepted by the vehicle - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - TIMEOUT - Request timed out + TIMEOUT + Request timed out - UNSUPPORTED - Request not supported + UNSUPPORTED + Request not supported - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -4023,7 +3154,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_pb2.TelemetryResult.RESULT_UNKNOWN: return TelemetryResult.Result.UNKNOWN if rpc_enum_value == telemetry_pb2.TelemetryResult.RESULT_SUCCESS: @@ -4043,69 +3174,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the TelemetryResult object """ + def __init__(self, result, result_str): + """Initializes the TelemetryResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two TelemetryResult are the same """ + """Checks if two TelemetryResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # TelemetryResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ TelemetryResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """TelemetryResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"TelemetryResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTelemetryResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TelemetryResult( - - TelemetryResult.Result.translate_from_rpc(rpcTelemetryResult.result), - - - rpcTelemetryResult.result_str - ) + TelemetryResult.Result.translate_from_rpc(rpcTelemetryResult.result), + rpcTelemetryResult.result_str, + ) def translate_to_rpc(self, rpcTelemetryResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTelemetryResult.result = self.result.translate_to_rpc() - - - - - - rpcTelemetryResult.result_str = self.result_str - - - + rpcTelemetryResult.result_str = self.result_str class TelemetryError(Exception): - """ Raised when a TelemetryResult is a fail code """ + """Raised when a TelemetryResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -4118,36 +3230,34 @@ def __str__(self): class Telemetry(AsyncBase): """ - Allow users to get vehicle telemetry and state information - (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates. - Certain Telemetry Topics such as, Position or Velocity_Ned require GPS Fix before data gets published. + Allow users to get vehicle telemetry and state information + (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates. + Certain Telemetry Topics such as, Position or Velocity_Ned require GPS Fix before data gets published. - Generated by dcsdkgen - MAVSDK Telemetry API + Generated by dcsdkgen - MAVSDK Telemetry API """ # Plugin name name = "Telemetry" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = telemetry_pb2_grpc.TelemetryServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return TelemetryResult.translate_from_rpc(response.telemetry_result) - async def position(self): """ - Subscribe to 'position' updates. + Subscribe to 'position' updates. + + Yields + ------- + position : Position + The next position - Yields - ------- - position : Position - The next position - """ request = telemetry_pb2.SubscribePositionRequest() @@ -4155,23 +3265,20 @@ async def position(self): try: async for response in position_stream: - - - yield Position.translate_from_rpc(response.position) finally: position_stream.cancel() async def home(self): """ - Subscribe to 'home position' updates. + Subscribe to 'home position' updates. + + Yields + ------- + home : Position + The next home position - Yields - ------- - home : Position - The next home position - """ request = telemetry_pb2.SubscribeHomeRequest() @@ -4179,23 +3286,20 @@ async def home(self): try: async for response in home_stream: - - - yield Position.translate_from_rpc(response.home) finally: home_stream.cancel() async def in_air(self): """ - Subscribe to in-air updates. + Subscribe to in-air updates. + + Yields + ------- + is_in_air : bool + The next 'in-air' state - Yields - ------- - is_in_air : bool - The next 'in-air' state - """ request = telemetry_pb2.SubscribeInAirRequest() @@ -4203,23 +3307,20 @@ async def in_air(self): try: async for response in in_air_stream: - - - yield response.is_in_air finally: in_air_stream.cancel() async def landed_state(self): """ - Subscribe to landed state updates + Subscribe to landed state updates + + Yields + ------- + landed_state : LandedState + The next 'landed' state - Yields - ------- - landed_state : LandedState - The next 'landed' state - """ request = telemetry_pb2.SubscribeLandedStateRequest() @@ -4227,23 +3328,20 @@ async def landed_state(self): try: async for response in landed_state_stream: - - - yield LandedState.translate_from_rpc(response.landed_state) finally: landed_state_stream.cancel() async def armed(self): """ - Subscribe to armed updates. + Subscribe to armed updates. + + Yields + ------- + is_armed : bool + The next 'armed' state - Yields - ------- - is_armed : bool - The next 'armed' state - """ request = telemetry_pb2.SubscribeArmedRequest() @@ -4251,23 +3349,20 @@ async def armed(self): try: async for response in armed_stream: - - - yield response.is_armed finally: armed_stream.cancel() async def vtol_state(self): """ - subscribe to vtol state Updates + subscribe to vtol state Updates + + Yields + ------- + vtol_state : VtolState + The next 'vtol' state - Yields - ------- - vtol_state : VtolState - The next 'vtol' state - """ request = telemetry_pb2.SubscribeVtolStateRequest() @@ -4275,23 +3370,20 @@ async def vtol_state(self): try: async for response in vtol_state_stream: - - - yield VtolState.translate_from_rpc(response.vtol_state) finally: vtol_state_stream.cancel() async def attitude_quaternion(self): """ - Subscribe to 'attitude' updates (quaternion). + Subscribe to 'attitude' updates (quaternion). + + Yields + ------- + attitude_quaternion : Quaternion + The next attitude (quaternion) - Yields - ------- - attitude_quaternion : Quaternion - The next attitude (quaternion) - """ request = telemetry_pb2.SubscribeAttitudeQuaternionRequest() @@ -4299,23 +3391,20 @@ async def attitude_quaternion(self): try: async for response in attitude_quaternion_stream: - - - yield Quaternion.translate_from_rpc(response.attitude_quaternion) finally: attitude_quaternion_stream.cancel() async def attitude_euler(self): """ - Subscribe to 'attitude' updates (Euler). + Subscribe to 'attitude' updates (Euler). + + Yields + ------- + attitude_euler : EulerAngle + The next attitude (Euler) - Yields - ------- - attitude_euler : EulerAngle - The next attitude (Euler) - """ request = telemetry_pb2.SubscribeAttitudeEulerRequest() @@ -4323,47 +3412,45 @@ async def attitude_euler(self): try: async for response in attitude_euler_stream: - - - yield EulerAngle.translate_from_rpc(response.attitude_euler) finally: attitude_euler_stream.cancel() async def attitude_angular_velocity_body(self): """ - Subscribe to 'attitude' updates (angular velocity) + Subscribe to 'attitude' updates (angular velocity) + + Yields + ------- + attitude_angular_velocity_body : AngularVelocityBody + The next angular velocity (rad/s) - Yields - ------- - attitude_angular_velocity_body : AngularVelocityBody - The next angular velocity (rad/s) - """ request = telemetry_pb2.SubscribeAttitudeAngularVelocityBodyRequest() - attitude_angular_velocity_body_stream = self._stub.SubscribeAttitudeAngularVelocityBody(request) + attitude_angular_velocity_body_stream = ( + self._stub.SubscribeAttitudeAngularVelocityBody(request) + ) try: async for response in attitude_angular_velocity_body_stream: - - - - yield AngularVelocityBody.translate_from_rpc(response.attitude_angular_velocity_body) + yield AngularVelocityBody.translate_from_rpc( + response.attitude_angular_velocity_body + ) finally: attitude_angular_velocity_body_stream.cancel() async def velocity_ned(self): """ - Subscribe to 'ground speed' updates (NED). + Subscribe to 'ground speed' updates (NED). + + Yields + ------- + velocity_ned : VelocityNed + The next velocity (NED) - Yields - ------- - velocity_ned : VelocityNed - The next velocity (NED) - """ request = telemetry_pb2.SubscribeVelocityNedRequest() @@ -4371,23 +3458,20 @@ async def velocity_ned(self): try: async for response in velocity_ned_stream: - - - yield VelocityNed.translate_from_rpc(response.velocity_ned) finally: velocity_ned_stream.cancel() async def gps_info(self): """ - Subscribe to 'GPS info' updates. + Subscribe to 'GPS info' updates. + + Yields + ------- + gps_info : GpsInfo + The next 'GPS info' state - Yields - ------- - gps_info : GpsInfo - The next 'GPS info' state - """ request = telemetry_pb2.SubscribeGpsInfoRequest() @@ -4395,23 +3479,20 @@ async def gps_info(self): try: async for response in gps_info_stream: - - - yield GpsInfo.translate_from_rpc(response.gps_info) finally: gps_info_stream.cancel() async def raw_gps(self): """ - Subscribe to 'Raw GPS' updates. + Subscribe to 'Raw GPS' updates. + + Yields + ------- + raw_gps : RawGps + The next 'Raw GPS' state. Warning: this is an advanced feature, use `Position` updates to get the location of the drone! - Yields - ------- - raw_gps : RawGps - The next 'Raw GPS' state. Warning: this is an advanced feature, use `Position` updates to get the location of the drone! - """ request = telemetry_pb2.SubscribeRawGpsRequest() @@ -4419,23 +3500,20 @@ async def raw_gps(self): try: async for response in raw_gps_stream: - - - yield RawGps.translate_from_rpc(response.raw_gps) finally: raw_gps_stream.cancel() async def battery(self): """ - Subscribe to 'battery' updates. + Subscribe to 'battery' updates. + + Yields + ------- + battery : Battery + The next 'battery' state - Yields - ------- - battery : Battery - The next 'battery' state - """ request = telemetry_pb2.SubscribeBatteryRequest() @@ -4443,23 +3521,20 @@ async def battery(self): try: async for response in battery_stream: - - - yield Battery.translate_from_rpc(response.battery) finally: battery_stream.cancel() async def flight_mode(self): """ - Subscribe to 'flight mode' updates. + Subscribe to 'flight mode' updates. + + Yields + ------- + flight_mode : FlightMode + The next flight mode - Yields - ------- - flight_mode : FlightMode - The next flight mode - """ request = telemetry_pb2.SubscribeFlightModeRequest() @@ -4467,23 +3542,20 @@ async def flight_mode(self): try: async for response in flight_mode_stream: - - - yield FlightMode.translate_from_rpc(response.flight_mode) finally: flight_mode_stream.cancel() async def health(self): """ - Subscribe to 'health' updates. + Subscribe to 'health' updates. + + Yields + ------- + health : Health + The next 'health' state - Yields - ------- - health : Health - The next 'health' state - """ request = telemetry_pb2.SubscribeHealthRequest() @@ -4491,23 +3563,20 @@ async def health(self): try: async for response in health_stream: - - - yield Health.translate_from_rpc(response.health) finally: health_stream.cancel() async def rc_status(self): """ - Subscribe to 'RC status' updates. + Subscribe to 'RC status' updates. + + Yields + ------- + rc_status : RcStatus + The next RC status - Yields - ------- - rc_status : RcStatus - The next RC status - """ request = telemetry_pb2.SubscribeRcStatusRequest() @@ -4515,23 +3584,20 @@ async def rc_status(self): try: async for response in rc_status_stream: - - - yield RcStatus.translate_from_rpc(response.rc_status) finally: rc_status_stream.cancel() async def status_text(self): """ - Subscribe to 'status text' updates. + Subscribe to 'status text' updates. + + Yields + ------- + status_text : StatusText + The next 'status text' - Yields - ------- - status_text : StatusText - The next 'status text' - """ request = telemetry_pb2.SubscribeStatusTextRequest() @@ -4539,71 +3605,70 @@ async def status_text(self): try: async for response in status_text_stream: - - - yield StatusText.translate_from_rpc(response.status_text) finally: status_text_stream.cancel() async def actuator_control_target(self): """ - Subscribe to 'actuator control target' updates. + Subscribe to 'actuator control target' updates. + + Yields + ------- + actuator_control_target : ActuatorControlTarget + The next actuator control target - Yields - ------- - actuator_control_target : ActuatorControlTarget - The next actuator control target - """ request = telemetry_pb2.SubscribeActuatorControlTargetRequest() - actuator_control_target_stream = self._stub.SubscribeActuatorControlTarget(request) + actuator_control_target_stream = self._stub.SubscribeActuatorControlTarget( + request + ) try: async for response in actuator_control_target_stream: - - - - yield ActuatorControlTarget.translate_from_rpc(response.actuator_control_target) + yield ActuatorControlTarget.translate_from_rpc( + response.actuator_control_target + ) finally: actuator_control_target_stream.cancel() async def actuator_output_status(self): """ - Subscribe to 'actuator output status' updates. + Subscribe to 'actuator output status' updates. + + Yields + ------- + actuator_output_status : ActuatorOutputStatus + The next actuator output status - Yields - ------- - actuator_output_status : ActuatorOutputStatus - The next actuator output status - """ request = telemetry_pb2.SubscribeActuatorOutputStatusRequest() - actuator_output_status_stream = self._stub.SubscribeActuatorOutputStatus(request) + actuator_output_status_stream = self._stub.SubscribeActuatorOutputStatus( + request + ) try: async for response in actuator_output_status_stream: - - - - yield ActuatorOutputStatus.translate_from_rpc(response.actuator_output_status) + yield ActuatorOutputStatus.translate_from_rpc( + response.actuator_output_status + ) finally: actuator_output_status_stream.cancel() async def odometry(self): """ - Subscribe to 'odometry' updates. + Subscribe to 'odometry' updates. + + Yields + ------- + odometry : Odometry + The next odometry status - Yields - ------- - odometry : Odometry - The next odometry status - """ request = telemetry_pb2.SubscribeOdometryRequest() @@ -4611,23 +3676,20 @@ async def odometry(self): try: async for response in odometry_stream: - - - yield Odometry.translate_from_rpc(response.odometry) finally: odometry_stream.cancel() async def position_velocity_ned(self): """ - Subscribe to 'position velocity' updates. + Subscribe to 'position velocity' updates. + + Yields + ------- + position_velocity_ned : PositionVelocityNed + The next position and velocity status - Yields - ------- - position_velocity_ned : PositionVelocityNed - The next position and velocity status - """ request = telemetry_pb2.SubscribePositionVelocityNedRequest() @@ -4635,23 +3697,22 @@ async def position_velocity_ned(self): try: async for response in position_velocity_ned_stream: - - - - yield PositionVelocityNed.translate_from_rpc(response.position_velocity_ned) + yield PositionVelocityNed.translate_from_rpc( + response.position_velocity_ned + ) finally: position_velocity_ned_stream.cancel() async def ground_truth(self): """ - Subscribe to 'ground truth' updates. + Subscribe to 'ground truth' updates. + + Yields + ------- + ground_truth : GroundTruth + Ground truth position information available in simulation - Yields - ------- - ground_truth : GroundTruth - Ground truth position information available in simulation - """ request = telemetry_pb2.SubscribeGroundTruthRequest() @@ -4659,23 +3720,20 @@ async def ground_truth(self): try: async for response in ground_truth_stream: - - - yield GroundTruth.translate_from_rpc(response.ground_truth) finally: ground_truth_stream.cancel() async def fixedwing_metrics(self): """ - Subscribe to 'fixedwing metrics' updates. + Subscribe to 'fixedwing metrics' updates. + + Yields + ------- + fixedwing_metrics : FixedwingMetrics + The next fixedwing metrics - Yields - ------- - fixedwing_metrics : FixedwingMetrics - The next fixedwing metrics - """ request = telemetry_pb2.SubscribeFixedwingMetricsRequest() @@ -4683,23 +3741,20 @@ async def fixedwing_metrics(self): try: async for response in fixedwing_metrics_stream: - - - yield FixedwingMetrics.translate_from_rpc(response.fixedwing_metrics) finally: fixedwing_metrics_stream.cancel() async def imu(self): """ - Subscribe to 'IMU' updates (in SI units in NED body frame). + Subscribe to 'IMU' updates (in SI units in NED body frame). + + Yields + ------- + imu : Imu + The next IMU status - Yields - ------- - imu : Imu - The next IMU status - """ request = telemetry_pb2.SubscribeImuRequest() @@ -4707,23 +3762,20 @@ async def imu(self): try: async for response in imu_stream: - - - yield Imu.translate_from_rpc(response.imu) finally: imu_stream.cancel() async def scaled_imu(self): """ - Subscribe to 'Scaled IMU' updates. + Subscribe to 'Scaled IMU' updates. + + Yields + ------- + imu : Imu + The next scaled IMU status - Yields - ------- - imu : Imu - The next scaled IMU status - """ request = telemetry_pb2.SubscribeScaledImuRequest() @@ -4731,23 +3783,20 @@ async def scaled_imu(self): try: async for response in scaled_imu_stream: - - - yield Imu.translate_from_rpc(response.imu) finally: scaled_imu_stream.cancel() async def raw_imu(self): """ - Subscribe to 'Raw IMU' updates (note that units are are incorrect and "raw" as provided by the sensor) + Subscribe to 'Raw IMU' updates (note that units are are incorrect and "raw" as provided by the sensor) + + Yields + ------- + imu : Imu + The next raw IMU status - Yields - ------- - imu : Imu - The next raw IMU status - """ request = telemetry_pb2.SubscribeRawImuRequest() @@ -4755,23 +3804,20 @@ async def raw_imu(self): try: async for response in raw_imu_stream: - - - yield Imu.translate_from_rpc(response.imu) finally: raw_imu_stream.cancel() async def health_all_ok(self): """ - Subscribe to 'HealthAllOk' updates. + Subscribe to 'HealthAllOk' updates. + + Yields + ------- + is_health_all_ok : bool + The next 'health all ok' status - Yields - ------- - is_health_all_ok : bool - The next 'health all ok' status - """ request = telemetry_pb2.SubscribeHealthAllOkRequest() @@ -4779,23 +3825,20 @@ async def health_all_ok(self): try: async for response in health_all_ok_stream: - - - yield response.is_health_all_ok finally: health_all_ok_stream.cancel() async def unix_epoch_time(self): """ - Subscribe to 'unix epoch time' updates. + Subscribe to 'unix epoch time' updates. + + Yields + ------- + time_us : uint64_t + The next 'unix epoch time' status - Yields - ------- - time_us : uint64_t - The next 'unix epoch time' status - """ request = telemetry_pb2.SubscribeUnixEpochTimeRequest() @@ -4803,23 +3846,20 @@ async def unix_epoch_time(self): try: async for response in unix_epoch_time_stream: - - - yield response.time_us finally: unix_epoch_time_stream.cancel() async def distance_sensor(self): """ - Subscribe to 'Distance Sensor' updates. + Subscribe to 'Distance Sensor' updates. + + Yields + ------- + distance_sensor : DistanceSensor + The next Distance Sensor status - Yields - ------- - distance_sensor : DistanceSensor - The next Distance Sensor status - """ request = telemetry_pb2.SubscribeDistanceSensorRequest() @@ -4827,23 +3867,20 @@ async def distance_sensor(self): try: async for response in distance_sensor_stream: - - - yield DistanceSensor.translate_from_rpc(response.distance_sensor) finally: distance_sensor_stream.cancel() async def scaled_pressure(self): """ - Subscribe to 'Scaled Pressure' updates. + Subscribe to 'Scaled Pressure' updates. + + Yields + ------- + scaled_pressure : ScaledPressure + The next Scaled Pressure status - Yields - ------- - scaled_pressure : ScaledPressure - The next Scaled Pressure status - """ request = telemetry_pb2.SubscribeScaledPressureRequest() @@ -4851,23 +3888,20 @@ async def scaled_pressure(self): try: async for response in scaled_pressure_stream: - - - yield ScaledPressure.translate_from_rpc(response.scaled_pressure) finally: scaled_pressure_stream.cancel() async def heading(self): """ - Subscribe to 'Heading' updates. + Subscribe to 'Heading' updates. + + Yields + ------- + heading_deg : Heading + The next heading (yaw) in degrees - Yields - ------- - heading_deg : Heading - The next heading (yaw) in degrees - """ request = telemetry_pb2.SubscribeHeadingRequest() @@ -4875,23 +3909,20 @@ async def heading(self): try: async for response in heading_stream: - - - yield Heading.translate_from_rpc(response.heading_deg) finally: heading_stream.cancel() async def altitude(self): """ - Subscribe to 'Altitude' updates. + Subscribe to 'Altitude' updates. + + Yields + ------- + altitude : Altitude + The next altitude - Yields - ------- - altitude : Altitude - The next altitude - """ request = telemetry_pb2.SubscribeAltitudeRequest() @@ -4899,23 +3930,20 @@ async def altitude(self): try: async for response in altitude_stream: - - - yield Altitude.translate_from_rpc(response.altitude) finally: altitude_stream.cancel() async def wind(self): """ - Subscribe to 'Wind Estimated' updates. + Subscribe to 'Wind Estimated' updates. + + Yields + ------- + wind : Wind + The next wind - Yields - ------- - wind : Wind - The next wind - """ request = telemetry_pb2.SubscribeWindRequest() @@ -4923,661 +3951,607 @@ async def wind(self): try: async for response in wind_stream: - - - yield Wind.translate_from_rpc(response.wind) finally: wind_stream.cancel() async def set_rate_position(self, rate_hz): """ - Set rate to 'position' updates. + Set rate to 'position' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRatePositionRequest() request.rate_hz = rate_hz response = await self._stub.SetRatePosition(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_position()", rate_hz) - async def set_rate_home(self, rate_hz): """ - Set rate to 'home position' updates. + Set rate to 'home position' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateHomeRequest() request.rate_hz = rate_hz response = await self._stub.SetRateHome(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_home()", rate_hz) - async def set_rate_in_air(self, rate_hz): """ - Set rate to in-air updates. + Set rate to in-air updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateInAirRequest() request.rate_hz = rate_hz response = await self._stub.SetRateInAir(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_in_air()", rate_hz) - async def set_rate_landed_state(self, rate_hz): """ - Set rate to landed state updates + Set rate to landed state updates - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateLandedStateRequest() request.rate_hz = rate_hz response = await self._stub.SetRateLandedState(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_landed_state()", rate_hz) - async def set_rate_vtol_state(self, rate_hz): """ - Set rate to VTOL state updates + Set rate to VTOL state updates - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateVtolStateRequest() request.rate_hz = rate_hz response = await self._stub.SetRateVtolState(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_vtol_state()", rate_hz) - async def set_rate_attitude_quaternion(self, rate_hz): """ - Set rate to 'attitude euler angle' updates. + Set rate to 'attitude euler angle' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateAttitudeQuaternionRequest() request.rate_hz = rate_hz response = await self._stub.SetRateAttitudeQuaternion(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_attitude_quaternion()", rate_hz) - async def set_rate_attitude_euler(self, rate_hz): """ - Set rate to 'attitude quaternion' updates. + Set rate to 'attitude quaternion' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateAttitudeEulerRequest() request.rate_hz = rate_hz response = await self._stub.SetRateAttitudeEuler(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_attitude_euler()", rate_hz) - async def set_rate_velocity_ned(self, rate_hz): """ - Set rate of camera attitude updates. - Set rate to 'ground speed' updates (NED). - - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) - - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Set rate of camera attitude updates. + Set rate to 'ground speed' updates (NED). + + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) + + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateVelocityNedRequest() request.rate_hz = rate_hz response = await self._stub.SetRateVelocityNed(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_velocity_ned()", rate_hz) - async def set_rate_gps_info(self, rate_hz): """ - Set rate to 'GPS info' updates. + Set rate to 'GPS info' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateGpsInfoRequest() request.rate_hz = rate_hz response = await self._stub.SetRateGpsInfo(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_gps_info()", rate_hz) - async def set_rate_battery(self, rate_hz): """ - Set rate to 'battery' updates. + Set rate to 'battery' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateBatteryRequest() request.rate_hz = rate_hz response = await self._stub.SetRateBattery(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_battery()", rate_hz) - async def set_rate_rc_status(self, rate_hz): """ - Set rate to 'RC status' updates. + Set rate to 'RC status' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateRcStatusRequest() request.rate_hz = rate_hz response = await self._stub.SetRateRcStatus(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_rc_status()", rate_hz) - async def set_rate_actuator_control_target(self, rate_hz): """ - Set rate to 'actuator control target' updates. + Set rate to 'actuator control target' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateActuatorControlTargetRequest() request.rate_hz = rate_hz response = await self._stub.SetRateActuatorControlTarget(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_actuator_control_target()", rate_hz) - async def set_rate_actuator_output_status(self, rate_hz): """ - Set rate to 'actuator output status' updates. + Set rate to 'actuator output status' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateActuatorOutputStatusRequest() request.rate_hz = rate_hz response = await self._stub.SetRateActuatorOutputStatus(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_actuator_output_status()", rate_hz) - async def set_rate_odometry(self, rate_hz): """ - Set rate to 'odometry' updates. + Set rate to 'odometry' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateOdometryRequest() request.rate_hz = rate_hz response = await self._stub.SetRateOdometry(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_odometry()", rate_hz) - async def set_rate_position_velocity_ned(self, rate_hz): """ - Set rate to 'position velocity' updates. + Set rate to 'position velocity' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRatePositionVelocityNedRequest() request.rate_hz = rate_hz response = await self._stub.SetRatePositionVelocityNed(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_position_velocity_ned()", rate_hz) - async def set_rate_ground_truth(self, rate_hz): """ - Set rate to 'ground truth' updates. + Set rate to 'ground truth' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateGroundTruthRequest() request.rate_hz = rate_hz response = await self._stub.SetRateGroundTruth(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_ground_truth()", rate_hz) - async def set_rate_fixedwing_metrics(self, rate_hz): """ - Set rate to 'fixedwing metrics' updates. + Set rate to 'fixedwing metrics' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateFixedwingMetricsRequest() request.rate_hz = rate_hz response = await self._stub.SetRateFixedwingMetrics(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_fixedwing_metrics()", rate_hz) - async def set_rate_imu(self, rate_hz): """ - Set rate to 'IMU' updates. + Set rate to 'IMU' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateImuRequest() request.rate_hz = rate_hz response = await self._stub.SetRateImu(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_imu()", rate_hz) - async def set_rate_scaled_imu(self, rate_hz): """ - Set rate to 'Scaled IMU' updates. + Set rate to 'Scaled IMU' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateScaledImuRequest() request.rate_hz = rate_hz response = await self._stub.SetRateScaledImu(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_scaled_imu()", rate_hz) - async def set_rate_raw_imu(self, rate_hz): """ - Set rate to 'Raw IMU' updates. + Set rate to 'Raw IMU' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateRawImuRequest() request.rate_hz = rate_hz response = await self._stub.SetRateRawImu(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_raw_imu()", rate_hz) - async def set_rate_unix_epoch_time(self, rate_hz): """ - Set rate to 'unix epoch time' updates. + Set rate to 'unix epoch time' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateUnixEpochTimeRequest() request.rate_hz = rate_hz response = await self._stub.SetRateUnixEpochTime(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_unix_epoch_time()", rate_hz) - async def set_rate_distance_sensor(self, rate_hz): """ - Set rate to 'Distance Sensor' updates. + Set rate to 'Distance Sensor' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateDistanceSensorRequest() request.rate_hz = rate_hz response = await self._stub.SetRateDistanceSensor(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_distance_sensor()", rate_hz) - async def set_rate_altitude(self, rate_hz): """ - Set rate to 'Altitude' updates. + Set rate to 'Altitude' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateAltitudeRequest() request.rate_hz = rate_hz response = await self._stub.SetRateAltitude(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_altitude()", rate_hz) - async def set_rate_health(self, rate_hz): """ - Set rate to 'Health' updates. + Set rate to 'Health' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.SetRateHealthRequest() request.rate_hz = rate_hz response = await self._stub.SetRateHealth(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_health()", rate_hz) - async def get_gps_global_origin(self): """ - Get the GPS location of where the estimator has been initialized. - - Returns - ------- - gps_global_origin : GpsGlobalOrigin - - Raises - ------ - TelemetryError - If the request fails. The error contains the reason for the failure. + Get the GPS location of where the estimator has been initialized. + + Returns + ------- + gps_global_origin : GpsGlobalOrigin + + Raises + ------ + TelemetryError + If the request fails. The error contains the reason for the failure. """ request = telemetry_pb2.GetGpsGlobalOriginRequest() response = await self._stub.GetGpsGlobalOrigin(request) - result = self._extract_result(response) if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "get_gps_global_origin()") - return GpsGlobalOrigin.translate_from_rpc(response.gps_global_origin) - \ No newline at end of file diff --git a/mavsdk/telemetry_pb2.py b/mavsdk/telemetry_pb2.py index 48d07d80..55aa2765 100644 --- a/mavsdk/telemetry_pb2.py +++ b/mavsdk/telemetry_pb2.py @@ -4,18 +4,15 @@ # source: telemetry/telemetry.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'telemetry/telemetry.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "telemetry/telemetry.proto" ) # @@protoc_insertion_point(imports) @@ -25,486 +22,678 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x19telemetry/telemetry.proto\x12\x14mavsdk.rpc.telemetry\x1a\x14mavsdk_options.proto\"\x1a\n\x18SubscribePositionRequest\"D\n\x10PositionResponse\x12\x30\n\x08position\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position\"\x16\n\x14SubscribeHomeRequest\"<\n\x0cHomeResponse\x12,\n\x04home\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position\"\x17\n\x15SubscribeInAirRequest\"\"\n\rInAirResponse\x12\x11\n\tis_in_air\x18\x01 \x01(\x08\"\x1d\n\x1bSubscribeLandedStateRequest\"N\n\x13LandedStateResponse\x12\x37\n\x0clanded_state\x18\x01 \x01(\x0e\x32!.mavsdk.rpc.telemetry.LandedState\"\x17\n\x15SubscribeArmedRequest\"!\n\rArmedResponse\x12\x10\n\x08is_armed\x18\x01 \x01(\x08\"\x1b\n\x19SubscribeVtolStateRequest\"H\n\x11VtolStateResponse\x12\x33\n\nvtol_state\x18\x01 \x01(\x0e\x32\x1f.mavsdk.rpc.telemetry.VtolState\"$\n\"SubscribeAttitudeQuaternionRequest\"[\n\x1a\x41ttitudeQuaternionResponse\x12=\n\x13\x61ttitude_quaternion\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\"\x1f\n\x1dSubscribeAttitudeEulerRequest\"Q\n\x15\x41ttitudeEulerResponse\x12\x38\n\x0e\x61ttitude_euler\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle\"-\n+SubscribeAttitudeAngularVelocityBodyRequest\"x\n#AttitudeAngularVelocityBodyResponse\x12Q\n\x1e\x61ttitude_angular_velocity_body\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\"\x1d\n\x1bSubscribeVelocityNedRequest\"N\n\x13VelocityNedResponse\x12\x37\n\x0cvelocity_ned\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed\"\x19\n\x17SubscribeGpsInfoRequest\"B\n\x0fGpsInfoResponse\x12/\n\x08gps_info\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.GpsInfo\"\x18\n\x16SubscribeRawGpsRequest\"?\n\x0eRawGpsResponse\x12-\n\x07raw_gps\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.telemetry.RawGps\"\x19\n\x17SubscribeBatteryRequest\"A\n\x0f\x42\x61tteryResponse\x12.\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.Battery\"\x1c\n\x1aSubscribeFlightModeRequest\"K\n\x12\x46lightModeResponse\x12\x35\n\x0b\x66light_mode\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.telemetry.FlightMode\"\x18\n\x16SubscribeHealthRequest\">\n\x0eHealthResponse\x12,\n\x06health\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.telemetry.Health\"\x1a\n\x18SubscribeRcStatusRequest\"E\n\x10RcStatusResponse\x12\x31\n\trc_status\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.RcStatus\"\x1c\n\x1aSubscribeStatusTextRequest\"K\n\x12StatusTextResponse\x12\x35\n\x0bstatus_text\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.StatusText\"\'\n%SubscribeActuatorControlTargetRequest\"m\n\x1d\x41\x63tuatorControlTargetResponse\x12L\n\x17\x61\x63tuator_control_target\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.telemetry.ActuatorControlTarget\"&\n$SubscribeActuatorOutputStatusRequest\"j\n\x1c\x41\x63tuatorOutputStatusResponse\x12J\n\x16\x61\x63tuator_output_status\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.telemetry.ActuatorOutputStatus\"\x1a\n\x18SubscribeOdometryRequest\"D\n\x10OdometryResponse\x12\x30\n\x08odometry\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Odometry\"%\n#SubscribePositionVelocityNedRequest\"g\n\x1bPositionVelocityNedResponse\x12H\n\x15position_velocity_ned\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.PositionVelocityNed\"\x1d\n\x1bSubscribeGroundTruthRequest\"N\n\x13GroundTruthResponse\x12\x37\n\x0cground_truth\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.GroundTruth\"\"\n SubscribeFixedwingMetricsRequest\"]\n\x18\x46ixedwingMetricsResponse\x12\x41\n\x11\x66ixedwing_metrics\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.telemetry.FixedwingMetrics\"\x15\n\x13SubscribeImuRequest\"5\n\x0bImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu\"\x1b\n\x19SubscribeScaledImuRequest\";\n\x11ScaledImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu\"\x18\n\x16SubscribeRawImuRequest\"8\n\x0eRawImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu\"\x1d\n\x1bSubscribeHealthAllOkRequest\"/\n\x13HealthAllOkResponse\x12\x18\n\x10is_health_all_ok\x18\x01 \x01(\x08\"\x1f\n\x1dSubscribeUnixEpochTimeRequest\"(\n\x15UnixEpochTimeResponse\x12\x0f\n\x07time_us\x18\x01 \x01(\x04\" \n\x1eSubscribeDistanceSensorRequest\"W\n\x16\x44istanceSensorResponse\x12=\n\x0f\x64istance_sensor\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry.DistanceSensor\" \n\x1eSubscribeScaledPressureRequest\"W\n\x16ScaledPressureResponse\x12=\n\x0fscaled_pressure\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry.ScaledPressure\"\x19\n\x17SubscribeHeadingRequest\"E\n\x0fHeadingResponse\x12\x32\n\x0bheading_deg\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.Heading\"\x1a\n\x18SubscribeAltitudeRequest\"D\n\x10\x41ltitudeResponse\x12\x30\n\x08\x61ltitude\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Altitude\"\x16\n\x14SubscribeWindRequest\"8\n\x0cWindResponse\x12(\n\x04wind\x18\x01 \x01(\x0b\x32\x1a.mavsdk.rpc.telemetry.Wind\")\n\x16SetRatePositionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRatePositionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"%\n\x12SetRateHomeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"V\n\x13SetRateHomeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"&\n\x13SetRateInAirRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"W\n\x14SetRateInAirResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateLandedStateRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateLandedStateResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"*\n\x17SetRateVtolStateRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"[\n\x18SetRateVtolStateResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\".\n\x1bSetRateAttitudeEulerRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"_\n\x1cSetRateAttitudeEulerResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"3\n SetRateAttitudeQuaternionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"d\n!SetRateAttitudeQuaternionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"<\n)SetRateAttitudeAngularVelocityBodyRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"m\n*SetRateAttitudeAngularVelocityBodyResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"(\n\x15SetRateGpsInfoRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Y\n\x16SetRateGpsInfoResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\'\n\x14SetRateRawGpsRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"(\n\x15SetRateBatteryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Y\n\x16SetRateBatteryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateRcStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateRcStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"6\n#SetRateActuatorControlTargetRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"g\n$SetRateActuatorControlTargetResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"5\n\"SetRateActuatorOutputStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"f\n#SetRateActuatorOutputStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateOdometryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateOdometryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"4\n!SetRatePositionVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"e\n\"SetRatePositionVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateGroundTruthRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateGroundTruthResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"1\n\x1eSetRateFixedwingMetricsRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"b\n\x1fSetRateFixedwingMetricsResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"$\n\x11SetRateImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"U\n\x12SetRateImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"*\n\x17SetRateScaledImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"[\n\x18SetRateScaledImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\'\n\x14SetRateRawImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"X\n\x15SetRateRawImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\".\n\x1bSetRateUnixEpochTimeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"_\n\x1cSetRateUnixEpochTimeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"/\n\x1cSetRateDistanceSensorRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"`\n\x1dSetRateDistanceSensorResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\x1b\n\x19GetGpsGlobalOriginRequest\"\x9f\x01\n\x1aGetGpsGlobalOriginResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\x12@\n\x11gps_global_origin\x18\x02 \x01(\x0b\x32%.mavsdk.rpc.telemetry.GpsGlobalOrigin\")\n\x16SetRateAltitudeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateAltitudeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\'\n\x14SetRateHealthRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"X\n\x15SetRateHealthResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\x95\x01\n\x08Position\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13relative_altitude_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\'\n\x07Heading\x12\x1c\n\x0bheading_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\"r\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04\"s\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x04 \x01(\x04\"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"Y\n\x07GpsInfo\x12\x1d\n\x0enum_satellites\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12/\n\x08\x66ix_type\x18\x02 \x01(\x0e\x32\x1d.mavsdk.rpc.telemetry.FixType\"\xdf\x02\n\x06RawGps\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x04 \x01(\x02\x12\x0c\n\x04hdop\x18\x05 \x01(\x02\x12\x0c\n\x04vdop\x18\x06 \x01(\x02\x12\x14\n\x0cvelocity_m_s\x18\x07 \x01(\x02\x12\x0f\n\x07\x63og_deg\x18\x08 \x01(\x02\x12\x1c\n\x14\x61ltitude_ellipsoid_m\x18\t \x01(\x02\x12 \n\x18horizontal_uncertainty_m\x18\n \x01(\x02\x12\x1e\n\x16vertical_uncertainty_m\x18\x0b \x01(\x02\x12 \n\x18velocity_uncertainty_m_s\x18\x0c \x01(\x02\x12\x1f\n\x17heading_uncertainty_deg\x18\r \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x0e \x01(\x02\"\xae\x02\n\x07\x42\x61ttery\x12\x11\n\x02id\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12!\n\x10temperature_degc\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tvoltage_v\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x11\x63urrent_battery_a\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12%\n\x14\x63\x61pacity_consumed_ah\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x11remaining_percent\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12!\n\x10time_remaining_s\x18\x07 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12?\n\x10\x62\x61ttery_function\x18\x08 \x01(\x0e\x32%.mavsdk.rpc.telemetry.BatteryFunction\"\xb9\x02\n\x06Health\x12.\n\x1bis_gyrometer_calibration_ok\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x32\n\x1fis_accelerometer_calibration_ok\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x31\n\x1eis_magnetometer_calibration_ok\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\'\n\x14is_local_position_ok\x18\x05 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x15is_global_position_ok\x18\x06 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12&\n\x13is_home_position_ok\x18\x07 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1d\n\nis_armable\x18\x08 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\"|\n\x08RcStatus\x12%\n\x12was_available_once\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1f\n\x0cis_available\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x17signal_strength_percent\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"N\n\nStatusText\x12\x32\n\x04type\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.telemetry.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t\"?\n\x15\x41\x63tuatorControlTarget\x12\x14\n\x05group\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x63ontrols\x18\x02 \x03(\x02\"?\n\x14\x41\x63tuatorOutputStatus\x12\x15\n\x06\x61\x63tive\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x61\x63tuator\x18\x02 \x03(\x02\"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02\";\n\x0cVelocityBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02\"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02\"\xec\x04\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x39\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12?\n\x0e\x63hild_frame_id\x18\x03 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12\x39\n\rposition_body\x18\x04 \x01(\x0b\x32\".mavsdk.rpc.telemetry.PositionBody\x12+\n\x01q\x18\x05 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\x12\x39\n\rvelocity_body\x18\x06 \x01(\x0b\x32\".mavsdk.rpc.telemetry.VelocityBody\x12H\n\x15\x61ngular_velocity_body\x18\x07 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\x12\x39\n\x0fpose_covariance\x18\x08 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\x12=\n\x13velocity_covariance\x18\t \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\"j\n\x08MavFrame\x12\x13\n\x0fMAV_FRAME_UNDEF\x10\x00\x12\x16\n\x12MAV_FRAME_BODY_NED\x10\x08\x12\x18\n\x14MAV_FRAME_VISION_NED\x10\x10\x12\x17\n\x13MAV_FRAME_ESTIM_NED\x10\x12\"\xb6\x01\n\x0e\x44istanceSensor\x12#\n\x12minimum_distance_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12maximum_distance_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x63urrent_distance_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x35\n\x0borientation\x18\x04 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle\"\xb0\x01\n\x0eScaledPressure\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x1d\n\x15\x61\x62solute_pressure_hpa\x18\x02 \x01(\x02\x12!\n\x19\x64ifferential_pressure_hpa\x18\x03 \x01(\x02\x12\x17\n\x0ftemperature_deg\x18\x04 \x01(\x02\x12-\n%differential_pressure_temperature_deg\x18\x05 \x01(\x02\"Y\n\x0bPositionNed\x12\x18\n\x07north_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x64own_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"D\n\x0bVelocityNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\"\x7f\n\x13PositionVelocityNed\x12\x33\n\x08position\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.PositionNed\x12\x33\n\x08velocity\x18\x02 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed\"r\n\x0bGroundTruth\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xde\x01\n\x10\x46ixedwingMetrics\x12\x1d\n\x0c\x61irspeed_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13throttle_percentage\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0e\x63limb_rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12 \n\x0fgroundspeed_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bheading_deg\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"i\n\x0f\x41\x63\x63\x65lerationFrd\x12\x1d\n\x0c\x66orward_m_s2\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\nright_m_s2\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tdown_m_s2\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"o\n\x12\x41ngularVelocityFrd\x12\x1e\n\rforward_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"m\n\x10MagneticFieldFrd\x12\x1e\n\rforward_gauss\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_gauss\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_gauss\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\x8b\x02\n\x03Imu\x12?\n\x10\x61\x63\x63\x65leration_frd\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.AccelerationFrd\x12\x46\n\x14\x61ngular_velocity_frd\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry.AngularVelocityFrd\x12\x42\n\x12magnetic_field_frd\x18\x03 \x01(\x0b\x32&.mavsdk.rpc.telemetry.MagneticFieldFrd\x12!\n\x10temperature_degc\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04\"m\n\x0fGpsGlobalOrigin\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\naltitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xe6\x01\n\x08\x41ltitude\x12%\n\x14\x61ltitude_monotonic_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12 \n\x0f\x61ltitude_amsl_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12!\n\x10\x61ltitude_local_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61ltitude_relative_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x61ltitude_terrain_m\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x62ottom_clearance_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xdd\x02\n\x04Wind\x12\x1f\n\x0ewind_x_ned_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0ewind_y_ned_m_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0ewind_z_ned_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x32\n!horizontal_variability_stddev_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x30\n\x1fvertical_variability_stddev_m_s\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13wind_altitude_msl_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x33\n\"horizontal_wind_speed_accuracy_m_s\x18\x07 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x31\n vertical_wind_speed_accuracy_m_s\x18\x08 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xa1\x02\n\x0fTelemetryResult\x12<\n\x06result\x18\x01 \x01(\x0e\x32,.mavsdk.rpc.telemetry.TelemetryResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xbb\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\x16\n\x12RESULT_UNSUPPORTED\x10\x07*\xa4\x01\n\x07\x46ixType\x12\x13\n\x0f\x46IX_TYPE_NO_GPS\x10\x00\x12\x13\n\x0f\x46IX_TYPE_NO_FIX\x10\x01\x12\x13\n\x0f\x46IX_TYPE_FIX_2D\x10\x02\x12\x13\n\x0f\x46IX_TYPE_FIX_3D\x10\x03\x12\x15\n\x11\x46IX_TYPE_FIX_DGPS\x10\x04\x12\x16\n\x12\x46IX_TYPE_RTK_FLOAT\x10\x05\x12\x16\n\x12\x46IX_TYPE_RTK_FIXED\x10\x06*\xa7\x01\n\x0f\x42\x61tteryFunction\x12\x1c\n\x18\x42\x41TTERY_FUNCTION_UNKNOWN\x10\x00\x12\x18\n\x14\x42\x41TTERY_FUNCTION_ALL\x10\x01\x12\x1f\n\x1b\x42\x41TTERY_FUNCTION_PROPULSION\x10\x02\x12\x1d\n\x19\x42\x41TTERY_FUNCTION_AVIONICS\x10\x03\x12\x1c\n\x18\x42\x41TTERY_FUNCTION_PAYLOAD\x10\x04*\x86\x03\n\nFlightMode\x12\x17\n\x13\x46LIGHT_MODE_UNKNOWN\x10\x00\x12\x15\n\x11\x46LIGHT_MODE_READY\x10\x01\x12\x17\n\x13\x46LIGHT_MODE_TAKEOFF\x10\x02\x12\x14\n\x10\x46LIGHT_MODE_HOLD\x10\x03\x12\x17\n\x13\x46LIGHT_MODE_MISSION\x10\x04\x12 \n\x1c\x46LIGHT_MODE_RETURN_TO_LAUNCH\x10\x05\x12\x14\n\x10\x46LIGHT_MODE_LAND\x10\x06\x12\x18\n\x14\x46LIGHT_MODE_OFFBOARD\x10\x07\x12\x19\n\x15\x46LIGHT_MODE_FOLLOW_ME\x10\x08\x12\x16\n\x12\x46LIGHT_MODE_MANUAL\x10\t\x12\x16\n\x12\x46LIGHT_MODE_ALTCTL\x10\n\x12\x16\n\x12\x46LIGHT_MODE_POSCTL\x10\x0b\x12\x14\n\x10\x46LIGHT_MODE_ACRO\x10\x0c\x12\x1a\n\x16\x46LIGHT_MODE_STABILIZED\x10\r\x12\x19\n\x15\x46LIGHT_MODE_RATTITUDE\x10\x0e*\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*\x93\x01\n\x0bLandedState\x12\x18\n\x14LANDED_STATE_UNKNOWN\x10\x00\x12\x1a\n\x16LANDED_STATE_ON_GROUND\x10\x01\x12\x17\n\x13LANDED_STATE_IN_AIR\x10\x02\x12\x1b\n\x17LANDED_STATE_TAKING_OFF\x10\x03\x12\x18\n\x14LANDED_STATE_LANDING\x10\x04*\x8d\x01\n\tVtolState\x12\x18\n\x14VTOL_STATE_UNDEFINED\x10\x00\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_FW\x10\x01\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_MC\x10\x02\x12\x11\n\rVTOL_STATE_MC\x10\x03\x12\x11\n\rVTOL_STATE_FW\x10\x04\x32\x98\x37\n\x10TelemetryService\x12o\n\x11SubscribePosition\x12..mavsdk.rpc.telemetry.SubscribePositionRequest\x1a&.mavsdk.rpc.telemetry.PositionResponse\"\x00\x30\x01\x12\x63\n\rSubscribeHome\x12*.mavsdk.rpc.telemetry.SubscribeHomeRequest\x1a\".mavsdk.rpc.telemetry.HomeResponse\"\x00\x30\x01\x12\x66\n\x0eSubscribeInAir\x12+.mavsdk.rpc.telemetry.SubscribeInAirRequest\x1a#.mavsdk.rpc.telemetry.InAirResponse\"\x00\x30\x01\x12x\n\x14SubscribeLandedState\x12\x31.mavsdk.rpc.telemetry.SubscribeLandedStateRequest\x1a).mavsdk.rpc.telemetry.LandedStateResponse\"\x00\x30\x01\x12\x66\n\x0eSubscribeArmed\x12+.mavsdk.rpc.telemetry.SubscribeArmedRequest\x1a#.mavsdk.rpc.telemetry.ArmedResponse\"\x00\x30\x01\x12r\n\x12SubscribeVtolState\x12/.mavsdk.rpc.telemetry.SubscribeVtolStateRequest\x1a\'.mavsdk.rpc.telemetry.VtolStateResponse\"\x00\x30\x01\x12\x8d\x01\n\x1bSubscribeAttitudeQuaternion\x12\x38.mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest\x1a\x30.mavsdk.rpc.telemetry.AttitudeQuaternionResponse\"\x00\x30\x01\x12~\n\x16SubscribeAttitudeEuler\x12\x33.mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest\x1a+.mavsdk.rpc.telemetry.AttitudeEulerResponse\"\x00\x30\x01\x12\xa8\x01\n$SubscribeAttitudeAngularVelocityBody\x12\x41.mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest\x1a\x39.mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse\"\x00\x30\x01\x12x\n\x14SubscribeVelocityNed\x12\x31.mavsdk.rpc.telemetry.SubscribeVelocityNedRequest\x1a).mavsdk.rpc.telemetry.VelocityNedResponse\"\x00\x30\x01\x12l\n\x10SubscribeGpsInfo\x12-.mavsdk.rpc.telemetry.SubscribeGpsInfoRequest\x1a%.mavsdk.rpc.telemetry.GpsInfoResponse\"\x00\x30\x01\x12i\n\x0fSubscribeRawGps\x12,.mavsdk.rpc.telemetry.SubscribeRawGpsRequest\x1a$.mavsdk.rpc.telemetry.RawGpsResponse\"\x00\x30\x01\x12l\n\x10SubscribeBattery\x12-.mavsdk.rpc.telemetry.SubscribeBatteryRequest\x1a%.mavsdk.rpc.telemetry.BatteryResponse\"\x00\x30\x01\x12u\n\x13SubscribeFlightMode\x12\x30.mavsdk.rpc.telemetry.SubscribeFlightModeRequest\x1a(.mavsdk.rpc.telemetry.FlightModeResponse\"\x00\x30\x01\x12i\n\x0fSubscribeHealth\x12,.mavsdk.rpc.telemetry.SubscribeHealthRequest\x1a$.mavsdk.rpc.telemetry.HealthResponse\"\x00\x30\x01\x12o\n\x11SubscribeRcStatus\x12..mavsdk.rpc.telemetry.SubscribeRcStatusRequest\x1a&.mavsdk.rpc.telemetry.RcStatusResponse\"\x00\x30\x01\x12u\n\x13SubscribeStatusText\x12\x30.mavsdk.rpc.telemetry.SubscribeStatusTextRequest\x1a(.mavsdk.rpc.telemetry.StatusTextResponse\"\x00\x30\x01\x12\x96\x01\n\x1eSubscribeActuatorControlTarget\x12;.mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest\x1a\x33.mavsdk.rpc.telemetry.ActuatorControlTargetResponse\"\x00\x30\x01\x12\x93\x01\n\x1dSubscribeActuatorOutputStatus\x12:.mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest\x1a\x32.mavsdk.rpc.telemetry.ActuatorOutputStatusResponse\"\x00\x30\x01\x12o\n\x11SubscribeOdometry\x12..mavsdk.rpc.telemetry.SubscribeOdometryRequest\x1a&.mavsdk.rpc.telemetry.OdometryResponse\"\x00\x30\x01\x12\x90\x01\n\x1cSubscribePositionVelocityNed\x12\x39.mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest\x1a\x31.mavsdk.rpc.telemetry.PositionVelocityNedResponse\"\x00\x30\x01\x12x\n\x14SubscribeGroundTruth\x12\x31.mavsdk.rpc.telemetry.SubscribeGroundTruthRequest\x1a).mavsdk.rpc.telemetry.GroundTruthResponse\"\x00\x30\x01\x12\x87\x01\n\x19SubscribeFixedwingMetrics\x12\x36.mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest\x1a..mavsdk.rpc.telemetry.FixedwingMetricsResponse\"\x00\x30\x01\x12`\n\x0cSubscribeImu\x12).mavsdk.rpc.telemetry.SubscribeImuRequest\x1a!.mavsdk.rpc.telemetry.ImuResponse\"\x00\x30\x01\x12r\n\x12SubscribeScaledImu\x12/.mavsdk.rpc.telemetry.SubscribeScaledImuRequest\x1a\'.mavsdk.rpc.telemetry.ScaledImuResponse\"\x00\x30\x01\x12i\n\x0fSubscribeRawImu\x12,.mavsdk.rpc.telemetry.SubscribeRawImuRequest\x1a$.mavsdk.rpc.telemetry.RawImuResponse\"\x00\x30\x01\x12x\n\x14SubscribeHealthAllOk\x12\x31.mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest\x1a).mavsdk.rpc.telemetry.HealthAllOkResponse\"\x00\x30\x01\x12~\n\x16SubscribeUnixEpochTime\x12\x33.mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest\x1a+.mavsdk.rpc.telemetry.UnixEpochTimeResponse\"\x00\x30\x01\x12\x81\x01\n\x17SubscribeDistanceSensor\x12\x34.mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest\x1a,.mavsdk.rpc.telemetry.DistanceSensorResponse\"\x00\x30\x01\x12\x81\x01\n\x17SubscribeScaledPressure\x12\x34.mavsdk.rpc.telemetry.SubscribeScaledPressureRequest\x1a,.mavsdk.rpc.telemetry.ScaledPressureResponse\"\x00\x30\x01\x12l\n\x10SubscribeHeading\x12-.mavsdk.rpc.telemetry.SubscribeHeadingRequest\x1a%.mavsdk.rpc.telemetry.HeadingResponse\"\x00\x30\x01\x12o\n\x11SubscribeAltitude\x12..mavsdk.rpc.telemetry.SubscribeAltitudeRequest\x1a&.mavsdk.rpc.telemetry.AltitudeResponse\"\x00\x30\x01\x12\x63\n\rSubscribeWind\x12*.mavsdk.rpc.telemetry.SubscribeWindRequest\x1a\".mavsdk.rpc.telemetry.WindResponse\"\x00\x30\x01\x12p\n\x0fSetRatePosition\x12,.mavsdk.rpc.telemetry.SetRatePositionRequest\x1a-.mavsdk.rpc.telemetry.SetRatePositionResponse\"\x00\x12\x64\n\x0bSetRateHome\x12(.mavsdk.rpc.telemetry.SetRateHomeRequest\x1a).mavsdk.rpc.telemetry.SetRateHomeResponse\"\x00\x12g\n\x0cSetRateInAir\x12).mavsdk.rpc.telemetry.SetRateInAirRequest\x1a*.mavsdk.rpc.telemetry.SetRateInAirResponse\"\x00\x12y\n\x12SetRateLandedState\x12/.mavsdk.rpc.telemetry.SetRateLandedStateRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateLandedStateResponse\"\x00\x12s\n\x10SetRateVtolState\x12-.mavsdk.rpc.telemetry.SetRateVtolStateRequest\x1a..mavsdk.rpc.telemetry.SetRateVtolStateResponse\"\x00\x12\x8e\x01\n\x19SetRateAttitudeQuaternion\x12\x36.mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest\x1a\x37.mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse\"\x00\x12\x7f\n\x14SetRateAttitudeEuler\x12\x31.mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest\x1a\x32.mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse\"\x00\x12y\n\x12SetRateVelocityNed\x12/.mavsdk.rpc.telemetry.SetRateVelocityNedRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateVelocityNedResponse\"\x00\x12m\n\x0eSetRateGpsInfo\x12+.mavsdk.rpc.telemetry.SetRateGpsInfoRequest\x1a,.mavsdk.rpc.telemetry.SetRateGpsInfoResponse\"\x00\x12m\n\x0eSetRateBattery\x12+.mavsdk.rpc.telemetry.SetRateBatteryRequest\x1a,.mavsdk.rpc.telemetry.SetRateBatteryResponse\"\x00\x12p\n\x0fSetRateRcStatus\x12,.mavsdk.rpc.telemetry.SetRateRcStatusRequest\x1a-.mavsdk.rpc.telemetry.SetRateRcStatusResponse\"\x00\x12\x97\x01\n\x1cSetRateActuatorControlTarget\x12\x39.mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest\x1a:.mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse\"\x00\x12\x94\x01\n\x1bSetRateActuatorOutputStatus\x12\x38.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest\x1a\x39.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse\"\x00\x12p\n\x0fSetRateOdometry\x12,.mavsdk.rpc.telemetry.SetRateOdometryRequest\x1a-.mavsdk.rpc.telemetry.SetRateOdometryResponse\"\x00\x12\x91\x01\n\x1aSetRatePositionVelocityNed\x12\x37.mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest\x1a\x38.mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse\"\x00\x12y\n\x12SetRateGroundTruth\x12/.mavsdk.rpc.telemetry.SetRateGroundTruthRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateGroundTruthResponse\"\x00\x12\x88\x01\n\x17SetRateFixedwingMetrics\x12\x34.mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest\x1a\x35.mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse\"\x00\x12\x61\n\nSetRateImu\x12\'.mavsdk.rpc.telemetry.SetRateImuRequest\x1a(.mavsdk.rpc.telemetry.SetRateImuResponse\"\x00\x12s\n\x10SetRateScaledImu\x12-.mavsdk.rpc.telemetry.SetRateScaledImuRequest\x1a..mavsdk.rpc.telemetry.SetRateScaledImuResponse\"\x00\x12j\n\rSetRateRawImu\x12*.mavsdk.rpc.telemetry.SetRateRawImuRequest\x1a+.mavsdk.rpc.telemetry.SetRateRawImuResponse\"\x00\x12\x7f\n\x14SetRateUnixEpochTime\x12\x31.mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest\x1a\x32.mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse\"\x00\x12\x82\x01\n\x15SetRateDistanceSensor\x12\x32.mavsdk.rpc.telemetry.SetRateDistanceSensorRequest\x1a\x33.mavsdk.rpc.telemetry.SetRateDistanceSensorResponse\"\x00\x12p\n\x0fSetRateAltitude\x12,.mavsdk.rpc.telemetry.SetRateAltitudeRequest\x1a-.mavsdk.rpc.telemetry.SetRateAltitudeResponse\"\x00\x12j\n\rSetRateHealth\x12*.mavsdk.rpc.telemetry.SetRateHealthRequest\x1a+.mavsdk.rpc.telemetry.SetRateHealthResponse\"\x00\x12y\n\x12GetGpsGlobalOrigin\x12/.mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest\x1a\x30.mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse\"\x00\x42%\n\x13io.mavsdk.telemetryB\x0eTelemetryProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x19telemetry/telemetry.proto\x12\x14mavsdk.rpc.telemetry\x1a\x14mavsdk_options.proto"\x1a\n\x18SubscribePositionRequest"D\n\x10PositionResponse\x12\x30\n\x08position\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position"\x16\n\x14SubscribeHomeRequest"<\n\x0cHomeResponse\x12,\n\x04home\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position"\x17\n\x15SubscribeInAirRequest""\n\rInAirResponse\x12\x11\n\tis_in_air\x18\x01 \x01(\x08"\x1d\n\x1bSubscribeLandedStateRequest"N\n\x13LandedStateResponse\x12\x37\n\x0clanded_state\x18\x01 \x01(\x0e\x32!.mavsdk.rpc.telemetry.LandedState"\x17\n\x15SubscribeArmedRequest"!\n\rArmedResponse\x12\x10\n\x08is_armed\x18\x01 \x01(\x08"\x1b\n\x19SubscribeVtolStateRequest"H\n\x11VtolStateResponse\x12\x33\n\nvtol_state\x18\x01 \x01(\x0e\x32\x1f.mavsdk.rpc.telemetry.VtolState"$\n"SubscribeAttitudeQuaternionRequest"[\n\x1a\x41ttitudeQuaternionResponse\x12=\n\x13\x61ttitude_quaternion\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion"\x1f\n\x1dSubscribeAttitudeEulerRequest"Q\n\x15\x41ttitudeEulerResponse\x12\x38\n\x0e\x61ttitude_euler\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle"-\n+SubscribeAttitudeAngularVelocityBodyRequest"x\n#AttitudeAngularVelocityBodyResponse\x12Q\n\x1e\x61ttitude_angular_velocity_body\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody"\x1d\n\x1bSubscribeVelocityNedRequest"N\n\x13VelocityNedResponse\x12\x37\n\x0cvelocity_ned\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed"\x19\n\x17SubscribeGpsInfoRequest"B\n\x0fGpsInfoResponse\x12/\n\x08gps_info\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.GpsInfo"\x18\n\x16SubscribeRawGpsRequest"?\n\x0eRawGpsResponse\x12-\n\x07raw_gps\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.telemetry.RawGps"\x19\n\x17SubscribeBatteryRequest"A\n\x0f\x42\x61tteryResponse\x12.\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.Battery"\x1c\n\x1aSubscribeFlightModeRequest"K\n\x12\x46lightModeResponse\x12\x35\n\x0b\x66light_mode\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.telemetry.FlightMode"\x18\n\x16SubscribeHealthRequest">\n\x0eHealthResponse\x12,\n\x06health\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.telemetry.Health"\x1a\n\x18SubscribeRcStatusRequest"E\n\x10RcStatusResponse\x12\x31\n\trc_status\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.RcStatus"\x1c\n\x1aSubscribeStatusTextRequest"K\n\x12StatusTextResponse\x12\x35\n\x0bstatus_text\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.StatusText"\'\n%SubscribeActuatorControlTargetRequest"m\n\x1d\x41\x63tuatorControlTargetResponse\x12L\n\x17\x61\x63tuator_control_target\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.telemetry.ActuatorControlTarget"&\n$SubscribeActuatorOutputStatusRequest"j\n\x1c\x41\x63tuatorOutputStatusResponse\x12J\n\x16\x61\x63tuator_output_status\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.telemetry.ActuatorOutputStatus"\x1a\n\x18SubscribeOdometryRequest"D\n\x10OdometryResponse\x12\x30\n\x08odometry\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Odometry"%\n#SubscribePositionVelocityNedRequest"g\n\x1bPositionVelocityNedResponse\x12H\n\x15position_velocity_ned\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.PositionVelocityNed"\x1d\n\x1bSubscribeGroundTruthRequest"N\n\x13GroundTruthResponse\x12\x37\n\x0cground_truth\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.GroundTruth""\n SubscribeFixedwingMetricsRequest"]\n\x18\x46ixedwingMetricsResponse\x12\x41\n\x11\x66ixedwing_metrics\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.telemetry.FixedwingMetrics"\x15\n\x13SubscribeImuRequest"5\n\x0bImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu"\x1b\n\x19SubscribeScaledImuRequest";\n\x11ScaledImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu"\x18\n\x16SubscribeRawImuRequest"8\n\x0eRawImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu"\x1d\n\x1bSubscribeHealthAllOkRequest"/\n\x13HealthAllOkResponse\x12\x18\n\x10is_health_all_ok\x18\x01 \x01(\x08"\x1f\n\x1dSubscribeUnixEpochTimeRequest"(\n\x15UnixEpochTimeResponse\x12\x0f\n\x07time_us\x18\x01 \x01(\x04" \n\x1eSubscribeDistanceSensorRequest"W\n\x16\x44istanceSensorResponse\x12=\n\x0f\x64istance_sensor\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry.DistanceSensor" \n\x1eSubscribeScaledPressureRequest"W\n\x16ScaledPressureResponse\x12=\n\x0fscaled_pressure\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry.ScaledPressure"\x19\n\x17SubscribeHeadingRequest"E\n\x0fHeadingResponse\x12\x32\n\x0bheading_deg\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.Heading"\x1a\n\x18SubscribeAltitudeRequest"D\n\x10\x41ltitudeResponse\x12\x30\n\x08\x61ltitude\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Altitude"\x16\n\x14SubscribeWindRequest"8\n\x0cWindResponse\x12(\n\x04wind\x18\x01 \x01(\x0b\x32\x1a.mavsdk.rpc.telemetry.Wind")\n\x16SetRatePositionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"Z\n\x17SetRatePositionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"%\n\x12SetRateHomeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"V\n\x13SetRateHomeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"&\n\x13SetRateInAirRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"W\n\x14SetRateInAirResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult",\n\x19SetRateLandedStateRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"]\n\x1aSetRateLandedStateResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"*\n\x17SetRateVtolStateRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"[\n\x18SetRateVtolStateResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult".\n\x1bSetRateAttitudeEulerRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"_\n\x1cSetRateAttitudeEulerResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"3\n SetRateAttitudeQuaternionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"d\n!SetRateAttitudeQuaternionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"<\n)SetRateAttitudeAngularVelocityBodyRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"m\n*SetRateAttitudeAngularVelocityBodyResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult",\n\x19SetRateVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"]\n\x1aSetRateVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"(\n\x15SetRateGpsInfoRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"Y\n\x16SetRateGpsInfoResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"\'\n\x14SetRateRawGpsRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"(\n\x15SetRateBatteryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"Y\n\x16SetRateBatteryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult")\n\x16SetRateRcStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"Z\n\x17SetRateRcStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"6\n#SetRateActuatorControlTargetRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"g\n$SetRateActuatorControlTargetResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"5\n"SetRateActuatorOutputStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"f\n#SetRateActuatorOutputStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult")\n\x16SetRateOdometryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"Z\n\x17SetRateOdometryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"4\n!SetRatePositionVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"e\n"SetRatePositionVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult",\n\x19SetRateGroundTruthRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"]\n\x1aSetRateGroundTruthResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"1\n\x1eSetRateFixedwingMetricsRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"b\n\x1fSetRateFixedwingMetricsResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"$\n\x11SetRateImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"U\n\x12SetRateImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"*\n\x17SetRateScaledImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"[\n\x18SetRateScaledImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"\'\n\x14SetRateRawImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"X\n\x15SetRateRawImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult".\n\x1bSetRateUnixEpochTimeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"_\n\x1cSetRateUnixEpochTimeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"/\n\x1cSetRateDistanceSensorRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"`\n\x1dSetRateDistanceSensorResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"\x1b\n\x19GetGpsGlobalOriginRequest"\x9f\x01\n\x1aGetGpsGlobalOriginResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\x12@\n\x11gps_global_origin\x18\x02 \x01(\x0b\x32%.mavsdk.rpc.telemetry.GpsGlobalOrigin")\n\x16SetRateAltitudeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"Z\n\x17SetRateAltitudeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"\'\n\x14SetRateHealthRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"X\n\x15SetRateHealthResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult"\x95\x01\n\x08Position\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13relative_altitude_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\'\n\x07Heading\x12\x1c\n\x0bheading_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN"r\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04"s\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x04 \x01(\x04"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"Y\n\x07GpsInfo\x12\x1d\n\x0enum_satellites\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12/\n\x08\x66ix_type\x18\x02 \x01(\x0e\x32\x1d.mavsdk.rpc.telemetry.FixType"\xdf\x02\n\x06RawGps\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x04 \x01(\x02\x12\x0c\n\x04hdop\x18\x05 \x01(\x02\x12\x0c\n\x04vdop\x18\x06 \x01(\x02\x12\x14\n\x0cvelocity_m_s\x18\x07 \x01(\x02\x12\x0f\n\x07\x63og_deg\x18\x08 \x01(\x02\x12\x1c\n\x14\x61ltitude_ellipsoid_m\x18\t \x01(\x02\x12 \n\x18horizontal_uncertainty_m\x18\n \x01(\x02\x12\x1e\n\x16vertical_uncertainty_m\x18\x0b \x01(\x02\x12 \n\x18velocity_uncertainty_m_s\x18\x0c \x01(\x02\x12\x1f\n\x17heading_uncertainty_deg\x18\r \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x0e \x01(\x02"\xae\x02\n\x07\x42\x61ttery\x12\x11\n\x02id\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12!\n\x10temperature_degc\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tvoltage_v\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12"\n\x11\x63urrent_battery_a\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12%\n\x14\x63\x61pacity_consumed_ah\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12"\n\x11remaining_percent\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12!\n\x10time_remaining_s\x18\x07 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12?\n\x10\x62\x61ttery_function\x18\x08 \x01(\x0e\x32%.mavsdk.rpc.telemetry.BatteryFunction"\xb9\x02\n\x06Health\x12.\n\x1bis_gyrometer_calibration_ok\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x32\n\x1fis_accelerometer_calibration_ok\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x31\n\x1eis_magnetometer_calibration_ok\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\'\n\x14is_local_position_ok\x18\x05 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x15is_global_position_ok\x18\x06 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12&\n\x13is_home_position_ok\x18\x07 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1d\n\nis_armable\x18\x08 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse"|\n\x08RcStatus\x12%\n\x12was_available_once\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1f\n\x0cis_available\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x17signal_strength_percent\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"N\n\nStatusText\x12\x32\n\x04type\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.telemetry.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t"?\n\x15\x41\x63tuatorControlTarget\x12\x14\n\x05group\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x63ontrols\x18\x02 \x03(\x02"?\n\x14\x41\x63tuatorOutputStatus\x12\x15\n\x06\x61\x63tive\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x61\x63tuator\x18\x02 \x03(\x02"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02";\n\x0cVelocityBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02"\xec\x04\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x39\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12?\n\x0e\x63hild_frame_id\x18\x03 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12\x39\n\rposition_body\x18\x04 \x01(\x0b\x32".mavsdk.rpc.telemetry.PositionBody\x12+\n\x01q\x18\x05 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\x12\x39\n\rvelocity_body\x18\x06 \x01(\x0b\x32".mavsdk.rpc.telemetry.VelocityBody\x12H\n\x15\x61ngular_velocity_body\x18\x07 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\x12\x39\n\x0fpose_covariance\x18\x08 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\x12=\n\x13velocity_covariance\x18\t \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance"j\n\x08MavFrame\x12\x13\n\x0fMAV_FRAME_UNDEF\x10\x00\x12\x16\n\x12MAV_FRAME_BODY_NED\x10\x08\x12\x18\n\x14MAV_FRAME_VISION_NED\x10\x10\x12\x17\n\x13MAV_FRAME_ESTIM_NED\x10\x12"\xb6\x01\n\x0e\x44istanceSensor\x12#\n\x12minimum_distance_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12maximum_distance_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x63urrent_distance_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x35\n\x0borientation\x18\x04 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle"\xb0\x01\n\x0eScaledPressure\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x1d\n\x15\x61\x62solute_pressure_hpa\x18\x02 \x01(\x02\x12!\n\x19\x64ifferential_pressure_hpa\x18\x03 \x01(\x02\x12\x17\n\x0ftemperature_deg\x18\x04 \x01(\x02\x12-\n%differential_pressure_temperature_deg\x18\x05 \x01(\x02"Y\n\x0bPositionNed\x12\x18\n\x07north_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x64own_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"D\n\x0bVelocityNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02"\x7f\n\x13PositionVelocityNed\x12\x33\n\x08position\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.PositionNed\x12\x33\n\x08velocity\x18\x02 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed"r\n\x0bGroundTruth\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xde\x01\n\x10\x46ixedwingMetrics\x12\x1d\n\x0c\x61irspeed_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13throttle_percentage\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0e\x63limb_rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12 \n\x0fgroundspeed_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bheading_deg\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"i\n\x0f\x41\x63\x63\x65lerationFrd\x12\x1d\n\x0c\x66orward_m_s2\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\nright_m_s2\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tdown_m_s2\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"o\n\x12\x41ngularVelocityFrd\x12\x1e\n\rforward_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"m\n\x10MagneticFieldFrd\x12\x1e\n\rforward_gauss\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_gauss\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_gauss\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\x8b\x02\n\x03Imu\x12?\n\x10\x61\x63\x63\x65leration_frd\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.AccelerationFrd\x12\x46\n\x14\x61ngular_velocity_frd\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry.AngularVelocityFrd\x12\x42\n\x12magnetic_field_frd\x18\x03 \x01(\x0b\x32&.mavsdk.rpc.telemetry.MagneticFieldFrd\x12!\n\x10temperature_degc\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04"m\n\x0fGpsGlobalOrigin\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\naltitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xe6\x01\n\x08\x41ltitude\x12%\n\x14\x61ltitude_monotonic_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12 \n\x0f\x61ltitude_amsl_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12!\n\x10\x61ltitude_local_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61ltitude_relative_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x61ltitude_terrain_m\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x62ottom_clearance_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xdd\x02\n\x04Wind\x12\x1f\n\x0ewind_x_ned_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0ewind_y_ned_m_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0ewind_z_ned_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x32\n!horizontal_variability_stddev_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x30\n\x1fvertical_variability_stddev_m_s\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13wind_altitude_msl_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x33\n"horizontal_wind_speed_accuracy_m_s\x18\x07 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x31\n vertical_wind_speed_accuracy_m_s\x18\x08 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xa1\x02\n\x0fTelemetryResult\x12<\n\x06result\x18\x01 \x01(\x0e\x32,.mavsdk.rpc.telemetry.TelemetryResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xbb\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\x16\n\x12RESULT_UNSUPPORTED\x10\x07*\xa4\x01\n\x07\x46ixType\x12\x13\n\x0f\x46IX_TYPE_NO_GPS\x10\x00\x12\x13\n\x0f\x46IX_TYPE_NO_FIX\x10\x01\x12\x13\n\x0f\x46IX_TYPE_FIX_2D\x10\x02\x12\x13\n\x0f\x46IX_TYPE_FIX_3D\x10\x03\x12\x15\n\x11\x46IX_TYPE_FIX_DGPS\x10\x04\x12\x16\n\x12\x46IX_TYPE_RTK_FLOAT\x10\x05\x12\x16\n\x12\x46IX_TYPE_RTK_FIXED\x10\x06*\xa7\x01\n\x0f\x42\x61tteryFunction\x12\x1c\n\x18\x42\x41TTERY_FUNCTION_UNKNOWN\x10\x00\x12\x18\n\x14\x42\x41TTERY_FUNCTION_ALL\x10\x01\x12\x1f\n\x1b\x42\x41TTERY_FUNCTION_PROPULSION\x10\x02\x12\x1d\n\x19\x42\x41TTERY_FUNCTION_AVIONICS\x10\x03\x12\x1c\n\x18\x42\x41TTERY_FUNCTION_PAYLOAD\x10\x04*\x86\x03\n\nFlightMode\x12\x17\n\x13\x46LIGHT_MODE_UNKNOWN\x10\x00\x12\x15\n\x11\x46LIGHT_MODE_READY\x10\x01\x12\x17\n\x13\x46LIGHT_MODE_TAKEOFF\x10\x02\x12\x14\n\x10\x46LIGHT_MODE_HOLD\x10\x03\x12\x17\n\x13\x46LIGHT_MODE_MISSION\x10\x04\x12 \n\x1c\x46LIGHT_MODE_RETURN_TO_LAUNCH\x10\x05\x12\x14\n\x10\x46LIGHT_MODE_LAND\x10\x06\x12\x18\n\x14\x46LIGHT_MODE_OFFBOARD\x10\x07\x12\x19\n\x15\x46LIGHT_MODE_FOLLOW_ME\x10\x08\x12\x16\n\x12\x46LIGHT_MODE_MANUAL\x10\t\x12\x16\n\x12\x46LIGHT_MODE_ALTCTL\x10\n\x12\x16\n\x12\x46LIGHT_MODE_POSCTL\x10\x0b\x12\x14\n\x10\x46LIGHT_MODE_ACRO\x10\x0c\x12\x1a\n\x16\x46LIGHT_MODE_STABILIZED\x10\r\x12\x19\n\x15\x46LIGHT_MODE_RATTITUDE\x10\x0e*\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*\x93\x01\n\x0bLandedState\x12\x18\n\x14LANDED_STATE_UNKNOWN\x10\x00\x12\x1a\n\x16LANDED_STATE_ON_GROUND\x10\x01\x12\x17\n\x13LANDED_STATE_IN_AIR\x10\x02\x12\x1b\n\x17LANDED_STATE_TAKING_OFF\x10\x03\x12\x18\n\x14LANDED_STATE_LANDING\x10\x04*\x8d\x01\n\tVtolState\x12\x18\n\x14VTOL_STATE_UNDEFINED\x10\x00\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_FW\x10\x01\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_MC\x10\x02\x12\x11\n\rVTOL_STATE_MC\x10\x03\x12\x11\n\rVTOL_STATE_FW\x10\x04\x32\x98\x37\n\x10TelemetryService\x12o\n\x11SubscribePosition\x12..mavsdk.rpc.telemetry.SubscribePositionRequest\x1a&.mavsdk.rpc.telemetry.PositionResponse"\x00\x30\x01\x12\x63\n\rSubscribeHome\x12*.mavsdk.rpc.telemetry.SubscribeHomeRequest\x1a".mavsdk.rpc.telemetry.HomeResponse"\x00\x30\x01\x12\x66\n\x0eSubscribeInAir\x12+.mavsdk.rpc.telemetry.SubscribeInAirRequest\x1a#.mavsdk.rpc.telemetry.InAirResponse"\x00\x30\x01\x12x\n\x14SubscribeLandedState\x12\x31.mavsdk.rpc.telemetry.SubscribeLandedStateRequest\x1a).mavsdk.rpc.telemetry.LandedStateResponse"\x00\x30\x01\x12\x66\n\x0eSubscribeArmed\x12+.mavsdk.rpc.telemetry.SubscribeArmedRequest\x1a#.mavsdk.rpc.telemetry.ArmedResponse"\x00\x30\x01\x12r\n\x12SubscribeVtolState\x12/.mavsdk.rpc.telemetry.SubscribeVtolStateRequest\x1a\'.mavsdk.rpc.telemetry.VtolStateResponse"\x00\x30\x01\x12\x8d\x01\n\x1bSubscribeAttitudeQuaternion\x12\x38.mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest\x1a\x30.mavsdk.rpc.telemetry.AttitudeQuaternionResponse"\x00\x30\x01\x12~\n\x16SubscribeAttitudeEuler\x12\x33.mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest\x1a+.mavsdk.rpc.telemetry.AttitudeEulerResponse"\x00\x30\x01\x12\xa8\x01\n$SubscribeAttitudeAngularVelocityBody\x12\x41.mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest\x1a\x39.mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse"\x00\x30\x01\x12x\n\x14SubscribeVelocityNed\x12\x31.mavsdk.rpc.telemetry.SubscribeVelocityNedRequest\x1a).mavsdk.rpc.telemetry.VelocityNedResponse"\x00\x30\x01\x12l\n\x10SubscribeGpsInfo\x12-.mavsdk.rpc.telemetry.SubscribeGpsInfoRequest\x1a%.mavsdk.rpc.telemetry.GpsInfoResponse"\x00\x30\x01\x12i\n\x0fSubscribeRawGps\x12,.mavsdk.rpc.telemetry.SubscribeRawGpsRequest\x1a$.mavsdk.rpc.telemetry.RawGpsResponse"\x00\x30\x01\x12l\n\x10SubscribeBattery\x12-.mavsdk.rpc.telemetry.SubscribeBatteryRequest\x1a%.mavsdk.rpc.telemetry.BatteryResponse"\x00\x30\x01\x12u\n\x13SubscribeFlightMode\x12\x30.mavsdk.rpc.telemetry.SubscribeFlightModeRequest\x1a(.mavsdk.rpc.telemetry.FlightModeResponse"\x00\x30\x01\x12i\n\x0fSubscribeHealth\x12,.mavsdk.rpc.telemetry.SubscribeHealthRequest\x1a$.mavsdk.rpc.telemetry.HealthResponse"\x00\x30\x01\x12o\n\x11SubscribeRcStatus\x12..mavsdk.rpc.telemetry.SubscribeRcStatusRequest\x1a&.mavsdk.rpc.telemetry.RcStatusResponse"\x00\x30\x01\x12u\n\x13SubscribeStatusText\x12\x30.mavsdk.rpc.telemetry.SubscribeStatusTextRequest\x1a(.mavsdk.rpc.telemetry.StatusTextResponse"\x00\x30\x01\x12\x96\x01\n\x1eSubscribeActuatorControlTarget\x12;.mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest\x1a\x33.mavsdk.rpc.telemetry.ActuatorControlTargetResponse"\x00\x30\x01\x12\x93\x01\n\x1dSubscribeActuatorOutputStatus\x12:.mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest\x1a\x32.mavsdk.rpc.telemetry.ActuatorOutputStatusResponse"\x00\x30\x01\x12o\n\x11SubscribeOdometry\x12..mavsdk.rpc.telemetry.SubscribeOdometryRequest\x1a&.mavsdk.rpc.telemetry.OdometryResponse"\x00\x30\x01\x12\x90\x01\n\x1cSubscribePositionVelocityNed\x12\x39.mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest\x1a\x31.mavsdk.rpc.telemetry.PositionVelocityNedResponse"\x00\x30\x01\x12x\n\x14SubscribeGroundTruth\x12\x31.mavsdk.rpc.telemetry.SubscribeGroundTruthRequest\x1a).mavsdk.rpc.telemetry.GroundTruthResponse"\x00\x30\x01\x12\x87\x01\n\x19SubscribeFixedwingMetrics\x12\x36.mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest\x1a..mavsdk.rpc.telemetry.FixedwingMetricsResponse"\x00\x30\x01\x12`\n\x0cSubscribeImu\x12).mavsdk.rpc.telemetry.SubscribeImuRequest\x1a!.mavsdk.rpc.telemetry.ImuResponse"\x00\x30\x01\x12r\n\x12SubscribeScaledImu\x12/.mavsdk.rpc.telemetry.SubscribeScaledImuRequest\x1a\'.mavsdk.rpc.telemetry.ScaledImuResponse"\x00\x30\x01\x12i\n\x0fSubscribeRawImu\x12,.mavsdk.rpc.telemetry.SubscribeRawImuRequest\x1a$.mavsdk.rpc.telemetry.RawImuResponse"\x00\x30\x01\x12x\n\x14SubscribeHealthAllOk\x12\x31.mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest\x1a).mavsdk.rpc.telemetry.HealthAllOkResponse"\x00\x30\x01\x12~\n\x16SubscribeUnixEpochTime\x12\x33.mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest\x1a+.mavsdk.rpc.telemetry.UnixEpochTimeResponse"\x00\x30\x01\x12\x81\x01\n\x17SubscribeDistanceSensor\x12\x34.mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest\x1a,.mavsdk.rpc.telemetry.DistanceSensorResponse"\x00\x30\x01\x12\x81\x01\n\x17SubscribeScaledPressure\x12\x34.mavsdk.rpc.telemetry.SubscribeScaledPressureRequest\x1a,.mavsdk.rpc.telemetry.ScaledPressureResponse"\x00\x30\x01\x12l\n\x10SubscribeHeading\x12-.mavsdk.rpc.telemetry.SubscribeHeadingRequest\x1a%.mavsdk.rpc.telemetry.HeadingResponse"\x00\x30\x01\x12o\n\x11SubscribeAltitude\x12..mavsdk.rpc.telemetry.SubscribeAltitudeRequest\x1a&.mavsdk.rpc.telemetry.AltitudeResponse"\x00\x30\x01\x12\x63\n\rSubscribeWind\x12*.mavsdk.rpc.telemetry.SubscribeWindRequest\x1a".mavsdk.rpc.telemetry.WindResponse"\x00\x30\x01\x12p\n\x0fSetRatePosition\x12,.mavsdk.rpc.telemetry.SetRatePositionRequest\x1a-.mavsdk.rpc.telemetry.SetRatePositionResponse"\x00\x12\x64\n\x0bSetRateHome\x12(.mavsdk.rpc.telemetry.SetRateHomeRequest\x1a).mavsdk.rpc.telemetry.SetRateHomeResponse"\x00\x12g\n\x0cSetRateInAir\x12).mavsdk.rpc.telemetry.SetRateInAirRequest\x1a*.mavsdk.rpc.telemetry.SetRateInAirResponse"\x00\x12y\n\x12SetRateLandedState\x12/.mavsdk.rpc.telemetry.SetRateLandedStateRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateLandedStateResponse"\x00\x12s\n\x10SetRateVtolState\x12-.mavsdk.rpc.telemetry.SetRateVtolStateRequest\x1a..mavsdk.rpc.telemetry.SetRateVtolStateResponse"\x00\x12\x8e\x01\n\x19SetRateAttitudeQuaternion\x12\x36.mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest\x1a\x37.mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse"\x00\x12\x7f\n\x14SetRateAttitudeEuler\x12\x31.mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest\x1a\x32.mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse"\x00\x12y\n\x12SetRateVelocityNed\x12/.mavsdk.rpc.telemetry.SetRateVelocityNedRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateVelocityNedResponse"\x00\x12m\n\x0eSetRateGpsInfo\x12+.mavsdk.rpc.telemetry.SetRateGpsInfoRequest\x1a,.mavsdk.rpc.telemetry.SetRateGpsInfoResponse"\x00\x12m\n\x0eSetRateBattery\x12+.mavsdk.rpc.telemetry.SetRateBatteryRequest\x1a,.mavsdk.rpc.telemetry.SetRateBatteryResponse"\x00\x12p\n\x0fSetRateRcStatus\x12,.mavsdk.rpc.telemetry.SetRateRcStatusRequest\x1a-.mavsdk.rpc.telemetry.SetRateRcStatusResponse"\x00\x12\x97\x01\n\x1cSetRateActuatorControlTarget\x12\x39.mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest\x1a:.mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse"\x00\x12\x94\x01\n\x1bSetRateActuatorOutputStatus\x12\x38.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest\x1a\x39.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse"\x00\x12p\n\x0fSetRateOdometry\x12,.mavsdk.rpc.telemetry.SetRateOdometryRequest\x1a-.mavsdk.rpc.telemetry.SetRateOdometryResponse"\x00\x12\x91\x01\n\x1aSetRatePositionVelocityNed\x12\x37.mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest\x1a\x38.mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse"\x00\x12y\n\x12SetRateGroundTruth\x12/.mavsdk.rpc.telemetry.SetRateGroundTruthRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateGroundTruthResponse"\x00\x12\x88\x01\n\x17SetRateFixedwingMetrics\x12\x34.mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest\x1a\x35.mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse"\x00\x12\x61\n\nSetRateImu\x12\'.mavsdk.rpc.telemetry.SetRateImuRequest\x1a(.mavsdk.rpc.telemetry.SetRateImuResponse"\x00\x12s\n\x10SetRateScaledImu\x12-.mavsdk.rpc.telemetry.SetRateScaledImuRequest\x1a..mavsdk.rpc.telemetry.SetRateScaledImuResponse"\x00\x12j\n\rSetRateRawImu\x12*.mavsdk.rpc.telemetry.SetRateRawImuRequest\x1a+.mavsdk.rpc.telemetry.SetRateRawImuResponse"\x00\x12\x7f\n\x14SetRateUnixEpochTime\x12\x31.mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest\x1a\x32.mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse"\x00\x12\x82\x01\n\x15SetRateDistanceSensor\x12\x32.mavsdk.rpc.telemetry.SetRateDistanceSensorRequest\x1a\x33.mavsdk.rpc.telemetry.SetRateDistanceSensorResponse"\x00\x12p\n\x0fSetRateAltitude\x12,.mavsdk.rpc.telemetry.SetRateAltitudeRequest\x1a-.mavsdk.rpc.telemetry.SetRateAltitudeResponse"\x00\x12j\n\rSetRateHealth\x12*.mavsdk.rpc.telemetry.SetRateHealthRequest\x1a+.mavsdk.rpc.telemetry.SetRateHealthResponse"\x00\x12y\n\x12GetGpsGlobalOrigin\x12/.mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest\x1a\x30.mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse"\x00\x42%\n\x13io.mavsdk.telemetryB\x0eTelemetryProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'telemetry.telemetry_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "telemetry.telemetry_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\023io.mavsdk.telemetryB\016TelemetryProto' - _globals['_POSITION'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_POSITION'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITION'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_POSITION'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITION'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_POSITION'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITION'].fields_by_name['relative_altitude_m']._loaded_options = None - _globals['_POSITION'].fields_by_name['relative_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_HEADING'].fields_by_name['heading_deg']._loaded_options = None - _globals['_HEADING'].fields_by_name['heading_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['w']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['w']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['x']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['x']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['y']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['y']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['z']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['z']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['roll_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['roll_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['pitch_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['pitch_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['yaw_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['yaw_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['roll_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['roll_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['pitch_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['pitch_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['yaw_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['yaw_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_GPSINFO'].fields_by_name['num_satellites']._loaded_options = None - _globals['_GPSINFO'].fields_by_name['num_satellites']._serialized_options = b'\202\265\030\0010' - _globals['_BATTERY'].fields_by_name['id']._loaded_options = None - _globals['_BATTERY'].fields_by_name['id']._serialized_options = b'\202\265\030\0010' - _globals['_BATTERY'].fields_by_name['temperature_degc']._loaded_options = None - _globals['_BATTERY'].fields_by_name['temperature_degc']._serialized_options = b'\202\265\030\003NaN' - _globals['_BATTERY'].fields_by_name['voltage_v']._loaded_options = None - _globals['_BATTERY'].fields_by_name['voltage_v']._serialized_options = b'\202\265\030\003NaN' - _globals['_BATTERY'].fields_by_name['current_battery_a']._loaded_options = None - _globals['_BATTERY'].fields_by_name['current_battery_a']._serialized_options = b'\202\265\030\003NaN' - _globals['_BATTERY'].fields_by_name['capacity_consumed_ah']._loaded_options = None - _globals['_BATTERY'].fields_by_name['capacity_consumed_ah']._serialized_options = b'\202\265\030\003NaN' - _globals['_BATTERY'].fields_by_name['remaining_percent']._loaded_options = None - _globals['_BATTERY'].fields_by_name['remaining_percent']._serialized_options = b'\202\265\030\003NaN' - _globals['_BATTERY'].fields_by_name['time_remaining_s']._loaded_options = None - _globals['_BATTERY'].fields_by_name['time_remaining_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_HEALTH'].fields_by_name['is_gyrometer_calibration_ok']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_gyrometer_calibration_ok']._serialized_options = b'\202\265\030\005false' - _globals['_HEALTH'].fields_by_name['is_accelerometer_calibration_ok']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_accelerometer_calibration_ok']._serialized_options = b'\202\265\030\005false' - _globals['_HEALTH'].fields_by_name['is_magnetometer_calibration_ok']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_magnetometer_calibration_ok']._serialized_options = b'\202\265\030\005false' - _globals['_HEALTH'].fields_by_name['is_local_position_ok']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_local_position_ok']._serialized_options = b'\202\265\030\005false' - _globals['_HEALTH'].fields_by_name['is_global_position_ok']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_global_position_ok']._serialized_options = b'\202\265\030\005false' - _globals['_HEALTH'].fields_by_name['is_home_position_ok']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_home_position_ok']._serialized_options = b'\202\265\030\005false' - _globals['_HEALTH'].fields_by_name['is_armable']._loaded_options = None - _globals['_HEALTH'].fields_by_name['is_armable']._serialized_options = b'\202\265\030\005false' - _globals['_RCSTATUS'].fields_by_name['was_available_once']._loaded_options = None - _globals['_RCSTATUS'].fields_by_name['was_available_once']._serialized_options = b'\202\265\030\005false' - _globals['_RCSTATUS'].fields_by_name['is_available']._loaded_options = None - _globals['_RCSTATUS'].fields_by_name['is_available']._serialized_options = b'\202\265\030\005false' - _globals['_RCSTATUS'].fields_by_name['signal_strength_percent']._loaded_options = None - _globals['_RCSTATUS'].fields_by_name['signal_strength_percent']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACTUATORCONTROLTARGET'].fields_by_name['group']._loaded_options = None - _globals['_ACTUATORCONTROLTARGET'].fields_by_name['group']._serialized_options = b'\202\265\030\0010' - _globals['_ACTUATOROUTPUTSTATUS'].fields_by_name['active']._loaded_options = None - _globals['_ACTUATOROUTPUTSTATUS'].fields_by_name['active']._serialized_options = b'\202\265\030\0010' - _globals['_DISTANCESENSOR'].fields_by_name['minimum_distance_m']._loaded_options = None - _globals['_DISTANCESENSOR'].fields_by_name['minimum_distance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_DISTANCESENSOR'].fields_by_name['maximum_distance_m']._loaded_options = None - _globals['_DISTANCESENSOR'].fields_by_name['maximum_distance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_DISTANCESENSOR'].fields_by_name['current_distance_m']._loaded_options = None - _globals['_DISTANCESENSOR'].fields_by_name['current_distance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITIONNED'].fields_by_name['north_m']._loaded_options = None - _globals['_POSITIONNED'].fields_by_name['north_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITIONNED'].fields_by_name['east_m']._loaded_options = None - _globals['_POSITIONNED'].fields_by_name['east_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITIONNED'].fields_by_name['down_m']._loaded_options = None - _globals['_POSITIONNED'].fields_by_name['down_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_GROUNDTRUTH'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_GROUNDTRUTH'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_GROUNDTRUTH'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_GROUNDTRUTH'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_GROUNDTRUTH'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_GROUNDTRUTH'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['airspeed_m_s']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['airspeed_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['throttle_percentage']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['throttle_percentage']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['climb_rate_m_s']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['climb_rate_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['groundspeed_m_s']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['groundspeed_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['heading_deg']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['heading_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACCELERATIONFRD'].fields_by_name['forward_m_s2']._loaded_options = None - _globals['_ACCELERATIONFRD'].fields_by_name['forward_m_s2']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACCELERATIONFRD'].fields_by_name['right_m_s2']._loaded_options = None - _globals['_ACCELERATIONFRD'].fields_by_name['right_m_s2']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACCELERATIONFRD'].fields_by_name['down_m_s2']._loaded_options = None - _globals['_ACCELERATIONFRD'].fields_by_name['down_m_s2']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYFRD'].fields_by_name['forward_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYFRD'].fields_by_name['forward_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYFRD'].fields_by_name['right_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYFRD'].fields_by_name['right_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYFRD'].fields_by_name['down_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYFRD'].fields_by_name['down_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_MAGNETICFIELDFRD'].fields_by_name['forward_gauss']._loaded_options = None - _globals['_MAGNETICFIELDFRD'].fields_by_name['forward_gauss']._serialized_options = b'\202\265\030\003NaN' - _globals['_MAGNETICFIELDFRD'].fields_by_name['right_gauss']._loaded_options = None - _globals['_MAGNETICFIELDFRD'].fields_by_name['right_gauss']._serialized_options = b'\202\265\030\003NaN' - _globals['_MAGNETICFIELDFRD'].fields_by_name['down_gauss']._loaded_options = None - _globals['_MAGNETICFIELDFRD'].fields_by_name['down_gauss']._serialized_options = b'\202\265\030\003NaN' - _globals['_IMU'].fields_by_name['temperature_degc']._loaded_options = None - _globals['_IMU'].fields_by_name['temperature_degc']._serialized_options = b'\202\265\030\003NaN' - _globals['_GPSGLOBALORIGIN'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_GPSGLOBALORIGIN'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_GPSGLOBALORIGIN'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_GPSGLOBALORIGIN'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_GPSGLOBALORIGIN'].fields_by_name['altitude_m']._loaded_options = None - _globals['_GPSGLOBALORIGIN'].fields_by_name['altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ALTITUDE'].fields_by_name['altitude_monotonic_m']._loaded_options = None - _globals['_ALTITUDE'].fields_by_name['altitude_monotonic_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ALTITUDE'].fields_by_name['altitude_amsl_m']._loaded_options = None - _globals['_ALTITUDE'].fields_by_name['altitude_amsl_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ALTITUDE'].fields_by_name['altitude_local_m']._loaded_options = None - _globals['_ALTITUDE'].fields_by_name['altitude_local_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ALTITUDE'].fields_by_name['altitude_relative_m']._loaded_options = None - _globals['_ALTITUDE'].fields_by_name['altitude_relative_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ALTITUDE'].fields_by_name['altitude_terrain_m']._loaded_options = None - _globals['_ALTITUDE'].fields_by_name['altitude_terrain_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ALTITUDE'].fields_by_name['bottom_clearance_m']._loaded_options = None - _globals['_ALTITUDE'].fields_by_name['bottom_clearance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['wind_x_ned_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['wind_x_ned_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['wind_y_ned_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['wind_y_ned_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['wind_z_ned_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['wind_z_ned_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['horizontal_variability_stddev_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['horizontal_variability_stddev_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['vertical_variability_stddev_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['vertical_variability_stddev_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['wind_altitude_msl_m']._loaded_options = None - _globals['_WIND'].fields_by_name['wind_altitude_msl_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['horizontal_wind_speed_accuracy_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['horizontal_wind_speed_accuracy_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WIND'].fields_by_name['vertical_wind_speed_accuracy_m_s']._loaded_options = None - _globals['_WIND'].fields_by_name['vertical_wind_speed_accuracy_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXTYPE']._serialized_start=12591 - _globals['_FIXTYPE']._serialized_end=12755 - _globals['_BATTERYFUNCTION']._serialized_start=12758 - _globals['_BATTERYFUNCTION']._serialized_end=12925 - _globals['_FLIGHTMODE']._serialized_start=12928 - _globals['_FLIGHTMODE']._serialized_end=13318 - _globals['_STATUSTEXTTYPE']._serialized_start=13321 - _globals['_STATUSTEXTTYPE']._serialized_end=13570 - _globals['_LANDEDSTATE']._serialized_start=13573 - _globals['_LANDEDSTATE']._serialized_end=13720 - _globals['_VTOLSTATE']._serialized_start=13723 - _globals['_VTOLSTATE']._serialized_end=13864 - _globals['_SUBSCRIBEPOSITIONREQUEST']._serialized_start=73 - _globals['_SUBSCRIBEPOSITIONREQUEST']._serialized_end=99 - _globals['_POSITIONRESPONSE']._serialized_start=101 - _globals['_POSITIONRESPONSE']._serialized_end=169 - _globals['_SUBSCRIBEHOMEREQUEST']._serialized_start=171 - _globals['_SUBSCRIBEHOMEREQUEST']._serialized_end=193 - _globals['_HOMERESPONSE']._serialized_start=195 - _globals['_HOMERESPONSE']._serialized_end=255 - _globals['_SUBSCRIBEINAIRREQUEST']._serialized_start=257 - _globals['_SUBSCRIBEINAIRREQUEST']._serialized_end=280 - _globals['_INAIRRESPONSE']._serialized_start=282 - _globals['_INAIRRESPONSE']._serialized_end=316 - _globals['_SUBSCRIBELANDEDSTATEREQUEST']._serialized_start=318 - _globals['_SUBSCRIBELANDEDSTATEREQUEST']._serialized_end=347 - _globals['_LANDEDSTATERESPONSE']._serialized_start=349 - _globals['_LANDEDSTATERESPONSE']._serialized_end=427 - _globals['_SUBSCRIBEARMEDREQUEST']._serialized_start=429 - _globals['_SUBSCRIBEARMEDREQUEST']._serialized_end=452 - _globals['_ARMEDRESPONSE']._serialized_start=454 - _globals['_ARMEDRESPONSE']._serialized_end=487 - _globals['_SUBSCRIBEVTOLSTATEREQUEST']._serialized_start=489 - _globals['_SUBSCRIBEVTOLSTATEREQUEST']._serialized_end=516 - _globals['_VTOLSTATERESPONSE']._serialized_start=518 - _globals['_VTOLSTATERESPONSE']._serialized_end=590 - _globals['_SUBSCRIBEATTITUDEQUATERNIONREQUEST']._serialized_start=592 - _globals['_SUBSCRIBEATTITUDEQUATERNIONREQUEST']._serialized_end=628 - _globals['_ATTITUDEQUATERNIONRESPONSE']._serialized_start=630 - _globals['_ATTITUDEQUATERNIONRESPONSE']._serialized_end=721 - _globals['_SUBSCRIBEATTITUDEEULERREQUEST']._serialized_start=723 - _globals['_SUBSCRIBEATTITUDEEULERREQUEST']._serialized_end=754 - _globals['_ATTITUDEEULERRESPONSE']._serialized_start=756 - _globals['_ATTITUDEEULERRESPONSE']._serialized_end=837 - _globals['_SUBSCRIBEATTITUDEANGULARVELOCITYBODYREQUEST']._serialized_start=839 - _globals['_SUBSCRIBEATTITUDEANGULARVELOCITYBODYREQUEST']._serialized_end=884 - _globals['_ATTITUDEANGULARVELOCITYBODYRESPONSE']._serialized_start=886 - _globals['_ATTITUDEANGULARVELOCITYBODYRESPONSE']._serialized_end=1006 - _globals['_SUBSCRIBEVELOCITYNEDREQUEST']._serialized_start=1008 - _globals['_SUBSCRIBEVELOCITYNEDREQUEST']._serialized_end=1037 - _globals['_VELOCITYNEDRESPONSE']._serialized_start=1039 - _globals['_VELOCITYNEDRESPONSE']._serialized_end=1117 - _globals['_SUBSCRIBEGPSINFOREQUEST']._serialized_start=1119 - _globals['_SUBSCRIBEGPSINFOREQUEST']._serialized_end=1144 - _globals['_GPSINFORESPONSE']._serialized_start=1146 - _globals['_GPSINFORESPONSE']._serialized_end=1212 - _globals['_SUBSCRIBERAWGPSREQUEST']._serialized_start=1214 - _globals['_SUBSCRIBERAWGPSREQUEST']._serialized_end=1238 - _globals['_RAWGPSRESPONSE']._serialized_start=1240 - _globals['_RAWGPSRESPONSE']._serialized_end=1303 - _globals['_SUBSCRIBEBATTERYREQUEST']._serialized_start=1305 - _globals['_SUBSCRIBEBATTERYREQUEST']._serialized_end=1330 - _globals['_BATTERYRESPONSE']._serialized_start=1332 - _globals['_BATTERYRESPONSE']._serialized_end=1397 - _globals['_SUBSCRIBEFLIGHTMODEREQUEST']._serialized_start=1399 - _globals['_SUBSCRIBEFLIGHTMODEREQUEST']._serialized_end=1427 - _globals['_FLIGHTMODERESPONSE']._serialized_start=1429 - _globals['_FLIGHTMODERESPONSE']._serialized_end=1504 - _globals['_SUBSCRIBEHEALTHREQUEST']._serialized_start=1506 - _globals['_SUBSCRIBEHEALTHREQUEST']._serialized_end=1530 - _globals['_HEALTHRESPONSE']._serialized_start=1532 - _globals['_HEALTHRESPONSE']._serialized_end=1594 - _globals['_SUBSCRIBERCSTATUSREQUEST']._serialized_start=1596 - _globals['_SUBSCRIBERCSTATUSREQUEST']._serialized_end=1622 - _globals['_RCSTATUSRESPONSE']._serialized_start=1624 - _globals['_RCSTATUSRESPONSE']._serialized_end=1693 - _globals['_SUBSCRIBESTATUSTEXTREQUEST']._serialized_start=1695 - _globals['_SUBSCRIBESTATUSTEXTREQUEST']._serialized_end=1723 - _globals['_STATUSTEXTRESPONSE']._serialized_start=1725 - _globals['_STATUSTEXTRESPONSE']._serialized_end=1800 - _globals['_SUBSCRIBEACTUATORCONTROLTARGETREQUEST']._serialized_start=1802 - _globals['_SUBSCRIBEACTUATORCONTROLTARGETREQUEST']._serialized_end=1841 - _globals['_ACTUATORCONTROLTARGETRESPONSE']._serialized_start=1843 - _globals['_ACTUATORCONTROLTARGETRESPONSE']._serialized_end=1952 - _globals['_SUBSCRIBEACTUATOROUTPUTSTATUSREQUEST']._serialized_start=1954 - _globals['_SUBSCRIBEACTUATOROUTPUTSTATUSREQUEST']._serialized_end=1992 - _globals['_ACTUATOROUTPUTSTATUSRESPONSE']._serialized_start=1994 - _globals['_ACTUATOROUTPUTSTATUSRESPONSE']._serialized_end=2100 - _globals['_SUBSCRIBEODOMETRYREQUEST']._serialized_start=2102 - _globals['_SUBSCRIBEODOMETRYREQUEST']._serialized_end=2128 - _globals['_ODOMETRYRESPONSE']._serialized_start=2130 - _globals['_ODOMETRYRESPONSE']._serialized_end=2198 - _globals['_SUBSCRIBEPOSITIONVELOCITYNEDREQUEST']._serialized_start=2200 - _globals['_SUBSCRIBEPOSITIONVELOCITYNEDREQUEST']._serialized_end=2237 - _globals['_POSITIONVELOCITYNEDRESPONSE']._serialized_start=2239 - _globals['_POSITIONVELOCITYNEDRESPONSE']._serialized_end=2342 - _globals['_SUBSCRIBEGROUNDTRUTHREQUEST']._serialized_start=2344 - _globals['_SUBSCRIBEGROUNDTRUTHREQUEST']._serialized_end=2373 - _globals['_GROUNDTRUTHRESPONSE']._serialized_start=2375 - _globals['_GROUNDTRUTHRESPONSE']._serialized_end=2453 - _globals['_SUBSCRIBEFIXEDWINGMETRICSREQUEST']._serialized_start=2455 - _globals['_SUBSCRIBEFIXEDWINGMETRICSREQUEST']._serialized_end=2489 - _globals['_FIXEDWINGMETRICSRESPONSE']._serialized_start=2491 - _globals['_FIXEDWINGMETRICSRESPONSE']._serialized_end=2584 - _globals['_SUBSCRIBEIMUREQUEST']._serialized_start=2586 - _globals['_SUBSCRIBEIMUREQUEST']._serialized_end=2607 - _globals['_IMURESPONSE']._serialized_start=2609 - _globals['_IMURESPONSE']._serialized_end=2662 - _globals['_SUBSCRIBESCALEDIMUREQUEST']._serialized_start=2664 - _globals['_SUBSCRIBESCALEDIMUREQUEST']._serialized_end=2691 - _globals['_SCALEDIMURESPONSE']._serialized_start=2693 - _globals['_SCALEDIMURESPONSE']._serialized_end=2752 - _globals['_SUBSCRIBERAWIMUREQUEST']._serialized_start=2754 - _globals['_SUBSCRIBERAWIMUREQUEST']._serialized_end=2778 - _globals['_RAWIMURESPONSE']._serialized_start=2780 - _globals['_RAWIMURESPONSE']._serialized_end=2836 - _globals['_SUBSCRIBEHEALTHALLOKREQUEST']._serialized_start=2838 - _globals['_SUBSCRIBEHEALTHALLOKREQUEST']._serialized_end=2867 - _globals['_HEALTHALLOKRESPONSE']._serialized_start=2869 - _globals['_HEALTHALLOKRESPONSE']._serialized_end=2916 - _globals['_SUBSCRIBEUNIXEPOCHTIMEREQUEST']._serialized_start=2918 - _globals['_SUBSCRIBEUNIXEPOCHTIMEREQUEST']._serialized_end=2949 - _globals['_UNIXEPOCHTIMERESPONSE']._serialized_start=2951 - _globals['_UNIXEPOCHTIMERESPONSE']._serialized_end=2991 - _globals['_SUBSCRIBEDISTANCESENSORREQUEST']._serialized_start=2993 - _globals['_SUBSCRIBEDISTANCESENSORREQUEST']._serialized_end=3025 - _globals['_DISTANCESENSORRESPONSE']._serialized_start=3027 - _globals['_DISTANCESENSORRESPONSE']._serialized_end=3114 - _globals['_SUBSCRIBESCALEDPRESSUREREQUEST']._serialized_start=3116 - _globals['_SUBSCRIBESCALEDPRESSUREREQUEST']._serialized_end=3148 - _globals['_SCALEDPRESSURERESPONSE']._serialized_start=3150 - _globals['_SCALEDPRESSURERESPONSE']._serialized_end=3237 - _globals['_SUBSCRIBEHEADINGREQUEST']._serialized_start=3239 - _globals['_SUBSCRIBEHEADINGREQUEST']._serialized_end=3264 - _globals['_HEADINGRESPONSE']._serialized_start=3266 - _globals['_HEADINGRESPONSE']._serialized_end=3335 - _globals['_SUBSCRIBEALTITUDEREQUEST']._serialized_start=3337 - _globals['_SUBSCRIBEALTITUDEREQUEST']._serialized_end=3363 - _globals['_ALTITUDERESPONSE']._serialized_start=3365 - _globals['_ALTITUDERESPONSE']._serialized_end=3433 - _globals['_SUBSCRIBEWINDREQUEST']._serialized_start=3435 - _globals['_SUBSCRIBEWINDREQUEST']._serialized_end=3457 - _globals['_WINDRESPONSE']._serialized_start=3459 - _globals['_WINDRESPONSE']._serialized_end=3515 - _globals['_SETRATEPOSITIONREQUEST']._serialized_start=3517 - _globals['_SETRATEPOSITIONREQUEST']._serialized_end=3558 - _globals['_SETRATEPOSITIONRESPONSE']._serialized_start=3560 - _globals['_SETRATEPOSITIONRESPONSE']._serialized_end=3650 - _globals['_SETRATEHOMEREQUEST']._serialized_start=3652 - _globals['_SETRATEHOMEREQUEST']._serialized_end=3689 - _globals['_SETRATEHOMERESPONSE']._serialized_start=3691 - _globals['_SETRATEHOMERESPONSE']._serialized_end=3777 - _globals['_SETRATEINAIRREQUEST']._serialized_start=3779 - _globals['_SETRATEINAIRREQUEST']._serialized_end=3817 - _globals['_SETRATEINAIRRESPONSE']._serialized_start=3819 - _globals['_SETRATEINAIRRESPONSE']._serialized_end=3906 - _globals['_SETRATELANDEDSTATEREQUEST']._serialized_start=3908 - _globals['_SETRATELANDEDSTATEREQUEST']._serialized_end=3952 - _globals['_SETRATELANDEDSTATERESPONSE']._serialized_start=3954 - _globals['_SETRATELANDEDSTATERESPONSE']._serialized_end=4047 - _globals['_SETRATEVTOLSTATEREQUEST']._serialized_start=4049 - _globals['_SETRATEVTOLSTATEREQUEST']._serialized_end=4091 - _globals['_SETRATEVTOLSTATERESPONSE']._serialized_start=4093 - _globals['_SETRATEVTOLSTATERESPONSE']._serialized_end=4184 - _globals['_SETRATEATTITUDEEULERREQUEST']._serialized_start=4186 - _globals['_SETRATEATTITUDEEULERREQUEST']._serialized_end=4232 - _globals['_SETRATEATTITUDEEULERRESPONSE']._serialized_start=4234 - _globals['_SETRATEATTITUDEEULERRESPONSE']._serialized_end=4329 - _globals['_SETRATEATTITUDEQUATERNIONREQUEST']._serialized_start=4331 - _globals['_SETRATEATTITUDEQUATERNIONREQUEST']._serialized_end=4382 - _globals['_SETRATEATTITUDEQUATERNIONRESPONSE']._serialized_start=4384 - _globals['_SETRATEATTITUDEQUATERNIONRESPONSE']._serialized_end=4484 - _globals['_SETRATEATTITUDEANGULARVELOCITYBODYREQUEST']._serialized_start=4486 - _globals['_SETRATEATTITUDEANGULARVELOCITYBODYREQUEST']._serialized_end=4546 - _globals['_SETRATEATTITUDEANGULARVELOCITYBODYRESPONSE']._serialized_start=4548 - _globals['_SETRATEATTITUDEANGULARVELOCITYBODYRESPONSE']._serialized_end=4657 - _globals['_SETRATEVELOCITYNEDREQUEST']._serialized_start=4659 - _globals['_SETRATEVELOCITYNEDREQUEST']._serialized_end=4703 - _globals['_SETRATEVELOCITYNEDRESPONSE']._serialized_start=4705 - _globals['_SETRATEVELOCITYNEDRESPONSE']._serialized_end=4798 - _globals['_SETRATEGPSINFOREQUEST']._serialized_start=4800 - _globals['_SETRATEGPSINFOREQUEST']._serialized_end=4840 - _globals['_SETRATEGPSINFORESPONSE']._serialized_start=4842 - _globals['_SETRATEGPSINFORESPONSE']._serialized_end=4931 - _globals['_SETRATERAWGPSREQUEST']._serialized_start=4933 - _globals['_SETRATERAWGPSREQUEST']._serialized_end=4972 - _globals['_SETRATEBATTERYREQUEST']._serialized_start=4974 - _globals['_SETRATEBATTERYREQUEST']._serialized_end=5014 - _globals['_SETRATEBATTERYRESPONSE']._serialized_start=5016 - _globals['_SETRATEBATTERYRESPONSE']._serialized_end=5105 - _globals['_SETRATERCSTATUSREQUEST']._serialized_start=5107 - _globals['_SETRATERCSTATUSREQUEST']._serialized_end=5148 - _globals['_SETRATERCSTATUSRESPONSE']._serialized_start=5150 - _globals['_SETRATERCSTATUSRESPONSE']._serialized_end=5240 - _globals['_SETRATEACTUATORCONTROLTARGETREQUEST']._serialized_start=5242 - _globals['_SETRATEACTUATORCONTROLTARGETREQUEST']._serialized_end=5296 - _globals['_SETRATEACTUATORCONTROLTARGETRESPONSE']._serialized_start=5298 - _globals['_SETRATEACTUATORCONTROLTARGETRESPONSE']._serialized_end=5401 - _globals['_SETRATEACTUATOROUTPUTSTATUSREQUEST']._serialized_start=5403 - _globals['_SETRATEACTUATOROUTPUTSTATUSREQUEST']._serialized_end=5456 - _globals['_SETRATEACTUATOROUTPUTSTATUSRESPONSE']._serialized_start=5458 - _globals['_SETRATEACTUATOROUTPUTSTATUSRESPONSE']._serialized_end=5560 - _globals['_SETRATEODOMETRYREQUEST']._serialized_start=5562 - _globals['_SETRATEODOMETRYREQUEST']._serialized_end=5603 - _globals['_SETRATEODOMETRYRESPONSE']._serialized_start=5605 - _globals['_SETRATEODOMETRYRESPONSE']._serialized_end=5695 - _globals['_SETRATEPOSITIONVELOCITYNEDREQUEST']._serialized_start=5697 - _globals['_SETRATEPOSITIONVELOCITYNEDREQUEST']._serialized_end=5749 - _globals['_SETRATEPOSITIONVELOCITYNEDRESPONSE']._serialized_start=5751 - _globals['_SETRATEPOSITIONVELOCITYNEDRESPONSE']._serialized_end=5852 - _globals['_SETRATEGROUNDTRUTHREQUEST']._serialized_start=5854 - _globals['_SETRATEGROUNDTRUTHREQUEST']._serialized_end=5898 - _globals['_SETRATEGROUNDTRUTHRESPONSE']._serialized_start=5900 - _globals['_SETRATEGROUNDTRUTHRESPONSE']._serialized_end=5993 - _globals['_SETRATEFIXEDWINGMETRICSREQUEST']._serialized_start=5995 - _globals['_SETRATEFIXEDWINGMETRICSREQUEST']._serialized_end=6044 - _globals['_SETRATEFIXEDWINGMETRICSRESPONSE']._serialized_start=6046 - _globals['_SETRATEFIXEDWINGMETRICSRESPONSE']._serialized_end=6144 - _globals['_SETRATEIMUREQUEST']._serialized_start=6146 - _globals['_SETRATEIMUREQUEST']._serialized_end=6182 - _globals['_SETRATEIMURESPONSE']._serialized_start=6184 - _globals['_SETRATEIMURESPONSE']._serialized_end=6269 - _globals['_SETRATESCALEDIMUREQUEST']._serialized_start=6271 - _globals['_SETRATESCALEDIMUREQUEST']._serialized_end=6313 - _globals['_SETRATESCALEDIMURESPONSE']._serialized_start=6315 - _globals['_SETRATESCALEDIMURESPONSE']._serialized_end=6406 - _globals['_SETRATERAWIMUREQUEST']._serialized_start=6408 - _globals['_SETRATERAWIMUREQUEST']._serialized_end=6447 - _globals['_SETRATERAWIMURESPONSE']._serialized_start=6449 - _globals['_SETRATERAWIMURESPONSE']._serialized_end=6537 - _globals['_SETRATEUNIXEPOCHTIMEREQUEST']._serialized_start=6539 - _globals['_SETRATEUNIXEPOCHTIMEREQUEST']._serialized_end=6585 - _globals['_SETRATEUNIXEPOCHTIMERESPONSE']._serialized_start=6587 - _globals['_SETRATEUNIXEPOCHTIMERESPONSE']._serialized_end=6682 - _globals['_SETRATEDISTANCESENSORREQUEST']._serialized_start=6684 - _globals['_SETRATEDISTANCESENSORREQUEST']._serialized_end=6731 - _globals['_SETRATEDISTANCESENSORRESPONSE']._serialized_start=6733 - _globals['_SETRATEDISTANCESENSORRESPONSE']._serialized_end=6829 - _globals['_GETGPSGLOBALORIGINREQUEST']._serialized_start=6831 - _globals['_GETGPSGLOBALORIGINREQUEST']._serialized_end=6858 - _globals['_GETGPSGLOBALORIGINRESPONSE']._serialized_start=6861 - _globals['_GETGPSGLOBALORIGINRESPONSE']._serialized_end=7020 - _globals['_SETRATEALTITUDEREQUEST']._serialized_start=7022 - _globals['_SETRATEALTITUDEREQUEST']._serialized_end=7063 - _globals['_SETRATEALTITUDERESPONSE']._serialized_start=7065 - _globals['_SETRATEALTITUDERESPONSE']._serialized_end=7155 - _globals['_SETRATEHEALTHREQUEST']._serialized_start=7157 - _globals['_SETRATEHEALTHREQUEST']._serialized_end=7196 - _globals['_SETRATEHEALTHRESPONSE']._serialized_start=7198 - _globals['_SETRATEHEALTHRESPONSE']._serialized_end=7286 - _globals['_POSITION']._serialized_start=7289 - _globals['_POSITION']._serialized_end=7438 - _globals['_HEADING']._serialized_start=7440 - _globals['_HEADING']._serialized_end=7479 - _globals['_QUATERNION']._serialized_start=7481 - _globals['_QUATERNION']._serialized_end=7595 - _globals['_EULERANGLE']._serialized_start=7597 - _globals['_EULERANGLE']._serialized_end=7712 - _globals['_ANGULARVELOCITYBODY']._serialized_start=7714 - _globals['_ANGULARVELOCITYBODY']._serialized_end=7822 - _globals['_GPSINFO']._serialized_start=7824 - _globals['_GPSINFO']._serialized_end=7913 - _globals['_RAWGPS']._serialized_start=7916 - _globals['_RAWGPS']._serialized_end=8267 - _globals['_BATTERY']._serialized_start=8270 - _globals['_BATTERY']._serialized_end=8572 - _globals['_HEALTH']._serialized_start=8575 - _globals['_HEALTH']._serialized_end=8888 - _globals['_RCSTATUS']._serialized_start=8890 - _globals['_RCSTATUS']._serialized_end=9014 - _globals['_STATUSTEXT']._serialized_start=9016 - _globals['_STATUSTEXT']._serialized_end=9094 - _globals['_ACTUATORCONTROLTARGET']._serialized_start=9096 - _globals['_ACTUATORCONTROLTARGET']._serialized_end=9159 - _globals['_ACTUATOROUTPUTSTATUS']._serialized_start=9161 - _globals['_ACTUATOROUTPUTSTATUS']._serialized_end=9224 - _globals['_COVARIANCE']._serialized_start=9226 - _globals['_COVARIANCE']._serialized_end=9265 - _globals['_VELOCITYBODY']._serialized_start=9267 - _globals['_VELOCITYBODY']._serialized_end=9326 - _globals['_POSITIONBODY']._serialized_start=9328 - _globals['_POSITIONBODY']._serialized_end=9381 - _globals['_ODOMETRY']._serialized_start=9384 - _globals['_ODOMETRY']._serialized_end=10004 - _globals['_ODOMETRY_MAVFRAME']._serialized_start=9898 - _globals['_ODOMETRY_MAVFRAME']._serialized_end=10004 - _globals['_DISTANCESENSOR']._serialized_start=10007 - _globals['_DISTANCESENSOR']._serialized_end=10189 - _globals['_SCALEDPRESSURE']._serialized_start=10192 - _globals['_SCALEDPRESSURE']._serialized_end=10368 - _globals['_POSITIONNED']._serialized_start=10370 - _globals['_POSITIONNED']._serialized_end=10459 - _globals['_VELOCITYNED']._serialized_start=10461 - _globals['_VELOCITYNED']._serialized_end=10529 - _globals['_POSITIONVELOCITYNED']._serialized_start=10531 - _globals['_POSITIONVELOCITYNED']._serialized_end=10658 - _globals['_GROUNDTRUTH']._serialized_start=10660 - _globals['_GROUNDTRUTH']._serialized_end=10774 - _globals['_FIXEDWINGMETRICS']._serialized_start=10777 - _globals['_FIXEDWINGMETRICS']._serialized_end=10999 - _globals['_ACCELERATIONFRD']._serialized_start=11001 - _globals['_ACCELERATIONFRD']._serialized_end=11106 - _globals['_ANGULARVELOCITYFRD']._serialized_start=11108 - _globals['_ANGULARVELOCITYFRD']._serialized_end=11219 - _globals['_MAGNETICFIELDFRD']._serialized_start=11221 - _globals['_MAGNETICFIELDFRD']._serialized_end=11330 - _globals['_IMU']._serialized_start=11333 - _globals['_IMU']._serialized_end=11600 - _globals['_GPSGLOBALORIGIN']._serialized_start=11602 - _globals['_GPSGLOBALORIGIN']._serialized_end=11711 - _globals['_ALTITUDE']._serialized_start=11714 - _globals['_ALTITUDE']._serialized_end=11944 - _globals['_WIND']._serialized_start=11947 - _globals['_WIND']._serialized_end=12296 - _globals['_TELEMETRYRESULT']._serialized_start=12299 - _globals['_TELEMETRYRESULT']._serialized_end=12588 - _globals['_TELEMETRYRESULT_RESULT']._serialized_start=12401 - _globals['_TELEMETRYRESULT_RESULT']._serialized_end=12588 - _globals['_TELEMETRYSERVICE']._serialized_start=13867 - _globals['_TELEMETRYSERVICE']._serialized_end=20931 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\023io.mavsdk.telemetryB\016TelemetryProto" + _globals["_POSITION"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITION"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITION"].fields_by_name["absolute_altitude_m"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITION"].fields_by_name["relative_altitude_m"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "relative_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_HEADING"].fields_by_name["heading_deg"]._loaded_options = None + _globals["_HEADING"].fields_by_name[ + "heading_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["w"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "w" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["x"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "x" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["y"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "y" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["z"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "z" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["roll_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "roll_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["pitch_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "pitch_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["yaw_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "yaw_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name["roll_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "roll_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "pitch_rad_s" + ]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "pitch_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name["yaw_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "yaw_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GPSINFO"].fields_by_name["num_satellites"]._loaded_options = None + _globals["_GPSINFO"].fields_by_name[ + "num_satellites" + ]._serialized_options = b"\202\265\030\0010" + _globals["_BATTERY"].fields_by_name["id"]._loaded_options = None + _globals["_BATTERY"].fields_by_name["id"]._serialized_options = b"\202\265\030\0010" + _globals["_BATTERY"].fields_by_name["temperature_degc"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "temperature_degc" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_BATTERY"].fields_by_name["voltage_v"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "voltage_v" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_BATTERY"].fields_by_name["current_battery_a"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "current_battery_a" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_BATTERY"].fields_by_name["capacity_consumed_ah"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "capacity_consumed_ah" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_BATTERY"].fields_by_name["remaining_percent"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "remaining_percent" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_BATTERY"].fields_by_name["time_remaining_s"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "time_remaining_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_HEALTH"].fields_by_name[ + "is_gyrometer_calibration_ok" + ]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_gyrometer_calibration_ok" + ]._serialized_options = b"\202\265\030\005false" + _globals["_HEALTH"].fields_by_name[ + "is_accelerometer_calibration_ok" + ]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_accelerometer_calibration_ok" + ]._serialized_options = b"\202\265\030\005false" + _globals["_HEALTH"].fields_by_name[ + "is_magnetometer_calibration_ok" + ]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_magnetometer_calibration_ok" + ]._serialized_options = b"\202\265\030\005false" + _globals["_HEALTH"].fields_by_name["is_local_position_ok"]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_local_position_ok" + ]._serialized_options = b"\202\265\030\005false" + _globals["_HEALTH"].fields_by_name["is_global_position_ok"]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_global_position_ok" + ]._serialized_options = b"\202\265\030\005false" + _globals["_HEALTH"].fields_by_name["is_home_position_ok"]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_home_position_ok" + ]._serialized_options = b"\202\265\030\005false" + _globals["_HEALTH"].fields_by_name["is_armable"]._loaded_options = None + _globals["_HEALTH"].fields_by_name[ + "is_armable" + ]._serialized_options = b"\202\265\030\005false" + _globals["_RCSTATUS"].fields_by_name["was_available_once"]._loaded_options = None + _globals["_RCSTATUS"].fields_by_name[ + "was_available_once" + ]._serialized_options = b"\202\265\030\005false" + _globals["_RCSTATUS"].fields_by_name["is_available"]._loaded_options = None + _globals["_RCSTATUS"].fields_by_name[ + "is_available" + ]._serialized_options = b"\202\265\030\005false" + _globals["_RCSTATUS"].fields_by_name[ + "signal_strength_percent" + ]._loaded_options = None + _globals["_RCSTATUS"].fields_by_name[ + "signal_strength_percent" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACTUATORCONTROLTARGET"].fields_by_name["group"]._loaded_options = None + _globals["_ACTUATORCONTROLTARGET"].fields_by_name[ + "group" + ]._serialized_options = b"\202\265\030\0010" + _globals["_ACTUATOROUTPUTSTATUS"].fields_by_name["active"]._loaded_options = None + _globals["_ACTUATOROUTPUTSTATUS"].fields_by_name[ + "active" + ]._serialized_options = b"\202\265\030\0010" + _globals["_DISTANCESENSOR"].fields_by_name[ + "minimum_distance_m" + ]._loaded_options = None + _globals["_DISTANCESENSOR"].fields_by_name[ + "minimum_distance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_DISTANCESENSOR"].fields_by_name[ + "maximum_distance_m" + ]._loaded_options = None + _globals["_DISTANCESENSOR"].fields_by_name[ + "maximum_distance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_DISTANCESENSOR"].fields_by_name[ + "current_distance_m" + ]._loaded_options = None + _globals["_DISTANCESENSOR"].fields_by_name[ + "current_distance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITIONNED"].fields_by_name["north_m"]._loaded_options = None + _globals["_POSITIONNED"].fields_by_name[ + "north_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITIONNED"].fields_by_name["east_m"]._loaded_options = None + _globals["_POSITIONNED"].fields_by_name[ + "east_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITIONNED"].fields_by_name["down_m"]._loaded_options = None + _globals["_POSITIONNED"].fields_by_name[ + "down_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GROUNDTRUTH"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_GROUNDTRUTH"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GROUNDTRUTH"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_GROUNDTRUTH"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GROUNDTRUTH"].fields_by_name[ + "absolute_altitude_m" + ]._loaded_options = None + _globals["_GROUNDTRUTH"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name["airspeed_m_s"]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "airspeed_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "throttle_percentage" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "throttle_percentage" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "climb_rate_m_s" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "climb_rate_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "groundspeed_m_s" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "groundspeed_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name["heading_deg"]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "heading_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "absolute_altitude_m" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACCELERATIONFRD"].fields_by_name["forward_m_s2"]._loaded_options = None + _globals["_ACCELERATIONFRD"].fields_by_name[ + "forward_m_s2" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACCELERATIONFRD"].fields_by_name["right_m_s2"]._loaded_options = None + _globals["_ACCELERATIONFRD"].fields_by_name[ + "right_m_s2" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACCELERATIONFRD"].fields_by_name["down_m_s2"]._loaded_options = None + _globals["_ACCELERATIONFRD"].fields_by_name[ + "down_m_s2" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "forward_rad_s" + ]._loaded_options = None + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "forward_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYFRD"].fields_by_name["right_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "right_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYFRD"].fields_by_name["down_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "down_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MAGNETICFIELDFRD"].fields_by_name["forward_gauss"]._loaded_options = None + _globals["_MAGNETICFIELDFRD"].fields_by_name[ + "forward_gauss" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MAGNETICFIELDFRD"].fields_by_name["right_gauss"]._loaded_options = None + _globals["_MAGNETICFIELDFRD"].fields_by_name[ + "right_gauss" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MAGNETICFIELDFRD"].fields_by_name["down_gauss"]._loaded_options = None + _globals["_MAGNETICFIELDFRD"].fields_by_name[ + "down_gauss" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_IMU"].fields_by_name["temperature_degc"]._loaded_options = None + _globals["_IMU"].fields_by_name[ + "temperature_degc" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GPSGLOBALORIGIN"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_GPSGLOBALORIGIN"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GPSGLOBALORIGIN"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_GPSGLOBALORIGIN"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GPSGLOBALORIGIN"].fields_by_name["altitude_m"]._loaded_options = None + _globals["_GPSGLOBALORIGIN"].fields_by_name[ + "altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ALTITUDE"].fields_by_name["altitude_monotonic_m"]._loaded_options = None + _globals["_ALTITUDE"].fields_by_name[ + "altitude_monotonic_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ALTITUDE"].fields_by_name["altitude_amsl_m"]._loaded_options = None + _globals["_ALTITUDE"].fields_by_name[ + "altitude_amsl_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ALTITUDE"].fields_by_name["altitude_local_m"]._loaded_options = None + _globals["_ALTITUDE"].fields_by_name[ + "altitude_local_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ALTITUDE"].fields_by_name["altitude_relative_m"]._loaded_options = None + _globals["_ALTITUDE"].fields_by_name[ + "altitude_relative_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ALTITUDE"].fields_by_name["altitude_terrain_m"]._loaded_options = None + _globals["_ALTITUDE"].fields_by_name[ + "altitude_terrain_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ALTITUDE"].fields_by_name["bottom_clearance_m"]._loaded_options = None + _globals["_ALTITUDE"].fields_by_name[ + "bottom_clearance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name["wind_x_ned_m_s"]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "wind_x_ned_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name["wind_y_ned_m_s"]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "wind_y_ned_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name["wind_z_ned_m_s"]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "wind_z_ned_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name[ + "horizontal_variability_stddev_m_s" + ]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "horizontal_variability_stddev_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name[ + "vertical_variability_stddev_m_s" + ]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "vertical_variability_stddev_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name["wind_altitude_msl_m"]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "wind_altitude_msl_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name[ + "horizontal_wind_speed_accuracy_m_s" + ]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "horizontal_wind_speed_accuracy_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WIND"].fields_by_name[ + "vertical_wind_speed_accuracy_m_s" + ]._loaded_options = None + _globals["_WIND"].fields_by_name[ + "vertical_wind_speed_accuracy_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXTYPE"]._serialized_start = 12591 + _globals["_FIXTYPE"]._serialized_end = 12755 + _globals["_BATTERYFUNCTION"]._serialized_start = 12758 + _globals["_BATTERYFUNCTION"]._serialized_end = 12925 + _globals["_FLIGHTMODE"]._serialized_start = 12928 + _globals["_FLIGHTMODE"]._serialized_end = 13318 + _globals["_STATUSTEXTTYPE"]._serialized_start = 13321 + _globals["_STATUSTEXTTYPE"]._serialized_end = 13570 + _globals["_LANDEDSTATE"]._serialized_start = 13573 + _globals["_LANDEDSTATE"]._serialized_end = 13720 + _globals["_VTOLSTATE"]._serialized_start = 13723 + _globals["_VTOLSTATE"]._serialized_end = 13864 + _globals["_SUBSCRIBEPOSITIONREQUEST"]._serialized_start = 73 + _globals["_SUBSCRIBEPOSITIONREQUEST"]._serialized_end = 99 + _globals["_POSITIONRESPONSE"]._serialized_start = 101 + _globals["_POSITIONRESPONSE"]._serialized_end = 169 + _globals["_SUBSCRIBEHOMEREQUEST"]._serialized_start = 171 + _globals["_SUBSCRIBEHOMEREQUEST"]._serialized_end = 193 + _globals["_HOMERESPONSE"]._serialized_start = 195 + _globals["_HOMERESPONSE"]._serialized_end = 255 + _globals["_SUBSCRIBEINAIRREQUEST"]._serialized_start = 257 + _globals["_SUBSCRIBEINAIRREQUEST"]._serialized_end = 280 + _globals["_INAIRRESPONSE"]._serialized_start = 282 + _globals["_INAIRRESPONSE"]._serialized_end = 316 + _globals["_SUBSCRIBELANDEDSTATEREQUEST"]._serialized_start = 318 + _globals["_SUBSCRIBELANDEDSTATEREQUEST"]._serialized_end = 347 + _globals["_LANDEDSTATERESPONSE"]._serialized_start = 349 + _globals["_LANDEDSTATERESPONSE"]._serialized_end = 427 + _globals["_SUBSCRIBEARMEDREQUEST"]._serialized_start = 429 + _globals["_SUBSCRIBEARMEDREQUEST"]._serialized_end = 452 + _globals["_ARMEDRESPONSE"]._serialized_start = 454 + _globals["_ARMEDRESPONSE"]._serialized_end = 487 + _globals["_SUBSCRIBEVTOLSTATEREQUEST"]._serialized_start = 489 + _globals["_SUBSCRIBEVTOLSTATEREQUEST"]._serialized_end = 516 + _globals["_VTOLSTATERESPONSE"]._serialized_start = 518 + _globals["_VTOLSTATERESPONSE"]._serialized_end = 590 + _globals["_SUBSCRIBEATTITUDEQUATERNIONREQUEST"]._serialized_start = 592 + _globals["_SUBSCRIBEATTITUDEQUATERNIONREQUEST"]._serialized_end = 628 + _globals["_ATTITUDEQUATERNIONRESPONSE"]._serialized_start = 630 + _globals["_ATTITUDEQUATERNIONRESPONSE"]._serialized_end = 721 + _globals["_SUBSCRIBEATTITUDEEULERREQUEST"]._serialized_start = 723 + _globals["_SUBSCRIBEATTITUDEEULERREQUEST"]._serialized_end = 754 + _globals["_ATTITUDEEULERRESPONSE"]._serialized_start = 756 + _globals["_ATTITUDEEULERRESPONSE"]._serialized_end = 837 + _globals["_SUBSCRIBEATTITUDEANGULARVELOCITYBODYREQUEST"]._serialized_start = 839 + _globals["_SUBSCRIBEATTITUDEANGULARVELOCITYBODYREQUEST"]._serialized_end = 884 + _globals["_ATTITUDEANGULARVELOCITYBODYRESPONSE"]._serialized_start = 886 + _globals["_ATTITUDEANGULARVELOCITYBODYRESPONSE"]._serialized_end = 1006 + _globals["_SUBSCRIBEVELOCITYNEDREQUEST"]._serialized_start = 1008 + _globals["_SUBSCRIBEVELOCITYNEDREQUEST"]._serialized_end = 1037 + _globals["_VELOCITYNEDRESPONSE"]._serialized_start = 1039 + _globals["_VELOCITYNEDRESPONSE"]._serialized_end = 1117 + _globals["_SUBSCRIBEGPSINFOREQUEST"]._serialized_start = 1119 + _globals["_SUBSCRIBEGPSINFOREQUEST"]._serialized_end = 1144 + _globals["_GPSINFORESPONSE"]._serialized_start = 1146 + _globals["_GPSINFORESPONSE"]._serialized_end = 1212 + _globals["_SUBSCRIBERAWGPSREQUEST"]._serialized_start = 1214 + _globals["_SUBSCRIBERAWGPSREQUEST"]._serialized_end = 1238 + _globals["_RAWGPSRESPONSE"]._serialized_start = 1240 + _globals["_RAWGPSRESPONSE"]._serialized_end = 1303 + _globals["_SUBSCRIBEBATTERYREQUEST"]._serialized_start = 1305 + _globals["_SUBSCRIBEBATTERYREQUEST"]._serialized_end = 1330 + _globals["_BATTERYRESPONSE"]._serialized_start = 1332 + _globals["_BATTERYRESPONSE"]._serialized_end = 1397 + _globals["_SUBSCRIBEFLIGHTMODEREQUEST"]._serialized_start = 1399 + _globals["_SUBSCRIBEFLIGHTMODEREQUEST"]._serialized_end = 1427 + _globals["_FLIGHTMODERESPONSE"]._serialized_start = 1429 + _globals["_FLIGHTMODERESPONSE"]._serialized_end = 1504 + _globals["_SUBSCRIBEHEALTHREQUEST"]._serialized_start = 1506 + _globals["_SUBSCRIBEHEALTHREQUEST"]._serialized_end = 1530 + _globals["_HEALTHRESPONSE"]._serialized_start = 1532 + _globals["_HEALTHRESPONSE"]._serialized_end = 1594 + _globals["_SUBSCRIBERCSTATUSREQUEST"]._serialized_start = 1596 + _globals["_SUBSCRIBERCSTATUSREQUEST"]._serialized_end = 1622 + _globals["_RCSTATUSRESPONSE"]._serialized_start = 1624 + _globals["_RCSTATUSRESPONSE"]._serialized_end = 1693 + _globals["_SUBSCRIBESTATUSTEXTREQUEST"]._serialized_start = 1695 + _globals["_SUBSCRIBESTATUSTEXTREQUEST"]._serialized_end = 1723 + _globals["_STATUSTEXTRESPONSE"]._serialized_start = 1725 + _globals["_STATUSTEXTRESPONSE"]._serialized_end = 1800 + _globals["_SUBSCRIBEACTUATORCONTROLTARGETREQUEST"]._serialized_start = 1802 + _globals["_SUBSCRIBEACTUATORCONTROLTARGETREQUEST"]._serialized_end = 1841 + _globals["_ACTUATORCONTROLTARGETRESPONSE"]._serialized_start = 1843 + _globals["_ACTUATORCONTROLTARGETRESPONSE"]._serialized_end = 1952 + _globals["_SUBSCRIBEACTUATOROUTPUTSTATUSREQUEST"]._serialized_start = 1954 + _globals["_SUBSCRIBEACTUATOROUTPUTSTATUSREQUEST"]._serialized_end = 1992 + _globals["_ACTUATOROUTPUTSTATUSRESPONSE"]._serialized_start = 1994 + _globals["_ACTUATOROUTPUTSTATUSRESPONSE"]._serialized_end = 2100 + _globals["_SUBSCRIBEODOMETRYREQUEST"]._serialized_start = 2102 + _globals["_SUBSCRIBEODOMETRYREQUEST"]._serialized_end = 2128 + _globals["_ODOMETRYRESPONSE"]._serialized_start = 2130 + _globals["_ODOMETRYRESPONSE"]._serialized_end = 2198 + _globals["_SUBSCRIBEPOSITIONVELOCITYNEDREQUEST"]._serialized_start = 2200 + _globals["_SUBSCRIBEPOSITIONVELOCITYNEDREQUEST"]._serialized_end = 2237 + _globals["_POSITIONVELOCITYNEDRESPONSE"]._serialized_start = 2239 + _globals["_POSITIONVELOCITYNEDRESPONSE"]._serialized_end = 2342 + _globals["_SUBSCRIBEGROUNDTRUTHREQUEST"]._serialized_start = 2344 + _globals["_SUBSCRIBEGROUNDTRUTHREQUEST"]._serialized_end = 2373 + _globals["_GROUNDTRUTHRESPONSE"]._serialized_start = 2375 + _globals["_GROUNDTRUTHRESPONSE"]._serialized_end = 2453 + _globals["_SUBSCRIBEFIXEDWINGMETRICSREQUEST"]._serialized_start = 2455 + _globals["_SUBSCRIBEFIXEDWINGMETRICSREQUEST"]._serialized_end = 2489 + _globals["_FIXEDWINGMETRICSRESPONSE"]._serialized_start = 2491 + _globals["_FIXEDWINGMETRICSRESPONSE"]._serialized_end = 2584 + _globals["_SUBSCRIBEIMUREQUEST"]._serialized_start = 2586 + _globals["_SUBSCRIBEIMUREQUEST"]._serialized_end = 2607 + _globals["_IMURESPONSE"]._serialized_start = 2609 + _globals["_IMURESPONSE"]._serialized_end = 2662 + _globals["_SUBSCRIBESCALEDIMUREQUEST"]._serialized_start = 2664 + _globals["_SUBSCRIBESCALEDIMUREQUEST"]._serialized_end = 2691 + _globals["_SCALEDIMURESPONSE"]._serialized_start = 2693 + _globals["_SCALEDIMURESPONSE"]._serialized_end = 2752 + _globals["_SUBSCRIBERAWIMUREQUEST"]._serialized_start = 2754 + _globals["_SUBSCRIBERAWIMUREQUEST"]._serialized_end = 2778 + _globals["_RAWIMURESPONSE"]._serialized_start = 2780 + _globals["_RAWIMURESPONSE"]._serialized_end = 2836 + _globals["_SUBSCRIBEHEALTHALLOKREQUEST"]._serialized_start = 2838 + _globals["_SUBSCRIBEHEALTHALLOKREQUEST"]._serialized_end = 2867 + _globals["_HEALTHALLOKRESPONSE"]._serialized_start = 2869 + _globals["_HEALTHALLOKRESPONSE"]._serialized_end = 2916 + _globals["_SUBSCRIBEUNIXEPOCHTIMEREQUEST"]._serialized_start = 2918 + _globals["_SUBSCRIBEUNIXEPOCHTIMEREQUEST"]._serialized_end = 2949 + _globals["_UNIXEPOCHTIMERESPONSE"]._serialized_start = 2951 + _globals["_UNIXEPOCHTIMERESPONSE"]._serialized_end = 2991 + _globals["_SUBSCRIBEDISTANCESENSORREQUEST"]._serialized_start = 2993 + _globals["_SUBSCRIBEDISTANCESENSORREQUEST"]._serialized_end = 3025 + _globals["_DISTANCESENSORRESPONSE"]._serialized_start = 3027 + _globals["_DISTANCESENSORRESPONSE"]._serialized_end = 3114 + _globals["_SUBSCRIBESCALEDPRESSUREREQUEST"]._serialized_start = 3116 + _globals["_SUBSCRIBESCALEDPRESSUREREQUEST"]._serialized_end = 3148 + _globals["_SCALEDPRESSURERESPONSE"]._serialized_start = 3150 + _globals["_SCALEDPRESSURERESPONSE"]._serialized_end = 3237 + _globals["_SUBSCRIBEHEADINGREQUEST"]._serialized_start = 3239 + _globals["_SUBSCRIBEHEADINGREQUEST"]._serialized_end = 3264 + _globals["_HEADINGRESPONSE"]._serialized_start = 3266 + _globals["_HEADINGRESPONSE"]._serialized_end = 3335 + _globals["_SUBSCRIBEALTITUDEREQUEST"]._serialized_start = 3337 + _globals["_SUBSCRIBEALTITUDEREQUEST"]._serialized_end = 3363 + _globals["_ALTITUDERESPONSE"]._serialized_start = 3365 + _globals["_ALTITUDERESPONSE"]._serialized_end = 3433 + _globals["_SUBSCRIBEWINDREQUEST"]._serialized_start = 3435 + _globals["_SUBSCRIBEWINDREQUEST"]._serialized_end = 3457 + _globals["_WINDRESPONSE"]._serialized_start = 3459 + _globals["_WINDRESPONSE"]._serialized_end = 3515 + _globals["_SETRATEPOSITIONREQUEST"]._serialized_start = 3517 + _globals["_SETRATEPOSITIONREQUEST"]._serialized_end = 3558 + _globals["_SETRATEPOSITIONRESPONSE"]._serialized_start = 3560 + _globals["_SETRATEPOSITIONRESPONSE"]._serialized_end = 3650 + _globals["_SETRATEHOMEREQUEST"]._serialized_start = 3652 + _globals["_SETRATEHOMEREQUEST"]._serialized_end = 3689 + _globals["_SETRATEHOMERESPONSE"]._serialized_start = 3691 + _globals["_SETRATEHOMERESPONSE"]._serialized_end = 3777 + _globals["_SETRATEINAIRREQUEST"]._serialized_start = 3779 + _globals["_SETRATEINAIRREQUEST"]._serialized_end = 3817 + _globals["_SETRATEINAIRRESPONSE"]._serialized_start = 3819 + _globals["_SETRATEINAIRRESPONSE"]._serialized_end = 3906 + _globals["_SETRATELANDEDSTATEREQUEST"]._serialized_start = 3908 + _globals["_SETRATELANDEDSTATEREQUEST"]._serialized_end = 3952 + _globals["_SETRATELANDEDSTATERESPONSE"]._serialized_start = 3954 + _globals["_SETRATELANDEDSTATERESPONSE"]._serialized_end = 4047 + _globals["_SETRATEVTOLSTATEREQUEST"]._serialized_start = 4049 + _globals["_SETRATEVTOLSTATEREQUEST"]._serialized_end = 4091 + _globals["_SETRATEVTOLSTATERESPONSE"]._serialized_start = 4093 + _globals["_SETRATEVTOLSTATERESPONSE"]._serialized_end = 4184 + _globals["_SETRATEATTITUDEEULERREQUEST"]._serialized_start = 4186 + _globals["_SETRATEATTITUDEEULERREQUEST"]._serialized_end = 4232 + _globals["_SETRATEATTITUDEEULERRESPONSE"]._serialized_start = 4234 + _globals["_SETRATEATTITUDEEULERRESPONSE"]._serialized_end = 4329 + _globals["_SETRATEATTITUDEQUATERNIONREQUEST"]._serialized_start = 4331 + _globals["_SETRATEATTITUDEQUATERNIONREQUEST"]._serialized_end = 4382 + _globals["_SETRATEATTITUDEQUATERNIONRESPONSE"]._serialized_start = 4384 + _globals["_SETRATEATTITUDEQUATERNIONRESPONSE"]._serialized_end = 4484 + _globals["_SETRATEATTITUDEANGULARVELOCITYBODYREQUEST"]._serialized_start = 4486 + _globals["_SETRATEATTITUDEANGULARVELOCITYBODYREQUEST"]._serialized_end = 4546 + _globals["_SETRATEATTITUDEANGULARVELOCITYBODYRESPONSE"]._serialized_start = 4548 + _globals["_SETRATEATTITUDEANGULARVELOCITYBODYRESPONSE"]._serialized_end = 4657 + _globals["_SETRATEVELOCITYNEDREQUEST"]._serialized_start = 4659 + _globals["_SETRATEVELOCITYNEDREQUEST"]._serialized_end = 4703 + _globals["_SETRATEVELOCITYNEDRESPONSE"]._serialized_start = 4705 + _globals["_SETRATEVELOCITYNEDRESPONSE"]._serialized_end = 4798 + _globals["_SETRATEGPSINFOREQUEST"]._serialized_start = 4800 + _globals["_SETRATEGPSINFOREQUEST"]._serialized_end = 4840 + _globals["_SETRATEGPSINFORESPONSE"]._serialized_start = 4842 + _globals["_SETRATEGPSINFORESPONSE"]._serialized_end = 4931 + _globals["_SETRATERAWGPSREQUEST"]._serialized_start = 4933 + _globals["_SETRATERAWGPSREQUEST"]._serialized_end = 4972 + _globals["_SETRATEBATTERYREQUEST"]._serialized_start = 4974 + _globals["_SETRATEBATTERYREQUEST"]._serialized_end = 5014 + _globals["_SETRATEBATTERYRESPONSE"]._serialized_start = 5016 + _globals["_SETRATEBATTERYRESPONSE"]._serialized_end = 5105 + _globals["_SETRATERCSTATUSREQUEST"]._serialized_start = 5107 + _globals["_SETRATERCSTATUSREQUEST"]._serialized_end = 5148 + _globals["_SETRATERCSTATUSRESPONSE"]._serialized_start = 5150 + _globals["_SETRATERCSTATUSRESPONSE"]._serialized_end = 5240 + _globals["_SETRATEACTUATORCONTROLTARGETREQUEST"]._serialized_start = 5242 + _globals["_SETRATEACTUATORCONTROLTARGETREQUEST"]._serialized_end = 5296 + _globals["_SETRATEACTUATORCONTROLTARGETRESPONSE"]._serialized_start = 5298 + _globals["_SETRATEACTUATORCONTROLTARGETRESPONSE"]._serialized_end = 5401 + _globals["_SETRATEACTUATOROUTPUTSTATUSREQUEST"]._serialized_start = 5403 + _globals["_SETRATEACTUATOROUTPUTSTATUSREQUEST"]._serialized_end = 5456 + _globals["_SETRATEACTUATOROUTPUTSTATUSRESPONSE"]._serialized_start = 5458 + _globals["_SETRATEACTUATOROUTPUTSTATUSRESPONSE"]._serialized_end = 5560 + _globals["_SETRATEODOMETRYREQUEST"]._serialized_start = 5562 + _globals["_SETRATEODOMETRYREQUEST"]._serialized_end = 5603 + _globals["_SETRATEODOMETRYRESPONSE"]._serialized_start = 5605 + _globals["_SETRATEODOMETRYRESPONSE"]._serialized_end = 5695 + _globals["_SETRATEPOSITIONVELOCITYNEDREQUEST"]._serialized_start = 5697 + _globals["_SETRATEPOSITIONVELOCITYNEDREQUEST"]._serialized_end = 5749 + _globals["_SETRATEPOSITIONVELOCITYNEDRESPONSE"]._serialized_start = 5751 + _globals["_SETRATEPOSITIONVELOCITYNEDRESPONSE"]._serialized_end = 5852 + _globals["_SETRATEGROUNDTRUTHREQUEST"]._serialized_start = 5854 + _globals["_SETRATEGROUNDTRUTHREQUEST"]._serialized_end = 5898 + _globals["_SETRATEGROUNDTRUTHRESPONSE"]._serialized_start = 5900 + _globals["_SETRATEGROUNDTRUTHRESPONSE"]._serialized_end = 5993 + _globals["_SETRATEFIXEDWINGMETRICSREQUEST"]._serialized_start = 5995 + _globals["_SETRATEFIXEDWINGMETRICSREQUEST"]._serialized_end = 6044 + _globals["_SETRATEFIXEDWINGMETRICSRESPONSE"]._serialized_start = 6046 + _globals["_SETRATEFIXEDWINGMETRICSRESPONSE"]._serialized_end = 6144 + _globals["_SETRATEIMUREQUEST"]._serialized_start = 6146 + _globals["_SETRATEIMUREQUEST"]._serialized_end = 6182 + _globals["_SETRATEIMURESPONSE"]._serialized_start = 6184 + _globals["_SETRATEIMURESPONSE"]._serialized_end = 6269 + _globals["_SETRATESCALEDIMUREQUEST"]._serialized_start = 6271 + _globals["_SETRATESCALEDIMUREQUEST"]._serialized_end = 6313 + _globals["_SETRATESCALEDIMURESPONSE"]._serialized_start = 6315 + _globals["_SETRATESCALEDIMURESPONSE"]._serialized_end = 6406 + _globals["_SETRATERAWIMUREQUEST"]._serialized_start = 6408 + _globals["_SETRATERAWIMUREQUEST"]._serialized_end = 6447 + _globals["_SETRATERAWIMURESPONSE"]._serialized_start = 6449 + _globals["_SETRATERAWIMURESPONSE"]._serialized_end = 6537 + _globals["_SETRATEUNIXEPOCHTIMEREQUEST"]._serialized_start = 6539 + _globals["_SETRATEUNIXEPOCHTIMEREQUEST"]._serialized_end = 6585 + _globals["_SETRATEUNIXEPOCHTIMERESPONSE"]._serialized_start = 6587 + _globals["_SETRATEUNIXEPOCHTIMERESPONSE"]._serialized_end = 6682 + _globals["_SETRATEDISTANCESENSORREQUEST"]._serialized_start = 6684 + _globals["_SETRATEDISTANCESENSORREQUEST"]._serialized_end = 6731 + _globals["_SETRATEDISTANCESENSORRESPONSE"]._serialized_start = 6733 + _globals["_SETRATEDISTANCESENSORRESPONSE"]._serialized_end = 6829 + _globals["_GETGPSGLOBALORIGINREQUEST"]._serialized_start = 6831 + _globals["_GETGPSGLOBALORIGINREQUEST"]._serialized_end = 6858 + _globals["_GETGPSGLOBALORIGINRESPONSE"]._serialized_start = 6861 + _globals["_GETGPSGLOBALORIGINRESPONSE"]._serialized_end = 7020 + _globals["_SETRATEALTITUDEREQUEST"]._serialized_start = 7022 + _globals["_SETRATEALTITUDEREQUEST"]._serialized_end = 7063 + _globals["_SETRATEALTITUDERESPONSE"]._serialized_start = 7065 + _globals["_SETRATEALTITUDERESPONSE"]._serialized_end = 7155 + _globals["_SETRATEHEALTHREQUEST"]._serialized_start = 7157 + _globals["_SETRATEHEALTHREQUEST"]._serialized_end = 7196 + _globals["_SETRATEHEALTHRESPONSE"]._serialized_start = 7198 + _globals["_SETRATEHEALTHRESPONSE"]._serialized_end = 7286 + _globals["_POSITION"]._serialized_start = 7289 + _globals["_POSITION"]._serialized_end = 7438 + _globals["_HEADING"]._serialized_start = 7440 + _globals["_HEADING"]._serialized_end = 7479 + _globals["_QUATERNION"]._serialized_start = 7481 + _globals["_QUATERNION"]._serialized_end = 7595 + _globals["_EULERANGLE"]._serialized_start = 7597 + _globals["_EULERANGLE"]._serialized_end = 7712 + _globals["_ANGULARVELOCITYBODY"]._serialized_start = 7714 + _globals["_ANGULARVELOCITYBODY"]._serialized_end = 7822 + _globals["_GPSINFO"]._serialized_start = 7824 + _globals["_GPSINFO"]._serialized_end = 7913 + _globals["_RAWGPS"]._serialized_start = 7916 + _globals["_RAWGPS"]._serialized_end = 8267 + _globals["_BATTERY"]._serialized_start = 8270 + _globals["_BATTERY"]._serialized_end = 8572 + _globals["_HEALTH"]._serialized_start = 8575 + _globals["_HEALTH"]._serialized_end = 8888 + _globals["_RCSTATUS"]._serialized_start = 8890 + _globals["_RCSTATUS"]._serialized_end = 9014 + _globals["_STATUSTEXT"]._serialized_start = 9016 + _globals["_STATUSTEXT"]._serialized_end = 9094 + _globals["_ACTUATORCONTROLTARGET"]._serialized_start = 9096 + _globals["_ACTUATORCONTROLTARGET"]._serialized_end = 9159 + _globals["_ACTUATOROUTPUTSTATUS"]._serialized_start = 9161 + _globals["_ACTUATOROUTPUTSTATUS"]._serialized_end = 9224 + _globals["_COVARIANCE"]._serialized_start = 9226 + _globals["_COVARIANCE"]._serialized_end = 9265 + _globals["_VELOCITYBODY"]._serialized_start = 9267 + _globals["_VELOCITYBODY"]._serialized_end = 9326 + _globals["_POSITIONBODY"]._serialized_start = 9328 + _globals["_POSITIONBODY"]._serialized_end = 9381 + _globals["_ODOMETRY"]._serialized_start = 9384 + _globals["_ODOMETRY"]._serialized_end = 10004 + _globals["_ODOMETRY_MAVFRAME"]._serialized_start = 9898 + _globals["_ODOMETRY_MAVFRAME"]._serialized_end = 10004 + _globals["_DISTANCESENSOR"]._serialized_start = 10007 + _globals["_DISTANCESENSOR"]._serialized_end = 10189 + _globals["_SCALEDPRESSURE"]._serialized_start = 10192 + _globals["_SCALEDPRESSURE"]._serialized_end = 10368 + _globals["_POSITIONNED"]._serialized_start = 10370 + _globals["_POSITIONNED"]._serialized_end = 10459 + _globals["_VELOCITYNED"]._serialized_start = 10461 + _globals["_VELOCITYNED"]._serialized_end = 10529 + _globals["_POSITIONVELOCITYNED"]._serialized_start = 10531 + _globals["_POSITIONVELOCITYNED"]._serialized_end = 10658 + _globals["_GROUNDTRUTH"]._serialized_start = 10660 + _globals["_GROUNDTRUTH"]._serialized_end = 10774 + _globals["_FIXEDWINGMETRICS"]._serialized_start = 10777 + _globals["_FIXEDWINGMETRICS"]._serialized_end = 10999 + _globals["_ACCELERATIONFRD"]._serialized_start = 11001 + _globals["_ACCELERATIONFRD"]._serialized_end = 11106 + _globals["_ANGULARVELOCITYFRD"]._serialized_start = 11108 + _globals["_ANGULARVELOCITYFRD"]._serialized_end = 11219 + _globals["_MAGNETICFIELDFRD"]._serialized_start = 11221 + _globals["_MAGNETICFIELDFRD"]._serialized_end = 11330 + _globals["_IMU"]._serialized_start = 11333 + _globals["_IMU"]._serialized_end = 11600 + _globals["_GPSGLOBALORIGIN"]._serialized_start = 11602 + _globals["_GPSGLOBALORIGIN"]._serialized_end = 11711 + _globals["_ALTITUDE"]._serialized_start = 11714 + _globals["_ALTITUDE"]._serialized_end = 11944 + _globals["_WIND"]._serialized_start = 11947 + _globals["_WIND"]._serialized_end = 12296 + _globals["_TELEMETRYRESULT"]._serialized_start = 12299 + _globals["_TELEMETRYRESULT"]._serialized_end = 12588 + _globals["_TELEMETRYRESULT_RESULT"]._serialized_start = 12401 + _globals["_TELEMETRYRESULT_RESULT"]._serialized_end = 12588 + _globals["_TELEMETRYSERVICE"]._serialized_start = 13867 + _globals["_TELEMETRYSERVICE"]._serialized_end = 20931 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/telemetry_pb2_grpc.py b/mavsdk/telemetry_pb2_grpc.py index 5be76a69..6e85a1d9 100644 --- a/mavsdk/telemetry_pb2_grpc.py +++ b/mavsdk/telemetry_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import telemetry_pb2 as telemetry_dot_telemetry__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in telemetry/telemetry_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in telemetry/telemetry_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -39,295 +43,353 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribePosition = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribePosition', - request_serializer=telemetry_dot_telemetry__pb2.SubscribePositionRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.PositionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribePosition", + request_serializer=telemetry_dot_telemetry__pb2.SubscribePositionRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.PositionResponse.FromString, + _registered_method=True, + ) self.SubscribeHome = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHome', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeHomeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.HomeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHome", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeHomeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.HomeResponse.FromString, + _registered_method=True, + ) self.SubscribeInAir = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeInAirRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.InAirResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeInAirRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.InAirResponse.FromString, + _registered_method=True, + ) self.SubscribeLandedState = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeLandedStateRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.LandedStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeLandedStateRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.LandedStateResponse.FromString, + _registered_method=True, + ) self.SubscribeArmed = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeArmedRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.ArmedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeArmedRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.ArmedResponse.FromString, + _registered_method=True, + ) self.SubscribeVtolState = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeVtolState', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeVtolStateRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.VtolStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeVtolState", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeVtolStateRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.VtolStateResponse.FromString, + _registered_method=True, + ) self.SubscribeAttitudeQuaternion = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeQuaternionRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.AttitudeQuaternionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeQuaternionRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.AttitudeQuaternionResponse.FromString, + _registered_method=True, + ) self.SubscribeAttitudeEuler = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeEulerRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.AttitudeEulerResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeEulerRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.AttitudeEulerResponse.FromString, + _registered_method=True, + ) self.SubscribeAttitudeAngularVelocityBody = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeAngularVelocityBodyRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.AttitudeAngularVelocityBodyResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeAngularVelocityBodyRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.AttitudeAngularVelocityBodyResponse.FromString, + _registered_method=True, + ) self.SubscribeVelocityNed = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeVelocityNedRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.VelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeVelocityNedRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.VelocityNedResponse.FromString, + _registered_method=True, + ) self.SubscribeGpsInfo = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeGpsInfoRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.GpsInfoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeGpsInfoRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.GpsInfoResponse.FromString, + _registered_method=True, + ) self.SubscribeRawGps = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawGps', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeRawGpsRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.RawGpsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawGps", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeRawGpsRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.RawGpsResponse.FromString, + _registered_method=True, + ) self.SubscribeBattery = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeBattery', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeBatteryRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.BatteryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeBattery", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeBatteryRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.BatteryResponse.FromString, + _registered_method=True, + ) self.SubscribeFlightMode = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeFlightMode', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeFlightModeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.FlightModeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeFlightMode", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeFlightModeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.FlightModeResponse.FromString, + _registered_method=True, + ) self.SubscribeHealth = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeHealthRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.HealthResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeHealthRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.HealthResponse.FromString, + _registered_method=True, + ) self.SubscribeRcStatus = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeRcStatusRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.RcStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeRcStatusRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.RcStatusResponse.FromString, + _registered_method=True, + ) self.SubscribeStatusText = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeStatusTextRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.StatusTextResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeStatusTextRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.StatusTextResponse.FromString, + _registered_method=True, + ) self.SubscribeActuatorControlTarget = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeActuatorControlTargetRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.ActuatorControlTargetResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeActuatorControlTargetRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.ActuatorControlTargetResponse.FromString, + _registered_method=True, + ) self.SubscribeActuatorOutputStatus = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeActuatorOutputStatusRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.ActuatorOutputStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeActuatorOutputStatusRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.ActuatorOutputStatusResponse.FromString, + _registered_method=True, + ) self.SubscribeOdometry = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeOdometryRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.OdometryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeOdometryRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.OdometryResponse.FromString, + _registered_method=True, + ) self.SubscribePositionVelocityNed = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribePositionVelocityNed', - request_serializer=telemetry_dot_telemetry__pb2.SubscribePositionVelocityNedRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.PositionVelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribePositionVelocityNed", + request_serializer=telemetry_dot_telemetry__pb2.SubscribePositionVelocityNedRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.PositionVelocityNedResponse.FromString, + _registered_method=True, + ) self.SubscribeGroundTruth = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundTruth', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeGroundTruthRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.GroundTruthResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundTruth", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeGroundTruthRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.GroundTruthResponse.FromString, + _registered_method=True, + ) self.SubscribeFixedwingMetrics = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeFixedwingMetrics', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeFixedwingMetricsRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.FixedwingMetricsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeFixedwingMetrics", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeFixedwingMetricsRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.FixedwingMetricsResponse.FromString, + _registered_method=True, + ) self.SubscribeImu = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeImu', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeImuRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.ImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeImu", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeImuRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.ImuResponse.FromString, + _registered_method=True, + ) self.SubscribeScaledImu = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledImu', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeScaledImuRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.ScaledImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledImu", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeScaledImuRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.ScaledImuResponse.FromString, + _registered_method=True, + ) self.SubscribeRawImu = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawImu', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeRawImuRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.RawImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawImu", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeRawImuRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.RawImuResponse.FromString, + _registered_method=True, + ) self.SubscribeHealthAllOk = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealthAllOk', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeHealthAllOkRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.HealthAllOkResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealthAllOk", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeHealthAllOkRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.HealthAllOkResponse.FromString, + _registered_method=True, + ) self.SubscribeUnixEpochTime = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeUnixEpochTime', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeUnixEpochTimeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.UnixEpochTimeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeUnixEpochTime", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeUnixEpochTimeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.UnixEpochTimeResponse.FromString, + _registered_method=True, + ) self.SubscribeDistanceSensor = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeDistanceSensorRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.DistanceSensorResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeDistanceSensorRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.DistanceSensorResponse.FromString, + _registered_method=True, + ) self.SubscribeScaledPressure = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledPressure', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeScaledPressureRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.ScaledPressureResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledPressure", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeScaledPressureRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.ScaledPressureResponse.FromString, + _registered_method=True, + ) self.SubscribeHeading = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHeading', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeHeadingRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.HeadingResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHeading", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeHeadingRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.HeadingResponse.FromString, + _registered_method=True, + ) self.SubscribeAltitude = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAltitude', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeAltitudeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.AltitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAltitude", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeAltitudeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.AltitudeResponse.FromString, + _registered_method=True, + ) self.SubscribeWind = channel.unary_stream( - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeWind', - request_serializer=telemetry_dot_telemetry__pb2.SubscribeWindRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.WindResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeWind", + request_serializer=telemetry_dot_telemetry__pb2.SubscribeWindRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.WindResponse.FromString, + _registered_method=True, + ) self.SetRatePosition = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition', - request_serializer=telemetry_dot_telemetry__pb2.SetRatePositionRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition", + request_serializer=telemetry_dot_telemetry__pb2.SetRatePositionRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionResponse.FromString, + _registered_method=True, + ) self.SetRateHome = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateHome', - request_serializer=telemetry_dot_telemetry__pb2.SetRateHomeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateHomeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateHome", + request_serializer=telemetry_dot_telemetry__pb2.SetRateHomeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateHomeResponse.FromString, + _registered_method=True, + ) self.SetRateInAir = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir', - request_serializer=telemetry_dot_telemetry__pb2.SetRateInAirRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateInAirResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir", + request_serializer=telemetry_dot_telemetry__pb2.SetRateInAirRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateInAirResponse.FromString, + _registered_method=True, + ) self.SetRateLandedState = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateLandedState', - request_serializer=telemetry_dot_telemetry__pb2.SetRateLandedStateRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateLandedStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateLandedState", + request_serializer=telemetry_dot_telemetry__pb2.SetRateLandedStateRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateLandedStateResponse.FromString, + _registered_method=True, + ) self.SetRateVtolState = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateVtolState', - request_serializer=telemetry_dot_telemetry__pb2.SetRateVtolStateRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateVtolStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateVtolState", + request_serializer=telemetry_dot_telemetry__pb2.SetRateVtolStateRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateVtolStateResponse.FromString, + _registered_method=True, + ) self.SetRateAttitudeQuaternion = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeQuaternion', - request_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeQuaternion", + request_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionResponse.FromString, + _registered_method=True, + ) self.SetRateAttitudeEuler = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeEuler', - request_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeEuler", + request_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerResponse.FromString, + _registered_method=True, + ) self.SetRateVelocityNed = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed', - request_serializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed", + request_serializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedResponse.FromString, + _registered_method=True, + ) self.SetRateGpsInfo = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo', - request_serializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo", + request_serializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoResponse.FromString, + _registered_method=True, + ) self.SetRateBattery = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery', - request_serializer=telemetry_dot_telemetry__pb2.SetRateBatteryRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateBatteryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery", + request_serializer=telemetry_dot_telemetry__pb2.SetRateBatteryRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateBatteryResponse.FromString, + _registered_method=True, + ) self.SetRateRcStatus = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateRcStatus', - request_serializer=telemetry_dot_telemetry__pb2.SetRateRcStatusRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateRcStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateRcStatus", + request_serializer=telemetry_dot_telemetry__pb2.SetRateRcStatusRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateRcStatusResponse.FromString, + _registered_method=True, + ) self.SetRateActuatorControlTarget = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorControlTarget', - request_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorControlTarget", + request_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetResponse.FromString, + _registered_method=True, + ) self.SetRateActuatorOutputStatus = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorOutputStatus', - request_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorOutputStatus", + request_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusResponse.FromString, + _registered_method=True, + ) self.SetRateOdometry = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateOdometry', - request_serializer=telemetry_dot_telemetry__pb2.SetRateOdometryRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateOdometryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateOdometry", + request_serializer=telemetry_dot_telemetry__pb2.SetRateOdometryRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateOdometryResponse.FromString, + _registered_method=True, + ) self.SetRatePositionVelocityNed = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRatePositionVelocityNed', - request_serializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRatePositionVelocityNed", + request_serializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedResponse.FromString, + _registered_method=True, + ) self.SetRateGroundTruth = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateGroundTruth', - request_serializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateGroundTruth", + request_serializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthResponse.FromString, + _registered_method=True, + ) self.SetRateFixedwingMetrics = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateFixedwingMetrics', - request_serializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateFixedwingMetrics", + request_serializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsResponse.FromString, + _registered_method=True, + ) self.SetRateImu = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateImu', - request_serializer=telemetry_dot_telemetry__pb2.SetRateImuRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateImu", + request_serializer=telemetry_dot_telemetry__pb2.SetRateImuRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateImuResponse.FromString, + _registered_method=True, + ) self.SetRateScaledImu = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateScaledImu', - request_serializer=telemetry_dot_telemetry__pb2.SetRateScaledImuRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateScaledImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateScaledImu", + request_serializer=telemetry_dot_telemetry__pb2.SetRateScaledImuRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateScaledImuResponse.FromString, + _registered_method=True, + ) self.SetRateRawImu = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateRawImu', - request_serializer=telemetry_dot_telemetry__pb2.SetRateRawImuRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateRawImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateRawImu", + request_serializer=telemetry_dot_telemetry__pb2.SetRateRawImuRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateRawImuResponse.FromString, + _registered_method=True, + ) self.SetRateUnixEpochTime = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime', - request_serializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime", + request_serializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeResponse.FromString, + _registered_method=True, + ) self.SetRateDistanceSensor = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor', - request_serializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor", + request_serializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorResponse.FromString, + _registered_method=True, + ) self.SetRateAltitude = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateAltitude', - request_serializer=telemetry_dot_telemetry__pb2.SetRateAltitudeRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateAltitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAltitude", + request_serializer=telemetry_dot_telemetry__pb2.SetRateAltitudeRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateAltitudeResponse.FromString, + _registered_method=True, + ) self.SetRateHealth = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/SetRateHealth', - request_serializer=telemetry_dot_telemetry__pb2.SetRateHealthRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.SetRateHealthResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/SetRateHealth", + request_serializer=telemetry_dot_telemetry__pb2.SetRateHealthRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.SetRateHealthResponse.FromString, + _registered_method=True, + ) self.GetGpsGlobalOrigin = channel.unary_unary( - '/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin', - request_serializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginRequest.SerializeToString, - response_deserializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin", + request_serializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginRequest.SerializeToString, + response_deserializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginResponse.FromString, + _registered_method=True, + ) class TelemetryServiceServicer(object): @@ -338,713 +400,659 @@ class TelemetryServiceServicer(object): """ def SubscribePosition(self, request, context): - """Subscribe to 'position' updates. - """ + """Subscribe to 'position' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeHome(self, request, context): - """Subscribe to 'home position' updates. - """ + """Subscribe to 'home position' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeInAir(self, request, context): - """Subscribe to in-air updates. - """ + """Subscribe to in-air updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeLandedState(self, request, context): - """Subscribe to landed state updates - """ + """Subscribe to landed state updates""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeArmed(self, request, context): - """Subscribe to armed updates. - """ + """Subscribe to armed updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeVtolState(self, request, context): - """subscribe to vtol state Updates - """ + """subscribe to vtol state Updates""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeAttitudeQuaternion(self, request, context): - """Subscribe to 'attitude' updates (quaternion). - """ + """Subscribe to 'attitude' updates (quaternion).""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeAttitudeEuler(self, request, context): - """Subscribe to 'attitude' updates (Euler). - """ + """Subscribe to 'attitude' updates (Euler).""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeAttitudeAngularVelocityBody(self, request, context): - """Subscribe to 'attitude' updates (angular velocity) - """ + """Subscribe to 'attitude' updates (angular velocity)""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeVelocityNed(self, request, context): - """Subscribe to 'ground speed' updates (NED). - """ + """Subscribe to 'ground speed' updates (NED).""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeGpsInfo(self, request, context): - """Subscribe to 'GPS info' updates. - """ + """Subscribe to 'GPS info' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeRawGps(self, request, context): - """Subscribe to 'Raw GPS' updates. - """ + """Subscribe to 'Raw GPS' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeBattery(self, request, context): - """Subscribe to 'battery' updates. - """ + """Subscribe to 'battery' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFlightMode(self, request, context): - """Subscribe to 'flight mode' updates. - """ + """Subscribe to 'flight mode' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeHealth(self, request, context): - """Subscribe to 'health' updates. - """ + """Subscribe to 'health' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeRcStatus(self, request, context): - """Subscribe to 'RC status' updates. - """ + """Subscribe to 'RC status' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeStatusText(self, request, context): - """Subscribe to 'status text' updates. - """ + """Subscribe to 'status text' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeActuatorControlTarget(self, request, context): - """Subscribe to 'actuator control target' updates. - """ + """Subscribe to 'actuator control target' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeActuatorOutputStatus(self, request, context): - """Subscribe to 'actuator output status' updates. - """ + """Subscribe to 'actuator output status' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeOdometry(self, request, context): - """Subscribe to 'odometry' updates. - """ + """Subscribe to 'odometry' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribePositionVelocityNed(self, request, context): - """Subscribe to 'position velocity' updates. - """ + """Subscribe to 'position velocity' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeGroundTruth(self, request, context): - """Subscribe to 'ground truth' updates. - """ + """Subscribe to 'ground truth' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeFixedwingMetrics(self, request, context): - """Subscribe to 'fixedwing metrics' updates. - """ + """Subscribe to 'fixedwing metrics' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeImu(self, request, context): - """Subscribe to 'IMU' updates (in SI units in NED body frame). - """ + """Subscribe to 'IMU' updates (in SI units in NED body frame).""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeScaledImu(self, request, context): - """Subscribe to 'Scaled IMU' updates. - """ + """Subscribe to 'Scaled IMU' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeRawImu(self, request, context): - """Subscribe to 'Raw IMU' updates (note that units are are incorrect and "raw" as provided by the sensor) - """ + """Subscribe to 'Raw IMU' updates (note that units are are incorrect and "raw" as provided by the sensor)""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeHealthAllOk(self, request, context): - """Subscribe to 'HealthAllOk' updates. - """ + """Subscribe to 'HealthAllOk' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeUnixEpochTime(self, request, context): - """Subscribe to 'unix epoch time' updates. - """ + """Subscribe to 'unix epoch time' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeDistanceSensor(self, request, context): - """Subscribe to 'Distance Sensor' updates. - """ + """Subscribe to 'Distance Sensor' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeScaledPressure(self, request, context): - """Subscribe to 'Scaled Pressure' updates. - """ + """Subscribe to 'Scaled Pressure' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeHeading(self, request, context): - """Subscribe to 'Heading' updates. - """ + """Subscribe to 'Heading' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeAltitude(self, request, context): - """Subscribe to 'Altitude' updates. - """ + """Subscribe to 'Altitude' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeWind(self, request, context): - """Subscribe to 'Wind Estimated' updates. - """ + """Subscribe to 'Wind Estimated' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRatePosition(self, request, context): - """Set rate to 'position' updates. - """ + """Set rate to 'position' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateHome(self, request, context): - """Set rate to 'home position' updates. - """ + """Set rate to 'home position' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateInAir(self, request, context): - """Set rate to in-air updates. - """ + """Set rate to in-air updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateLandedState(self, request, context): - """Set rate to landed state updates - """ + """Set rate to landed state updates""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateVtolState(self, request, context): - """Set rate to VTOL state updates - """ + """Set rate to VTOL state updates""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateAttitudeQuaternion(self, request, context): - """Set rate to 'attitude euler angle' updates. - """ + """Set rate to 'attitude euler angle' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateAttitudeEuler(self, request, context): - """Set rate to 'attitude quaternion' updates. - """ + """Set rate to 'attitude quaternion' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateVelocityNed(self, request, context): """Set rate of camera attitude updates. Set rate to 'ground speed' updates (NED). """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateGpsInfo(self, request, context): - """Set rate to 'GPS info' updates. - """ + """Set rate to 'GPS info' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateBattery(self, request, context): - """Set rate to 'battery' updates. - """ + """Set rate to 'battery' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateRcStatus(self, request, context): - """Set rate to 'RC status' updates. - """ + """Set rate to 'RC status' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateActuatorControlTarget(self, request, context): - """Set rate to 'actuator control target' updates. - """ + """Set rate to 'actuator control target' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateActuatorOutputStatus(self, request, context): - """Set rate to 'actuator output status' updates. - """ + """Set rate to 'actuator output status' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateOdometry(self, request, context): - """Set rate to 'odometry' updates. - """ + """Set rate to 'odometry' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRatePositionVelocityNed(self, request, context): - """Set rate to 'position velocity' updates. - """ + """Set rate to 'position velocity' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateGroundTruth(self, request, context): - """Set rate to 'ground truth' updates. - """ + """Set rate to 'ground truth' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateFixedwingMetrics(self, request, context): - """Set rate to 'fixedwing metrics' updates. - """ + """Set rate to 'fixedwing metrics' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateImu(self, request, context): - """Set rate to 'IMU' updates. - """ + """Set rate to 'IMU' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateScaledImu(self, request, context): - """Set rate to 'Scaled IMU' updates. - """ + """Set rate to 'Scaled IMU' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateRawImu(self, request, context): - """Set rate to 'Raw IMU' updates. - """ + """Set rate to 'Raw IMU' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateUnixEpochTime(self, request, context): - """Set rate to 'unix epoch time' updates. - """ + """Set rate to 'unix epoch time' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateDistanceSensor(self, request, context): - """Set rate to 'Distance Sensor' updates. - """ + """Set rate to 'Distance Sensor' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateAltitude(self, request, context): - """Set rate to 'Altitude' updates. - """ + """Set rate to 'Altitude' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateHealth(self, request, context): - """Set rate to 'Health' updates. - """ + """Set rate to 'Health' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def GetGpsGlobalOrigin(self, request, context): - """Get the GPS location of where the estimator has been initialized. - """ + """Get the GPS location of where the estimator has been initialized.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_TelemetryServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribePosition': grpc.unary_stream_rpc_method_handler( - servicer.SubscribePosition, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribePositionRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.PositionResponse.SerializeToString, - ), - 'SubscribeHome': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeHome, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHomeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.HomeResponse.SerializeToString, - ), - 'SubscribeInAir': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeInAir, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeInAirRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.InAirResponse.SerializeToString, - ), - 'SubscribeLandedState': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeLandedState, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeLandedStateRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.LandedStateResponse.SerializeToString, - ), - 'SubscribeArmed': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeArmed, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeArmedRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.ArmedResponse.SerializeToString, - ), - 'SubscribeVtolState': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeVtolState, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeVtolStateRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.VtolStateResponse.SerializeToString, - ), - 'SubscribeAttitudeQuaternion': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeAttitudeQuaternion, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeQuaternionRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.AttitudeQuaternionResponse.SerializeToString, - ), - 'SubscribeAttitudeEuler': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeAttitudeEuler, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeEulerRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.AttitudeEulerResponse.SerializeToString, - ), - 'SubscribeAttitudeAngularVelocityBody': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeAttitudeAngularVelocityBody, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeAngularVelocityBodyRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.AttitudeAngularVelocityBodyResponse.SerializeToString, - ), - 'SubscribeVelocityNed': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeVelocityNed, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeVelocityNedRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.VelocityNedResponse.SerializeToString, - ), - 'SubscribeGpsInfo': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeGpsInfo, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeGpsInfoRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.GpsInfoResponse.SerializeToString, - ), - 'SubscribeRawGps': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeRawGps, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeRawGpsRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.RawGpsResponse.SerializeToString, - ), - 'SubscribeBattery': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeBattery, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeBatteryRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.BatteryResponse.SerializeToString, - ), - 'SubscribeFlightMode': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFlightMode, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeFlightModeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.FlightModeResponse.SerializeToString, - ), - 'SubscribeHealth': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeHealth, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHealthRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.HealthResponse.SerializeToString, - ), - 'SubscribeRcStatus': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeRcStatus, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeRcStatusRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.RcStatusResponse.SerializeToString, - ), - 'SubscribeStatusText': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStatusText, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeStatusTextRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.StatusTextResponse.SerializeToString, - ), - 'SubscribeActuatorControlTarget': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeActuatorControlTarget, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeActuatorControlTargetRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.ActuatorControlTargetResponse.SerializeToString, - ), - 'SubscribeActuatorOutputStatus': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeActuatorOutputStatus, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeActuatorOutputStatusRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.ActuatorOutputStatusResponse.SerializeToString, - ), - 'SubscribeOdometry': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeOdometry, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeOdometryRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.OdometryResponse.SerializeToString, - ), - 'SubscribePositionVelocityNed': grpc.unary_stream_rpc_method_handler( - servicer.SubscribePositionVelocityNed, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribePositionVelocityNedRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.PositionVelocityNedResponse.SerializeToString, - ), - 'SubscribeGroundTruth': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeGroundTruth, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeGroundTruthRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.GroundTruthResponse.SerializeToString, - ), - 'SubscribeFixedwingMetrics': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeFixedwingMetrics, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeFixedwingMetricsRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.FixedwingMetricsResponse.SerializeToString, - ), - 'SubscribeImu': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeImu, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeImuRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.ImuResponse.SerializeToString, - ), - 'SubscribeScaledImu': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeScaledImu, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeScaledImuRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.ScaledImuResponse.SerializeToString, - ), - 'SubscribeRawImu': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeRawImu, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeRawImuRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.RawImuResponse.SerializeToString, - ), - 'SubscribeHealthAllOk': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeHealthAllOk, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHealthAllOkRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.HealthAllOkResponse.SerializeToString, - ), - 'SubscribeUnixEpochTime': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeUnixEpochTime, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeUnixEpochTimeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.UnixEpochTimeResponse.SerializeToString, - ), - 'SubscribeDistanceSensor': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeDistanceSensor, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeDistanceSensorRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.DistanceSensorResponse.SerializeToString, - ), - 'SubscribeScaledPressure': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeScaledPressure, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeScaledPressureRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.ScaledPressureResponse.SerializeToString, - ), - 'SubscribeHeading': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeHeading, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHeadingRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.HeadingResponse.SerializeToString, - ), - 'SubscribeAltitude': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeAltitude, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAltitudeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.AltitudeResponse.SerializeToString, - ), - 'SubscribeWind': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeWind, - request_deserializer=telemetry_dot_telemetry__pb2.SubscribeWindRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.WindResponse.SerializeToString, - ), - 'SetRatePosition': grpc.unary_unary_rpc_method_handler( - servicer.SetRatePosition, - request_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRatePositionResponse.SerializeToString, - ), - 'SetRateHome': grpc.unary_unary_rpc_method_handler( - servicer.SetRateHome, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateHomeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateHomeResponse.SerializeToString, - ), - 'SetRateInAir': grpc.unary_unary_rpc_method_handler( - servicer.SetRateInAir, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateInAirRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateInAirResponse.SerializeToString, - ), - 'SetRateLandedState': grpc.unary_unary_rpc_method_handler( - servicer.SetRateLandedState, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateLandedStateRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateLandedStateResponse.SerializeToString, - ), - 'SetRateVtolState': grpc.unary_unary_rpc_method_handler( - servicer.SetRateVtolState, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateVtolStateRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateVtolStateResponse.SerializeToString, - ), - 'SetRateAttitudeQuaternion': grpc.unary_unary_rpc_method_handler( - servicer.SetRateAttitudeQuaternion, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionResponse.SerializeToString, - ), - 'SetRateAttitudeEuler': grpc.unary_unary_rpc_method_handler( - servicer.SetRateAttitudeEuler, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerResponse.SerializeToString, - ), - 'SetRateVelocityNed': grpc.unary_unary_rpc_method_handler( - servicer.SetRateVelocityNed, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedResponse.SerializeToString, - ), - 'SetRateGpsInfo': grpc.unary_unary_rpc_method_handler( - servicer.SetRateGpsInfo, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoResponse.SerializeToString, - ), - 'SetRateBattery': grpc.unary_unary_rpc_method_handler( - servicer.SetRateBattery, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateBatteryRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateBatteryResponse.SerializeToString, - ), - 'SetRateRcStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetRateRcStatus, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateRcStatusRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateRcStatusResponse.SerializeToString, - ), - 'SetRateActuatorControlTarget': grpc.unary_unary_rpc_method_handler( - servicer.SetRateActuatorControlTarget, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetResponse.SerializeToString, - ), - 'SetRateActuatorOutputStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetRateActuatorOutputStatus, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusResponse.SerializeToString, - ), - 'SetRateOdometry': grpc.unary_unary_rpc_method_handler( - servicer.SetRateOdometry, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateOdometryRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateOdometryResponse.SerializeToString, - ), - 'SetRatePositionVelocityNed': grpc.unary_unary_rpc_method_handler( - servicer.SetRatePositionVelocityNed, - request_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedResponse.SerializeToString, - ), - 'SetRateGroundTruth': grpc.unary_unary_rpc_method_handler( - servicer.SetRateGroundTruth, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthResponse.SerializeToString, - ), - 'SetRateFixedwingMetrics': grpc.unary_unary_rpc_method_handler( - servicer.SetRateFixedwingMetrics, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsResponse.SerializeToString, - ), - 'SetRateImu': grpc.unary_unary_rpc_method_handler( - servicer.SetRateImu, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateImuRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateImuResponse.SerializeToString, - ), - 'SetRateScaledImu': grpc.unary_unary_rpc_method_handler( - servicer.SetRateScaledImu, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateScaledImuRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateScaledImuResponse.SerializeToString, - ), - 'SetRateRawImu': grpc.unary_unary_rpc_method_handler( - servicer.SetRateRawImu, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateRawImuRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateRawImuResponse.SerializeToString, - ), - 'SetRateUnixEpochTime': grpc.unary_unary_rpc_method_handler( - servicer.SetRateUnixEpochTime, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeResponse.SerializeToString, - ), - 'SetRateDistanceSensor': grpc.unary_unary_rpc_method_handler( - servicer.SetRateDistanceSensor, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorResponse.SerializeToString, - ), - 'SetRateAltitude': grpc.unary_unary_rpc_method_handler( - servicer.SetRateAltitude, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateAltitudeRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateAltitudeResponse.SerializeToString, - ), - 'SetRateHealth': grpc.unary_unary_rpc_method_handler( - servicer.SetRateHealth, - request_deserializer=telemetry_dot_telemetry__pb2.SetRateHealthRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.SetRateHealthResponse.SerializeToString, - ), - 'GetGpsGlobalOrigin': grpc.unary_unary_rpc_method_handler( - servicer.GetGpsGlobalOrigin, - request_deserializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginRequest.FromString, - response_serializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginResponse.SerializeToString, - ), + "SubscribePosition": grpc.unary_stream_rpc_method_handler( + servicer.SubscribePosition, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribePositionRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.PositionResponse.SerializeToString, + ), + "SubscribeHome": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeHome, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHomeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.HomeResponse.SerializeToString, + ), + "SubscribeInAir": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeInAir, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeInAirRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.InAirResponse.SerializeToString, + ), + "SubscribeLandedState": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeLandedState, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeLandedStateRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.LandedStateResponse.SerializeToString, + ), + "SubscribeArmed": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeArmed, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeArmedRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.ArmedResponse.SerializeToString, + ), + "SubscribeVtolState": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeVtolState, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeVtolStateRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.VtolStateResponse.SerializeToString, + ), + "SubscribeAttitudeQuaternion": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeAttitudeQuaternion, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeQuaternionRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.AttitudeQuaternionResponse.SerializeToString, + ), + "SubscribeAttitudeEuler": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeAttitudeEuler, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeEulerRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.AttitudeEulerResponse.SerializeToString, + ), + "SubscribeAttitudeAngularVelocityBody": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeAttitudeAngularVelocityBody, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAttitudeAngularVelocityBodyRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.AttitudeAngularVelocityBodyResponse.SerializeToString, + ), + "SubscribeVelocityNed": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeVelocityNed, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeVelocityNedRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.VelocityNedResponse.SerializeToString, + ), + "SubscribeGpsInfo": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeGpsInfo, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeGpsInfoRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.GpsInfoResponse.SerializeToString, + ), + "SubscribeRawGps": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeRawGps, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeRawGpsRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.RawGpsResponse.SerializeToString, + ), + "SubscribeBattery": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeBattery, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeBatteryRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.BatteryResponse.SerializeToString, + ), + "SubscribeFlightMode": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFlightMode, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeFlightModeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.FlightModeResponse.SerializeToString, + ), + "SubscribeHealth": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeHealth, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHealthRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.HealthResponse.SerializeToString, + ), + "SubscribeRcStatus": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeRcStatus, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeRcStatusRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.RcStatusResponse.SerializeToString, + ), + "SubscribeStatusText": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStatusText, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeStatusTextRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.StatusTextResponse.SerializeToString, + ), + "SubscribeActuatorControlTarget": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeActuatorControlTarget, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeActuatorControlTargetRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.ActuatorControlTargetResponse.SerializeToString, + ), + "SubscribeActuatorOutputStatus": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeActuatorOutputStatus, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeActuatorOutputStatusRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.ActuatorOutputStatusResponse.SerializeToString, + ), + "SubscribeOdometry": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeOdometry, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeOdometryRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.OdometryResponse.SerializeToString, + ), + "SubscribePositionVelocityNed": grpc.unary_stream_rpc_method_handler( + servicer.SubscribePositionVelocityNed, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribePositionVelocityNedRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.PositionVelocityNedResponse.SerializeToString, + ), + "SubscribeGroundTruth": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeGroundTruth, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeGroundTruthRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.GroundTruthResponse.SerializeToString, + ), + "SubscribeFixedwingMetrics": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeFixedwingMetrics, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeFixedwingMetricsRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.FixedwingMetricsResponse.SerializeToString, + ), + "SubscribeImu": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeImu, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeImuRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.ImuResponse.SerializeToString, + ), + "SubscribeScaledImu": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeScaledImu, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeScaledImuRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.ScaledImuResponse.SerializeToString, + ), + "SubscribeRawImu": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeRawImu, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeRawImuRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.RawImuResponse.SerializeToString, + ), + "SubscribeHealthAllOk": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeHealthAllOk, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHealthAllOkRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.HealthAllOkResponse.SerializeToString, + ), + "SubscribeUnixEpochTime": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeUnixEpochTime, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeUnixEpochTimeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.UnixEpochTimeResponse.SerializeToString, + ), + "SubscribeDistanceSensor": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeDistanceSensor, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeDistanceSensorRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.DistanceSensorResponse.SerializeToString, + ), + "SubscribeScaledPressure": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeScaledPressure, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeScaledPressureRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.ScaledPressureResponse.SerializeToString, + ), + "SubscribeHeading": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeHeading, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeHeadingRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.HeadingResponse.SerializeToString, + ), + "SubscribeAltitude": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeAltitude, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeAltitudeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.AltitudeResponse.SerializeToString, + ), + "SubscribeWind": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeWind, + request_deserializer=telemetry_dot_telemetry__pb2.SubscribeWindRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.WindResponse.SerializeToString, + ), + "SetRatePosition": grpc.unary_unary_rpc_method_handler( + servicer.SetRatePosition, + request_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRatePositionResponse.SerializeToString, + ), + "SetRateHome": grpc.unary_unary_rpc_method_handler( + servicer.SetRateHome, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateHomeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateHomeResponse.SerializeToString, + ), + "SetRateInAir": grpc.unary_unary_rpc_method_handler( + servicer.SetRateInAir, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateInAirRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateInAirResponse.SerializeToString, + ), + "SetRateLandedState": grpc.unary_unary_rpc_method_handler( + servicer.SetRateLandedState, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateLandedStateRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateLandedStateResponse.SerializeToString, + ), + "SetRateVtolState": grpc.unary_unary_rpc_method_handler( + servicer.SetRateVtolState, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateVtolStateRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateVtolStateResponse.SerializeToString, + ), + "SetRateAttitudeQuaternion": grpc.unary_unary_rpc_method_handler( + servicer.SetRateAttitudeQuaternion, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionResponse.SerializeToString, + ), + "SetRateAttitudeEuler": grpc.unary_unary_rpc_method_handler( + servicer.SetRateAttitudeEuler, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateAttitudeEulerResponse.SerializeToString, + ), + "SetRateVelocityNed": grpc.unary_unary_rpc_method_handler( + servicer.SetRateVelocityNed, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateVelocityNedResponse.SerializeToString, + ), + "SetRateGpsInfo": grpc.unary_unary_rpc_method_handler( + servicer.SetRateGpsInfo, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateGpsInfoResponse.SerializeToString, + ), + "SetRateBattery": grpc.unary_unary_rpc_method_handler( + servicer.SetRateBattery, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateBatteryRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateBatteryResponse.SerializeToString, + ), + "SetRateRcStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetRateRcStatus, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateRcStatusRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateRcStatusResponse.SerializeToString, + ), + "SetRateActuatorControlTarget": grpc.unary_unary_rpc_method_handler( + servicer.SetRateActuatorControlTarget, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetResponse.SerializeToString, + ), + "SetRateActuatorOutputStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetRateActuatorOutputStatus, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusResponse.SerializeToString, + ), + "SetRateOdometry": grpc.unary_unary_rpc_method_handler( + servicer.SetRateOdometry, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateOdometryRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateOdometryResponse.SerializeToString, + ), + "SetRatePositionVelocityNed": grpc.unary_unary_rpc_method_handler( + servicer.SetRatePositionVelocityNed, + request_deserializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedResponse.SerializeToString, + ), + "SetRateGroundTruth": grpc.unary_unary_rpc_method_handler( + servicer.SetRateGroundTruth, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateGroundTruthResponse.SerializeToString, + ), + "SetRateFixedwingMetrics": grpc.unary_unary_rpc_method_handler( + servicer.SetRateFixedwingMetrics, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsResponse.SerializeToString, + ), + "SetRateImu": grpc.unary_unary_rpc_method_handler( + servicer.SetRateImu, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateImuRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateImuResponse.SerializeToString, + ), + "SetRateScaledImu": grpc.unary_unary_rpc_method_handler( + servicer.SetRateScaledImu, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateScaledImuRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateScaledImuResponse.SerializeToString, + ), + "SetRateRawImu": grpc.unary_unary_rpc_method_handler( + servicer.SetRateRawImu, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateRawImuRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateRawImuResponse.SerializeToString, + ), + "SetRateUnixEpochTime": grpc.unary_unary_rpc_method_handler( + servicer.SetRateUnixEpochTime, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeResponse.SerializeToString, + ), + "SetRateDistanceSensor": grpc.unary_unary_rpc_method_handler( + servicer.SetRateDistanceSensor, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateDistanceSensorResponse.SerializeToString, + ), + "SetRateAltitude": grpc.unary_unary_rpc_method_handler( + servicer.SetRateAltitude, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateAltitudeRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateAltitudeResponse.SerializeToString, + ), + "SetRateHealth": grpc.unary_unary_rpc_method_handler( + servicer.SetRateHealth, + request_deserializer=telemetry_dot_telemetry__pb2.SetRateHealthRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.SetRateHealthResponse.SerializeToString, + ), + "GetGpsGlobalOrigin": grpc.unary_unary_rpc_method_handler( + servicer.GetGpsGlobalOrigin, + request_deserializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginRequest.FromString, + response_serializer=telemetry_dot_telemetry__pb2.GetGpsGlobalOriginResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.telemetry.TelemetryService', rpc_method_handlers) + "mavsdk.rpc.telemetry.TelemetryService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.telemetry.TelemetryService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.telemetry.TelemetryService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class TelemetryService(object): """ Allow users to get vehicle telemetry and state information @@ -1053,20 +1061,22 @@ class TelemetryService(object): """ @staticmethod - def SubscribePosition(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribePosition( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribePosition', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribePosition", telemetry_dot_telemetry__pb2.SubscribePositionRequest.SerializeToString, telemetry_dot_telemetry__pb2.PositionResponse.FromString, options, @@ -1077,23 +1087,26 @@ def SubscribePosition(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeHome(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeHome( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHome', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHome", telemetry_dot_telemetry__pb2.SubscribeHomeRequest.SerializeToString, telemetry_dot_telemetry__pb2.HomeResponse.FromString, options, @@ -1104,23 +1117,26 @@ def SubscribeHome(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeInAir(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeInAir( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir", telemetry_dot_telemetry__pb2.SubscribeInAirRequest.SerializeToString, telemetry_dot_telemetry__pb2.InAirResponse.FromString, options, @@ -1131,23 +1147,26 @@ def SubscribeInAir(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeLandedState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeLandedState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState", telemetry_dot_telemetry__pb2.SubscribeLandedStateRequest.SerializeToString, telemetry_dot_telemetry__pb2.LandedStateResponse.FromString, options, @@ -1158,23 +1177,26 @@ def SubscribeLandedState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeArmed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeArmed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed", telemetry_dot_telemetry__pb2.SubscribeArmedRequest.SerializeToString, telemetry_dot_telemetry__pb2.ArmedResponse.FromString, options, @@ -1185,23 +1207,26 @@ def SubscribeArmed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeVtolState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeVtolState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeVtolState', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeVtolState", telemetry_dot_telemetry__pb2.SubscribeVtolStateRequest.SerializeToString, telemetry_dot_telemetry__pb2.VtolStateResponse.FromString, options, @@ -1212,23 +1237,26 @@ def SubscribeVtolState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeAttitudeQuaternion(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeAttitudeQuaternion( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion", telemetry_dot_telemetry__pb2.SubscribeAttitudeQuaternionRequest.SerializeToString, telemetry_dot_telemetry__pb2.AttitudeQuaternionResponse.FromString, options, @@ -1239,23 +1267,26 @@ def SubscribeAttitudeQuaternion(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeAttitudeEuler(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeAttitudeEuler( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler", telemetry_dot_telemetry__pb2.SubscribeAttitudeEulerRequest.SerializeToString, telemetry_dot_telemetry__pb2.AttitudeEulerResponse.FromString, options, @@ -1266,23 +1297,26 @@ def SubscribeAttitudeEuler(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeAttitudeAngularVelocityBody(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeAttitudeAngularVelocityBody( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody", telemetry_dot_telemetry__pb2.SubscribeAttitudeAngularVelocityBodyRequest.SerializeToString, telemetry_dot_telemetry__pb2.AttitudeAngularVelocityBodyResponse.FromString, options, @@ -1293,23 +1327,26 @@ def SubscribeAttitudeAngularVelocityBody(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed", telemetry_dot_telemetry__pb2.SubscribeVelocityNedRequest.SerializeToString, telemetry_dot_telemetry__pb2.VelocityNedResponse.FromString, options, @@ -1320,23 +1357,26 @@ def SubscribeVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeGpsInfo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeGpsInfo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo", telemetry_dot_telemetry__pb2.SubscribeGpsInfoRequest.SerializeToString, telemetry_dot_telemetry__pb2.GpsInfoResponse.FromString, options, @@ -1347,23 +1387,26 @@ def SubscribeGpsInfo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeRawGps(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeRawGps( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawGps', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawGps", telemetry_dot_telemetry__pb2.SubscribeRawGpsRequest.SerializeToString, telemetry_dot_telemetry__pb2.RawGpsResponse.FromString, options, @@ -1374,23 +1417,26 @@ def SubscribeRawGps(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeBattery(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeBattery( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeBattery', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeBattery", telemetry_dot_telemetry__pb2.SubscribeBatteryRequest.SerializeToString, telemetry_dot_telemetry__pb2.BatteryResponse.FromString, options, @@ -1401,23 +1447,26 @@ def SubscribeBattery(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeFlightMode(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeFlightMode( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeFlightMode', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeFlightMode", telemetry_dot_telemetry__pb2.SubscribeFlightModeRequest.SerializeToString, telemetry_dot_telemetry__pb2.FlightModeResponse.FromString, options, @@ -1428,23 +1477,26 @@ def SubscribeFlightMode(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeHealth(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeHealth( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth", telemetry_dot_telemetry__pb2.SubscribeHealthRequest.SerializeToString, telemetry_dot_telemetry__pb2.HealthResponse.FromString, options, @@ -1455,23 +1507,26 @@ def SubscribeHealth(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeRcStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeRcStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus", telemetry_dot_telemetry__pb2.SubscribeRcStatusRequest.SerializeToString, telemetry_dot_telemetry__pb2.RcStatusResponse.FromString, options, @@ -1482,23 +1537,26 @@ def SubscribeRcStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeStatusText(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStatusText( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText", telemetry_dot_telemetry__pb2.SubscribeStatusTextRequest.SerializeToString, telemetry_dot_telemetry__pb2.StatusTextResponse.FromString, options, @@ -1509,23 +1567,26 @@ def SubscribeStatusText(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeActuatorControlTarget(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeActuatorControlTarget( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget", telemetry_dot_telemetry__pb2.SubscribeActuatorControlTargetRequest.SerializeToString, telemetry_dot_telemetry__pb2.ActuatorControlTargetResponse.FromString, options, @@ -1536,23 +1597,26 @@ def SubscribeActuatorControlTarget(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeActuatorOutputStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeActuatorOutputStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus", telemetry_dot_telemetry__pb2.SubscribeActuatorOutputStatusRequest.SerializeToString, telemetry_dot_telemetry__pb2.ActuatorOutputStatusResponse.FromString, options, @@ -1563,23 +1627,26 @@ def SubscribeActuatorOutputStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeOdometry(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeOdometry( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry", telemetry_dot_telemetry__pb2.SubscribeOdometryRequest.SerializeToString, telemetry_dot_telemetry__pb2.OdometryResponse.FromString, options, @@ -1590,23 +1657,26 @@ def SubscribeOdometry(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribePositionVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribePositionVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribePositionVelocityNed', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribePositionVelocityNed", telemetry_dot_telemetry__pb2.SubscribePositionVelocityNedRequest.SerializeToString, telemetry_dot_telemetry__pb2.PositionVelocityNedResponse.FromString, options, @@ -1617,23 +1687,26 @@ def SubscribePositionVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeGroundTruth(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeGroundTruth( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundTruth', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundTruth", telemetry_dot_telemetry__pb2.SubscribeGroundTruthRequest.SerializeToString, telemetry_dot_telemetry__pb2.GroundTruthResponse.FromString, options, @@ -1644,23 +1717,26 @@ def SubscribeGroundTruth(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeFixedwingMetrics(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeFixedwingMetrics( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeFixedwingMetrics', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeFixedwingMetrics", telemetry_dot_telemetry__pb2.SubscribeFixedwingMetricsRequest.SerializeToString, telemetry_dot_telemetry__pb2.FixedwingMetricsResponse.FromString, options, @@ -1671,23 +1747,26 @@ def SubscribeFixedwingMetrics(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeImu', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeImu", telemetry_dot_telemetry__pb2.SubscribeImuRequest.SerializeToString, telemetry_dot_telemetry__pb2.ImuResponse.FromString, options, @@ -1698,23 +1777,26 @@ def SubscribeImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeScaledImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeScaledImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledImu', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledImu", telemetry_dot_telemetry__pb2.SubscribeScaledImuRequest.SerializeToString, telemetry_dot_telemetry__pb2.ScaledImuResponse.FromString, options, @@ -1725,23 +1807,26 @@ def SubscribeScaledImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeRawImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeRawImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawImu', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawImu", telemetry_dot_telemetry__pb2.SubscribeRawImuRequest.SerializeToString, telemetry_dot_telemetry__pb2.RawImuResponse.FromString, options, @@ -1752,23 +1837,26 @@ def SubscribeRawImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeHealthAllOk(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeHealthAllOk( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealthAllOk', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealthAllOk", telemetry_dot_telemetry__pb2.SubscribeHealthAllOkRequest.SerializeToString, telemetry_dot_telemetry__pb2.HealthAllOkResponse.FromString, options, @@ -1779,23 +1867,26 @@ def SubscribeHealthAllOk(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeUnixEpochTime(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeUnixEpochTime( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeUnixEpochTime', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeUnixEpochTime", telemetry_dot_telemetry__pb2.SubscribeUnixEpochTimeRequest.SerializeToString, telemetry_dot_telemetry__pb2.UnixEpochTimeResponse.FromString, options, @@ -1806,23 +1897,26 @@ def SubscribeUnixEpochTime(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeDistanceSensor(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeDistanceSensor( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor", telemetry_dot_telemetry__pb2.SubscribeDistanceSensorRequest.SerializeToString, telemetry_dot_telemetry__pb2.DistanceSensorResponse.FromString, options, @@ -1833,23 +1927,26 @@ def SubscribeDistanceSensor(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeScaledPressure(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeScaledPressure( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledPressure', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledPressure", telemetry_dot_telemetry__pb2.SubscribeScaledPressureRequest.SerializeToString, telemetry_dot_telemetry__pb2.ScaledPressureResponse.FromString, options, @@ -1860,23 +1957,26 @@ def SubscribeScaledPressure(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeHeading(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeHeading( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeHeading', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHeading", telemetry_dot_telemetry__pb2.SubscribeHeadingRequest.SerializeToString, telemetry_dot_telemetry__pb2.HeadingResponse.FromString, options, @@ -1887,23 +1987,26 @@ def SubscribeHeading(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeAltitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeAltitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeAltitude', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAltitude", telemetry_dot_telemetry__pb2.SubscribeAltitudeRequest.SerializeToString, telemetry_dot_telemetry__pb2.AltitudeResponse.FromString, options, @@ -1914,23 +2017,26 @@ def SubscribeAltitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SubscribeWind(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeWind( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SubscribeWind', + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeWind", telemetry_dot_telemetry__pb2.SubscribeWindRequest.SerializeToString, telemetry_dot_telemetry__pb2.WindResponse.FromString, options, @@ -1941,23 +2047,26 @@ def SubscribeWind(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRatePosition(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRatePosition( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition', + "/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition", telemetry_dot_telemetry__pb2.SetRatePositionRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRatePositionResponse.FromString, options, @@ -1968,23 +2077,26 @@ def SetRatePosition(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateHome(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateHome( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateHome', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateHome", telemetry_dot_telemetry__pb2.SetRateHomeRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateHomeResponse.FromString, options, @@ -1995,23 +2107,26 @@ def SetRateHome(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateInAir(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateInAir( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir", telemetry_dot_telemetry__pb2.SetRateInAirRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateInAirResponse.FromString, options, @@ -2022,23 +2137,26 @@ def SetRateInAir(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateLandedState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateLandedState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateLandedState', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateLandedState", telemetry_dot_telemetry__pb2.SetRateLandedStateRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateLandedStateResponse.FromString, options, @@ -2049,23 +2167,26 @@ def SetRateLandedState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateVtolState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateVtolState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateVtolState', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateVtolState", telemetry_dot_telemetry__pb2.SetRateVtolStateRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateVtolStateResponse.FromString, options, @@ -2076,23 +2197,26 @@ def SetRateVtolState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateAttitudeQuaternion(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateAttitudeQuaternion( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeQuaternion', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeQuaternion", telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateAttitudeQuaternionResponse.FromString, options, @@ -2103,23 +2227,26 @@ def SetRateAttitudeQuaternion(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateAttitudeEuler(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateAttitudeEuler( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeEuler', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeEuler", telemetry_dot_telemetry__pb2.SetRateAttitudeEulerRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateAttitudeEulerResponse.FromString, options, @@ -2130,23 +2257,26 @@ def SetRateAttitudeEuler(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed", telemetry_dot_telemetry__pb2.SetRateVelocityNedRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateVelocityNedResponse.FromString, options, @@ -2157,23 +2287,26 @@ def SetRateVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateGpsInfo(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateGpsInfo( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo", telemetry_dot_telemetry__pb2.SetRateGpsInfoRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateGpsInfoResponse.FromString, options, @@ -2184,23 +2317,26 @@ def SetRateGpsInfo(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateBattery(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateBattery( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery", telemetry_dot_telemetry__pb2.SetRateBatteryRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateBatteryResponse.FromString, options, @@ -2211,23 +2347,26 @@ def SetRateBattery(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateRcStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateRcStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateRcStatus', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateRcStatus", telemetry_dot_telemetry__pb2.SetRateRcStatusRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateRcStatusResponse.FromString, options, @@ -2238,23 +2377,26 @@ def SetRateRcStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateActuatorControlTarget(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateActuatorControlTarget( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorControlTarget', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorControlTarget", telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateActuatorControlTargetResponse.FromString, options, @@ -2265,23 +2407,26 @@ def SetRateActuatorControlTarget(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateActuatorOutputStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateActuatorOutputStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorOutputStatus', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorOutputStatus", telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateActuatorOutputStatusResponse.FromString, options, @@ -2292,23 +2437,26 @@ def SetRateActuatorOutputStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateOdometry(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateOdometry( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateOdometry', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateOdometry", telemetry_dot_telemetry__pb2.SetRateOdometryRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateOdometryResponse.FromString, options, @@ -2319,23 +2467,26 @@ def SetRateOdometry(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRatePositionVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRatePositionVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRatePositionVelocityNed', + "/mavsdk.rpc.telemetry.TelemetryService/SetRatePositionVelocityNed", telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRatePositionVelocityNedResponse.FromString, options, @@ -2346,23 +2497,26 @@ def SetRatePositionVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateGroundTruth(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateGroundTruth( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateGroundTruth', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateGroundTruth", telemetry_dot_telemetry__pb2.SetRateGroundTruthRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateGroundTruthResponse.FromString, options, @@ -2373,23 +2527,26 @@ def SetRateGroundTruth(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateFixedwingMetrics(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateFixedwingMetrics( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateFixedwingMetrics', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateFixedwingMetrics", telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateFixedwingMetricsResponse.FromString, options, @@ -2400,23 +2557,26 @@ def SetRateFixedwingMetrics(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateImu', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateImu", telemetry_dot_telemetry__pb2.SetRateImuRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateImuResponse.FromString, options, @@ -2427,23 +2587,26 @@ def SetRateImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateScaledImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateScaledImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateScaledImu', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateScaledImu", telemetry_dot_telemetry__pb2.SetRateScaledImuRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateScaledImuResponse.FromString, options, @@ -2454,23 +2617,26 @@ def SetRateScaledImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateRawImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateRawImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateRawImu', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateRawImu", telemetry_dot_telemetry__pb2.SetRateRawImuRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateRawImuResponse.FromString, options, @@ -2481,23 +2647,26 @@ def SetRateRawImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateUnixEpochTime(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateUnixEpochTime( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime", telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateUnixEpochTimeResponse.FromString, options, @@ -2508,23 +2677,26 @@ def SetRateUnixEpochTime(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateDistanceSensor(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateDistanceSensor( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor", telemetry_dot_telemetry__pb2.SetRateDistanceSensorRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateDistanceSensorResponse.FromString, options, @@ -2535,23 +2707,26 @@ def SetRateDistanceSensor(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateAltitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateAltitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateAltitude', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAltitude", telemetry_dot_telemetry__pb2.SetRateAltitudeRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateAltitudeResponse.FromString, options, @@ -2562,23 +2737,26 @@ def SetRateAltitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateHealth(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateHealth( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/SetRateHealth', + "/mavsdk.rpc.telemetry.TelemetryService/SetRateHealth", telemetry_dot_telemetry__pb2.SetRateHealthRequest.SerializeToString, telemetry_dot_telemetry__pb2.SetRateHealthResponse.FromString, options, @@ -2589,23 +2767,26 @@ def SetRateHealth(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def GetGpsGlobalOrigin(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def GetGpsGlobalOrigin( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin', + "/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin", telemetry_dot_telemetry__pb2.GetGpsGlobalOriginRequest.SerializeToString, telemetry_dot_telemetry__pb2.GetGpsGlobalOriginResponse.FromString, options, @@ -2616,4 +2797,5 @@ def GetGpsGlobalOrigin(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/telemetry_server.py b/mavsdk/telemetry_server.py index 80726104..c274c4df 100644 --- a/mavsdk/telemetry_server.py +++ b/mavsdk/telemetry_server.py @@ -8,34 +8,33 @@ class FixType(Enum): """ - GPS fix type. + GPS fix type. - Values - ------ - NO_GPS - No GPS connected + Values + ------ + NO_GPS + No GPS connected - NO_FIX - No position information, GPS is connected + NO_FIX + No position information, GPS is connected - FIX_2D - 2D position + FIX_2D + 2D position - FIX_3D - 3D position + FIX_3D + 3D position - FIX_DGPS - DGPS/SBAS aided 3D position + FIX_DGPS + DGPS/SBAS aided 3D position - RTK_FLOAT - RTK float, 3D position + RTK_FLOAT + RTK float, 3D position - RTK_FIXED - RTK Fixed, 3D position + RTK_FIXED + RTK Fixed, 3D position - """ + """ - NO_GPS = 0 NO_FIX = 1 FIX_2D = 2 @@ -62,7 +61,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_server_pb2.FIX_TYPE_NO_GPS: return FixType.NO_GPS if rpc_enum_value == telemetry_server_pb2.FIX_TYPE_NO_FIX: @@ -84,28 +83,27 @@ def __str__(self): class VtolState(Enum): """ - Maps to MAV_VTOL_STATE + Maps to MAV_VTOL_STATE - Values - ------ - UNDEFINED - Not VTOL + Values + ------ + UNDEFINED + Not VTOL - TRANSITION_TO_FW - Transitioning to fixed-wing + TRANSITION_TO_FW + Transitioning to fixed-wing - TRANSITION_TO_MC - Transitioning to multi-copter + TRANSITION_TO_MC + Transitioning to multi-copter - MC - Multi-copter + MC + Multi-copter - FW - Fixed-wing + FW + Fixed-wing - """ + """ - UNDEFINED = 0 TRANSITION_TO_FW = 1 TRANSITION_TO_MC = 2 @@ -126,7 +124,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_server_pb2.VTOL_STATE_UNDEFINED: return VtolState.UNDEFINED if rpc_enum_value == telemetry_server_pb2.VTOL_STATE_TRANSITION_TO_FW: @@ -144,37 +142,36 @@ def __str__(self): class StatusTextType(Enum): """ - Status types. + Status types. - Values - ------ - DEBUG - Debug + Values + ------ + DEBUG + Debug - INFO - Information + INFO + Information - NOTICE - Notice + NOTICE + Notice - WARNING - Warning + WARNING + Warning - ERROR - Error + ERROR + Error - CRITICAL - Critical + CRITICAL + Critical - ALERT - Alert + ALERT + Alert - EMERGENCY - Emergency + EMERGENCY + Emergency - """ + """ - DEBUG = 0 INFO = 1 NOTICE = 2 @@ -204,7 +201,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_server_pb2.STATUS_TEXT_TYPE_DEBUG: return StatusTextType.DEBUG if rpc_enum_value == telemetry_server_pb2.STATUS_TEXT_TYPE_INFO: @@ -228,28 +225,27 @@ def __str__(self): class LandedState(Enum): """ - Landed State enumeration. + Landed State enumeration. - Values - ------ - UNKNOWN - Landed state is unknown + Values + ------ + UNKNOWN + Landed state is unknown - ON_GROUND - The vehicle is on the ground + ON_GROUND + The vehicle is on the ground - IN_AIR - The vehicle is in the air + IN_AIR + The vehicle is in the air - TAKING_OFF - The vehicle is taking off + TAKING_OFF + The vehicle is taking off - LANDING - The vehicle is landing + LANDING + The vehicle is landing - """ + """ - UNKNOWN = 0 ON_GROUND = 1 IN_AIR = 2 @@ -270,7 +266,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_server_pb2.LANDED_STATE_UNKNOWN: return LandedState.UNKNOWN if rpc_enum_value == telemetry_server_pb2.LANDED_STATE_ON_GROUND: @@ -288,208 +284,157 @@ def __str__(self): class Position: """ - Position type in global coordinates. + Position type in global coordinates. - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - longitude_deg : double - Longitude in degrees (range: -180 to +180) + longitude_deg : double + Longitude in degrees (range: -180 to +180) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - relative_altitude_m : float - Altitude relative to takeoff altitude in metres + relative_altitude_m : float + Altitude relative to takeoff altitude in metres - """ - - + """ def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m, - relative_altitude_m): - """ Initializes the Position object """ + self, latitude_deg, longitude_deg, absolute_altitude_m, relative_altitude_m + ): + """Initializes the Position object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m def __eq__(self, to_compare): - """ Checks if two Position are the same """ + """Checks if two Position are the same""" try: # Try to compare - this likely fails when it is compared to a non # Position object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.relative_altitude_m == to_compare.relative_altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.relative_altitude_m == to_compare.relative_altitude_m) + ) except AttributeError: return False def __str__(self): - """ Position in string representation """ - struct_repr = ", ".join([ + """Position in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), "absolute_altitude_m: " + str(self.absolute_altitude_m), - "relative_altitude_m: " + str(self.relative_altitude_m) - ]) + "relative_altitude_m: " + str(self.relative_altitude_m), + ] + ) return f"Position: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPosition): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Position( - - rpcPosition.latitude_deg, - - - rpcPosition.longitude_deg, - - - rpcPosition.absolute_altitude_m, - - - rpcPosition.relative_altitude_m - ) + rpcPosition.latitude_deg, + rpcPosition.longitude_deg, + rpcPosition.absolute_altitude_m, + rpcPosition.relative_altitude_m, + ) def translate_to_rpc(self, rpcPosition): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPosition.latitude_deg = self.latitude_deg - - - - - + rpcPosition.longitude_deg = self.longitude_deg - - - - - + rpcPosition.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcPosition.relative_altitude_m = self.relative_altitude_m - - - class Heading: """ - Heading type used for global position + Heading type used for global position - Parameters - ---------- - heading_deg : double - Heading in degrees (range: 0 to +360) + Parameters + ---------- + heading_deg : double + Heading in degrees (range: 0 to +360) - """ - - + """ - def __init__( - self, - heading_deg): - """ Initializes the Heading object """ + def __init__(self, heading_deg): + """Initializes the Heading object""" self.heading_deg = heading_deg def __eq__(self, to_compare): - """ Checks if two Heading are the same """ + """Checks if two Heading are the same""" try: # Try to compare - this likely fails when it is compared to a non # Heading object - return \ - (self.heading_deg == to_compare.heading_deg) + return self.heading_deg == to_compare.heading_deg except AttributeError: return False def __str__(self): - """ Heading in string representation """ - struct_repr = ", ".join([ - "heading_deg: " + str(self.heading_deg) - ]) + """Heading in string representation""" + struct_repr = ", ".join(["heading_deg: " + str(self.heading_deg)]) return f"Heading: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcHeading): - """ Translates a gRPC struct to the SDK equivalent """ - return Heading( - - rpcHeading.heading_deg - ) + """Translates a gRPC struct to the SDK equivalent""" + return Heading(rpcHeading.heading_deg) def translate_to_rpc(self, rpcHeading): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcHeading.heading_deg = self.heading_deg - - - class Quaternion: """ - Quaternion type. + Quaternion type. - All rotations and axis systems follow the right-hand rule. - The Hamilton quaternion product definition is used. - A zero-rotation quaternion is represented by (1,0,0,0). - The quaternion could also be written as w + xi + yj + zk. + All rotations and axis systems follow the right-hand rule. + The Hamilton quaternion product definition is used. + A zero-rotation quaternion is represented by (1,0,0,0). + The quaternion could also be written as w + xi + yj + zk. - For more info see: https://en.wikipedia.org/wiki/Quaternion + For more info see: https://en.wikipedia.org/wiki/Quaternion - Parameters - ---------- - w : float - Quaternion entry 0, also denoted as a + Parameters + ---------- + w : float + Quaternion entry 0, also denoted as a - x : float - Quaternion entry 1, also denoted as b + x : float + Quaternion entry 1, also denoted as b - y : float - Quaternion entry 2, also denoted as c + y : float + Quaternion entry 2, also denoted as c - z : float - Quaternion entry 3, also denoted as d + z : float + Quaternion entry 3, also denoted as d - timestamp_us : uint64_t - Timestamp in microseconds + timestamp_us : uint64_t + Timestamp in microseconds - """ - - + """ - def __init__( - self, - w, - x, - y, - z, - timestamp_us): - """ Initializes the Quaternion object """ + def __init__(self, w, x, y, z, timestamp_us): + """Initializes the Quaternion object""" self.w = w self.x = x self.y = y @@ -497,435 +442,338 @@ def __init__( self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two Quaternion are the same """ + """Checks if two Quaternion are the same""" try: # Try to compare - this likely fails when it is compared to a non # Quaternion object - return \ - (self.w == to_compare.w) and \ - (self.x == to_compare.x) and \ - (self.y == to_compare.y) and \ - (self.z == to_compare.z) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.w == to_compare.w) + and (self.x == to_compare.x) + and (self.y == to_compare.y) + and (self.z == to_compare.z) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ Quaternion in string representation """ - struct_repr = ", ".join([ + """Quaternion in string representation""" + struct_repr = ", ".join( + [ "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), "z: " + str(self.z), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"Quaternion: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcQuaternion): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Quaternion( - - rpcQuaternion.w, - - - rpcQuaternion.x, - - - rpcQuaternion.y, - - - rpcQuaternion.z, - - - rpcQuaternion.timestamp_us - ) + rpcQuaternion.w, + rpcQuaternion.x, + rpcQuaternion.y, + rpcQuaternion.z, + rpcQuaternion.timestamp_us, + ) def translate_to_rpc(self, rpcQuaternion): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcQuaternion.w = self.w - - - - - + rpcQuaternion.x = self.x - - - - - + rpcQuaternion.y = self.y - - - - - + rpcQuaternion.z = self.z - - - - - + rpcQuaternion.timestamp_us = self.timestamp_us - - - class EulerAngle: """ - Euler angle type. + Euler angle type. - All rotations and axis systems follow the right-hand rule. - The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. + All rotations and axis systems follow the right-hand rule. + The Euler angles follow the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. - For more info see https://en.wikipedia.org/wiki/Euler_angles + For more info see https://en.wikipedia.org/wiki/Euler_angles - Parameters - ---------- - roll_deg : float - Roll angle in degrees, positive is banking to the right + Parameters + ---------- + roll_deg : float + Roll angle in degrees, positive is banking to the right - pitch_deg : float - Pitch angle in degrees, positive is pitching nose up + pitch_deg : float + Pitch angle in degrees, positive is pitching nose up - yaw_deg : float - Yaw angle in degrees, positive is clock-wise seen from above + yaw_deg : float + Yaw angle in degrees, positive is clock-wise seen from above - timestamp_us : uint64_t - Timestamp in microseconds + timestamp_us : uint64_t + Timestamp in microseconds - """ - - + """ - def __init__( - self, - roll_deg, - pitch_deg, - yaw_deg, - timestamp_us): - """ Initializes the EulerAngle object """ + def __init__(self, roll_deg, pitch_deg, yaw_deg, timestamp_us): + """Initializes the EulerAngle object""" self.roll_deg = roll_deg self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two EulerAngle are the same """ + """Checks if two EulerAngle are the same""" try: # Try to compare - this likely fails when it is compared to a non # EulerAngle object - return \ - (self.roll_deg == to_compare.roll_deg) and \ - (self.pitch_deg == to_compare.pitch_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.roll_deg == to_compare.roll_deg) + and (self.pitch_deg == to_compare.pitch_deg) + and (self.yaw_deg == to_compare.yaw_deg) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ EulerAngle in string representation """ - struct_repr = ", ".join([ + """EulerAngle in string representation""" + struct_repr = ", ".join( + [ "roll_deg: " + str(self.roll_deg), "pitch_deg: " + str(self.pitch_deg), "yaw_deg: " + str(self.yaw_deg), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"EulerAngle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcEulerAngle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return EulerAngle( - - rpcEulerAngle.roll_deg, - - - rpcEulerAngle.pitch_deg, - - - rpcEulerAngle.yaw_deg, - - - rpcEulerAngle.timestamp_us - ) + rpcEulerAngle.roll_deg, + rpcEulerAngle.pitch_deg, + rpcEulerAngle.yaw_deg, + rpcEulerAngle.timestamp_us, + ) def translate_to_rpc(self, rpcEulerAngle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcEulerAngle.roll_deg = self.roll_deg - - - - - + rpcEulerAngle.pitch_deg = self.pitch_deg - - - - - + rpcEulerAngle.yaw_deg = self.yaw_deg - - - - - + rpcEulerAngle.timestamp_us = self.timestamp_us - - - class AngularVelocityBody: """ - Angular velocity type. - - Parameters - ---------- - roll_rad_s : float - Roll angular velocity + Angular velocity type. - pitch_rad_s : float - Pitch angular velocity + Parameters + ---------- + roll_rad_s : float + Roll angular velocity - yaw_rad_s : float - Yaw angular velocity + pitch_rad_s : float + Pitch angular velocity - """ + yaw_rad_s : float + Yaw angular velocity - + """ - def __init__( - self, - roll_rad_s, - pitch_rad_s, - yaw_rad_s): - """ Initializes the AngularVelocityBody object """ + def __init__(self, roll_rad_s, pitch_rad_s, yaw_rad_s): + """Initializes the AngularVelocityBody object""" self.roll_rad_s = roll_rad_s self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s def __eq__(self, to_compare): - """ Checks if two AngularVelocityBody are the same """ + """Checks if two AngularVelocityBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngularVelocityBody object - return \ - (self.roll_rad_s == to_compare.roll_rad_s) and \ - (self.pitch_rad_s == to_compare.pitch_rad_s) and \ - (self.yaw_rad_s == to_compare.yaw_rad_s) + return ( + (self.roll_rad_s == to_compare.roll_rad_s) + and (self.pitch_rad_s == to_compare.pitch_rad_s) + and (self.yaw_rad_s == to_compare.yaw_rad_s) + ) except AttributeError: return False def __str__(self): - """ AngularVelocityBody in string representation """ - struct_repr = ", ".join([ + """AngularVelocityBody in string representation""" + struct_repr = ", ".join( + [ "roll_rad_s: " + str(self.roll_rad_s), "pitch_rad_s: " + str(self.pitch_rad_s), - "yaw_rad_s: " + str(self.yaw_rad_s) - ]) + "yaw_rad_s: " + str(self.yaw_rad_s), + ] + ) return f"AngularVelocityBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngularVelocityBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngularVelocityBody( - - rpcAngularVelocityBody.roll_rad_s, - - - rpcAngularVelocityBody.pitch_rad_s, - - - rpcAngularVelocityBody.yaw_rad_s - ) + rpcAngularVelocityBody.roll_rad_s, + rpcAngularVelocityBody.pitch_rad_s, + rpcAngularVelocityBody.yaw_rad_s, + ) def translate_to_rpc(self, rpcAngularVelocityBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngularVelocityBody.roll_rad_s = self.roll_rad_s - - - - - + rpcAngularVelocityBody.pitch_rad_s = self.pitch_rad_s - - - - - + rpcAngularVelocityBody.yaw_rad_s = self.yaw_rad_s - - - class GpsInfo: """ - GPS information type. - - Parameters - ---------- - num_satellites : int32_t - Number of visible satellites in use + GPS information type. - fix_type : FixType - Fix type + Parameters + ---------- + num_satellites : int32_t + Number of visible satellites in use - """ + fix_type : FixType + Fix type - + """ - def __init__( - self, - num_satellites, - fix_type): - """ Initializes the GpsInfo object """ + def __init__(self, num_satellites, fix_type): + """Initializes the GpsInfo object""" self.num_satellites = num_satellites self.fix_type = fix_type def __eq__(self, to_compare): - """ Checks if two GpsInfo are the same """ + """Checks if two GpsInfo are the same""" try: # Try to compare - this likely fails when it is compared to a non # GpsInfo object - return \ - (self.num_satellites == to_compare.num_satellites) and \ - (self.fix_type == to_compare.fix_type) + return (self.num_satellites == to_compare.num_satellites) and ( + self.fix_type == to_compare.fix_type + ) except AttributeError: return False def __str__(self): - """ GpsInfo in string representation """ - struct_repr = ", ".join([ + """GpsInfo in string representation""" + struct_repr = ", ".join( + [ "num_satellites: " + str(self.num_satellites), - "fix_type: " + str(self.fix_type) - ]) + "fix_type: " + str(self.fix_type), + ] + ) return f"GpsInfo: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGpsInfo): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GpsInfo( - - rpcGpsInfo.num_satellites, - - - FixType.translate_from_rpc(rpcGpsInfo.fix_type) - ) + rpcGpsInfo.num_satellites, FixType.translate_from_rpc(rpcGpsInfo.fix_type) + ) def translate_to_rpc(self, rpcGpsInfo): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGpsInfo.num_satellites = self.num_satellites - - - - - + rpcGpsInfo.fix_type = self.fix_type.translate_to_rpc() - - - class RawGps: """ - Raw GPS information type. + Raw GPS information type. - Warning: this is an advanced type! If you want the location of the drone, use - the position instead. This message exposes the raw values of the GNSS sensor. + Warning: this is an advanced type! If you want the location of the drone, use + the position instead. This message exposes the raw values of the GNSS sensor. - Parameters - ---------- - timestamp_us : uint64_t - Timestamp in microseconds (UNIX Epoch time or time since system boot, to be inferred) + Parameters + ---------- + timestamp_us : uint64_t + Timestamp in microseconds (UNIX Epoch time or time since system boot, to be inferred) - latitude_deg : double - Latitude in degrees (WGS84, EGM96 ellipsoid) + latitude_deg : double + Latitude in degrees (WGS84, EGM96 ellipsoid) - longitude_deg : double - Longitude in degrees (WGS84, EGM96 ellipsoid) + longitude_deg : double + Longitude in degrees (WGS84, EGM96 ellipsoid) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - hdop : float - GPS HDOP horizontal dilution of position (unitless). If unknown, set to NaN + hdop : float + GPS HDOP horizontal dilution of position (unitless). If unknown, set to NaN - vdop : float - GPS VDOP vertical dilution of position (unitless). If unknown, set to NaN + vdop : float + GPS VDOP vertical dilution of position (unitless). If unknown, set to NaN - velocity_m_s : float - Ground velocity in metres per second + velocity_m_s : float + Ground velocity in metres per second - cog_deg : float - Course over ground (NOT heading, but direction of movement) in degrees. If unknown, set to NaN + cog_deg : float + Course over ground (NOT heading, but direction of movement) in degrees. If unknown, set to NaN - altitude_ellipsoid_m : float - Altitude in metres (above WGS84, EGM96 ellipsoid) + altitude_ellipsoid_m : float + Altitude in metres (above WGS84, EGM96 ellipsoid) - horizontal_uncertainty_m : float - Position uncertainty in metres + horizontal_uncertainty_m : float + Position uncertainty in metres - vertical_uncertainty_m : float - Altitude uncertainty in metres + vertical_uncertainty_m : float + Altitude uncertainty in metres - velocity_uncertainty_m_s : float - Velocity uncertainty in metres per second + velocity_uncertainty_m_s : float + Velocity uncertainty in metres per second - heading_uncertainty_deg : float - Heading uncertainty in degrees + heading_uncertainty_deg : float + Heading uncertainty in degrees - yaw_deg : float - Yaw in earth frame from north. + yaw_deg : float + Yaw in earth frame from north. - """ - - + """ def __init__( - self, - timestamp_us, - latitude_deg, - longitude_deg, - absolute_altitude_m, - hdop, - vdop, - velocity_m_s, - cog_deg, - altitude_ellipsoid_m, - horizontal_uncertainty_m, - vertical_uncertainty_m, - velocity_uncertainty_m_s, - heading_uncertainty_deg, - yaw_deg): - """ Initializes the RawGps object """ + self, + timestamp_us, + latitude_deg, + longitude_deg, + absolute_altitude_m, + hdop, + vdop, + velocity_m_s, + cog_deg, + altitude_ellipsoid_m, + horizontal_uncertainty_m, + vertical_uncertainty_m, + velocity_uncertainty_m_s, + heading_uncertainty_deg, + yaw_deg, + ): + """Initializes the RawGps object""" self.timestamp_us = timestamp_us self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg @@ -942,32 +790,38 @@ def __init__( self.yaw_deg = yaw_deg def __eq__(self, to_compare): - """ Checks if two RawGps are the same """ + """Checks if two RawGps are the same""" try: # Try to compare - this likely fails when it is compared to a non # RawGps object - return \ - (self.timestamp_us == to_compare.timestamp_us) and \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.hdop == to_compare.hdop) and \ - (self.vdop == to_compare.vdop) and \ - (self.velocity_m_s == to_compare.velocity_m_s) and \ - (self.cog_deg == to_compare.cog_deg) and \ - (self.altitude_ellipsoid_m == to_compare.altitude_ellipsoid_m) and \ - (self.horizontal_uncertainty_m == to_compare.horizontal_uncertainty_m) and \ - (self.vertical_uncertainty_m == to_compare.vertical_uncertainty_m) and \ - (self.velocity_uncertainty_m_s == to_compare.velocity_uncertainty_m_s) and \ - (self.heading_uncertainty_deg == to_compare.heading_uncertainty_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) + return ( + (self.timestamp_us == to_compare.timestamp_us) + and (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.hdop == to_compare.hdop) + and (self.vdop == to_compare.vdop) + and (self.velocity_m_s == to_compare.velocity_m_s) + and (self.cog_deg == to_compare.cog_deg) + and (self.altitude_ellipsoid_m == to_compare.altitude_ellipsoid_m) + and ( + self.horizontal_uncertainty_m == to_compare.horizontal_uncertainty_m + ) + and (self.vertical_uncertainty_m == to_compare.vertical_uncertainty_m) + and ( + self.velocity_uncertainty_m_s == to_compare.velocity_uncertainty_m_s + ) + and (self.heading_uncertainty_deg == to_compare.heading_uncertainty_deg) + and (self.yaw_deg == to_compare.yaw_deg) + ) except AttributeError: return False def __str__(self): - """ RawGps in string representation """ - struct_repr = ", ".join([ + """RawGps in string representation""" + struct_repr = ", ".join( + [ "timestamp_us: " + str(self.timestamp_us), "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), @@ -981,837 +835,577 @@ def __str__(self): "vertical_uncertainty_m: " + str(self.vertical_uncertainty_m), "velocity_uncertainty_m_s: " + str(self.velocity_uncertainty_m_s), "heading_uncertainty_deg: " + str(self.heading_uncertainty_deg), - "yaw_deg: " + str(self.yaw_deg) - ]) + "yaw_deg: " + str(self.yaw_deg), + ] + ) return f"RawGps: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcRawGps): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return RawGps( - - rpcRawGps.timestamp_us, - - - rpcRawGps.latitude_deg, - - - rpcRawGps.longitude_deg, - - - rpcRawGps.absolute_altitude_m, - - - rpcRawGps.hdop, - - - rpcRawGps.vdop, - - - rpcRawGps.velocity_m_s, - - - rpcRawGps.cog_deg, - - - rpcRawGps.altitude_ellipsoid_m, - - - rpcRawGps.horizontal_uncertainty_m, - - - rpcRawGps.vertical_uncertainty_m, - - - rpcRawGps.velocity_uncertainty_m_s, - - - rpcRawGps.heading_uncertainty_deg, - - - rpcRawGps.yaw_deg - ) + rpcRawGps.timestamp_us, + rpcRawGps.latitude_deg, + rpcRawGps.longitude_deg, + rpcRawGps.absolute_altitude_m, + rpcRawGps.hdop, + rpcRawGps.vdop, + rpcRawGps.velocity_m_s, + rpcRawGps.cog_deg, + rpcRawGps.altitude_ellipsoid_m, + rpcRawGps.horizontal_uncertainty_m, + rpcRawGps.vertical_uncertainty_m, + rpcRawGps.velocity_uncertainty_m_s, + rpcRawGps.heading_uncertainty_deg, + rpcRawGps.yaw_deg, + ) def translate_to_rpc(self, rpcRawGps): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcRawGps.timestamp_us = self.timestamp_us - - - - - + rpcRawGps.latitude_deg = self.latitude_deg - - - - - + rpcRawGps.longitude_deg = self.longitude_deg - - - - - + rpcRawGps.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcRawGps.hdop = self.hdop - - - - - + rpcRawGps.vdop = self.vdop - - - - - + rpcRawGps.velocity_m_s = self.velocity_m_s - - - - - + rpcRawGps.cog_deg = self.cog_deg - - - - - + rpcRawGps.altitude_ellipsoid_m = self.altitude_ellipsoid_m - - - - - + rpcRawGps.horizontal_uncertainty_m = self.horizontal_uncertainty_m - - - - - + rpcRawGps.vertical_uncertainty_m = self.vertical_uncertainty_m - - - - - + rpcRawGps.velocity_uncertainty_m_s = self.velocity_uncertainty_m_s - - - - - + rpcRawGps.heading_uncertainty_deg = self.heading_uncertainty_deg - - - - - + rpcRawGps.yaw_deg = self.yaw_deg - - - class Battery: """ - Battery type. - - Parameters - ---------- - voltage_v : float - Voltage in volts + Battery type. - remaining_percent : float - Estimated battery remaining (range: 0.0 to 1.0) + Parameters + ---------- + voltage_v : float + Voltage in volts - """ + remaining_percent : float + Estimated battery remaining (range: 0.0 to 1.0) - + """ - def __init__( - self, - voltage_v, - remaining_percent): - """ Initializes the Battery object """ + def __init__(self, voltage_v, remaining_percent): + """Initializes the Battery object""" self.voltage_v = voltage_v self.remaining_percent = remaining_percent def __eq__(self, to_compare): - """ Checks if two Battery are the same """ + """Checks if two Battery are the same""" try: # Try to compare - this likely fails when it is compared to a non # Battery object - return \ - (self.voltage_v == to_compare.voltage_v) and \ - (self.remaining_percent == to_compare.remaining_percent) + return (self.voltage_v == to_compare.voltage_v) and ( + self.remaining_percent == to_compare.remaining_percent + ) except AttributeError: return False def __str__(self): - """ Battery in string representation """ - struct_repr = ", ".join([ + """Battery in string representation""" + struct_repr = ", ".join( + [ "voltage_v: " + str(self.voltage_v), - "remaining_percent: " + str(self.remaining_percent) - ]) + "remaining_percent: " + str(self.remaining_percent), + ] + ) return f"Battery: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcBattery): - """ Translates a gRPC struct to the SDK equivalent """ - return Battery( - - rpcBattery.voltage_v, - - - rpcBattery.remaining_percent - ) + """Translates a gRPC struct to the SDK equivalent""" + return Battery(rpcBattery.voltage_v, rpcBattery.remaining_percent) def translate_to_rpc(self, rpcBattery): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcBattery.voltage_v = self.voltage_v - - - - - + rpcBattery.remaining_percent = self.remaining_percent - - - class RcStatus: """ - Remote control status type. + Remote control status type. - Parameters - ---------- - was_available_once : bool - True if an RC signal has been available once + Parameters + ---------- + was_available_once : bool + True if an RC signal has been available once - is_available : bool - True if the RC signal is available now + is_available : bool + True if the RC signal is available now - signal_strength_percent : float - Signal strength (range: 0 to 100, NaN if unknown) + signal_strength_percent : float + Signal strength (range: 0 to 100, NaN if unknown) - """ - - + """ - def __init__( - self, - was_available_once, - is_available, - signal_strength_percent): - """ Initializes the RcStatus object """ + def __init__(self, was_available_once, is_available, signal_strength_percent): + """Initializes the RcStatus object""" self.was_available_once = was_available_once self.is_available = is_available self.signal_strength_percent = signal_strength_percent def __eq__(self, to_compare): - """ Checks if two RcStatus are the same """ + """Checks if two RcStatus are the same""" try: # Try to compare - this likely fails when it is compared to a non # RcStatus object - return \ - (self.was_available_once == to_compare.was_available_once) and \ - (self.is_available == to_compare.is_available) and \ - (self.signal_strength_percent == to_compare.signal_strength_percent) + return ( + (self.was_available_once == to_compare.was_available_once) + and (self.is_available == to_compare.is_available) + and (self.signal_strength_percent == to_compare.signal_strength_percent) + ) except AttributeError: return False def __str__(self): - """ RcStatus in string representation """ - struct_repr = ", ".join([ + """RcStatus in string representation""" + struct_repr = ", ".join( + [ "was_available_once: " + str(self.was_available_once), "is_available: " + str(self.is_available), - "signal_strength_percent: " + str(self.signal_strength_percent) - ]) + "signal_strength_percent: " + str(self.signal_strength_percent), + ] + ) return f"RcStatus: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcRcStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return RcStatus( - - rpcRcStatus.was_available_once, - - - rpcRcStatus.is_available, - - - rpcRcStatus.signal_strength_percent - ) + rpcRcStatus.was_available_once, + rpcRcStatus.is_available, + rpcRcStatus.signal_strength_percent, + ) def translate_to_rpc(self, rpcRcStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcRcStatus.was_available_once = self.was_available_once - - - - - + rpcRcStatus.is_available = self.is_available - - - - - + rpcRcStatus.signal_strength_percent = self.signal_strength_percent - - - class StatusText: """ - StatusText information type. + StatusText information type. - Parameters - ---------- - type : StatusTextType - Message type + Parameters + ---------- + type : StatusTextType + Message type - text : std::string - MAVLink status message + text : std::string + MAVLink status message - """ - - + """ - def __init__( - self, - type, - text): - """ Initializes the StatusText object """ + def __init__(self, type, text): + """Initializes the StatusText object""" self.type = type self.text = text def __eq__(self, to_compare): - """ Checks if two StatusText are the same """ + """Checks if two StatusText are the same""" try: # Try to compare - this likely fails when it is compared to a non # StatusText object - return \ - (self.type == to_compare.type) and \ - (self.text == to_compare.text) + return (self.type == to_compare.type) and (self.text == to_compare.text) except AttributeError: return False def __str__(self): - """ StatusText in string representation """ - struct_repr = ", ".join([ - "type: " + str(self.type), - "text: " + str(self.text) - ]) + """StatusText in string representation""" + struct_repr = ", ".join(["type: " + str(self.type), "text: " + str(self.text)]) return f"StatusText: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStatusText): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return StatusText( - - StatusTextType.translate_from_rpc(rpcStatusText.type), - - - rpcStatusText.text - ) + StatusTextType.translate_from_rpc(rpcStatusText.type), rpcStatusText.text + ) def translate_to_rpc(self, rpcStatusText): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStatusText.type = self.type.translate_to_rpc() - - - - - + rpcStatusText.text = self.text - - - class ActuatorControlTarget: """ - Actuator control target type. - - Parameters - ---------- - group : int32_t - An actuator control group is e.g. 'attitude' for the core flight controls, or 'gimbal' for a payload. + Actuator control target type. - controls : [float] - Controls normed from -1 to 1, where 0 is neutral position. + Parameters + ---------- + group : int32_t + An actuator control group is e.g. 'attitude' for the core flight controls, or 'gimbal' for a payload. - """ + controls : [float] + Controls normed from -1 to 1, where 0 is neutral position. - + """ - def __init__( - self, - group, - controls): - """ Initializes the ActuatorControlTarget object """ + def __init__(self, group, controls): + """Initializes the ActuatorControlTarget object""" self.group = group self.controls = controls def __eq__(self, to_compare): - """ Checks if two ActuatorControlTarget are the same """ + """Checks if two ActuatorControlTarget are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActuatorControlTarget object - return \ - (self.group == to_compare.group) and \ - (self.controls == to_compare.controls) + return (self.group == to_compare.group) and ( + self.controls == to_compare.controls + ) except AttributeError: return False def __str__(self): - """ ActuatorControlTarget in string representation """ - struct_repr = ", ".join([ - "group: " + str(self.group), - "controls: " + str(self.controls) - ]) + """ActuatorControlTarget in string representation""" + struct_repr = ", ".join( + ["group: " + str(self.group), "controls: " + str(self.controls)] + ) return f"ActuatorControlTarget: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActuatorControlTarget): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActuatorControlTarget( - - rpcActuatorControlTarget.group, - - - rpcActuatorControlTarget.controls - ) + rpcActuatorControlTarget.group, rpcActuatorControlTarget.controls + ) def translate_to_rpc(self, rpcActuatorControlTarget): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcActuatorControlTarget.group = self.group - - - - - + for elem in self.controls: - rpcActuatorControlTarget.controls.append(elem) - - - + rpcActuatorControlTarget.controls.append(elem) class ActuatorOutputStatus: """ - Actuator output status type. + Actuator output status type. - Parameters - ---------- - active : uint32_t - Active outputs + Parameters + ---------- + active : uint32_t + Active outputs - actuator : [float] - Servo/motor output values + actuator : [float] + Servo/motor output values - """ - - + """ - def __init__( - self, - active, - actuator): - """ Initializes the ActuatorOutputStatus object """ + def __init__(self, active, actuator): + """Initializes the ActuatorOutputStatus object""" self.active = active self.actuator = actuator def __eq__(self, to_compare): - """ Checks if two ActuatorOutputStatus are the same """ + """Checks if two ActuatorOutputStatus are the same""" try: # Try to compare - this likely fails when it is compared to a non # ActuatorOutputStatus object - return \ - (self.active == to_compare.active) and \ - (self.actuator == to_compare.actuator) + return (self.active == to_compare.active) and ( + self.actuator == to_compare.actuator + ) except AttributeError: return False def __str__(self): - """ ActuatorOutputStatus in string representation """ - struct_repr = ", ".join([ - "active: " + str(self.active), - "actuator: " + str(self.actuator) - ]) + """ActuatorOutputStatus in string representation""" + struct_repr = ", ".join( + ["active: " + str(self.active), "actuator: " + str(self.actuator)] + ) return f"ActuatorOutputStatus: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcActuatorOutputStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ActuatorOutputStatus( - - rpcActuatorOutputStatus.active, - - - rpcActuatorOutputStatus.actuator - ) + rpcActuatorOutputStatus.active, rpcActuatorOutputStatus.actuator + ) def translate_to_rpc(self, rpcActuatorOutputStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcActuatorOutputStatus.active = self.active - - - - - + for elem in self.actuator: - rpcActuatorOutputStatus.actuator.append(elem) - - - + rpcActuatorOutputStatus.actuator.append(elem) class Covariance: """ - Covariance type. - - Row-major representation of a 6x6 cross-covariance matrix - upper right triangle. - Set first to NaN if unknown. + Covariance type. - Parameters - ---------- - covariance_matrix : [float] - Representation of a covariance matrix. + Row-major representation of a 6x6 cross-covariance matrix + upper right triangle. + Set first to NaN if unknown. - """ + Parameters + ---------- + covariance_matrix : [float] + Representation of a covariance matrix. - + """ - def __init__( - self, - covariance_matrix): - """ Initializes the Covariance object """ + def __init__(self, covariance_matrix): + """Initializes the Covariance object""" self.covariance_matrix = covariance_matrix def __eq__(self, to_compare): - """ Checks if two Covariance are the same """ + """Checks if two Covariance are the same""" try: # Try to compare - this likely fails when it is compared to a non # Covariance object - return \ - (self.covariance_matrix == to_compare.covariance_matrix) + return self.covariance_matrix == to_compare.covariance_matrix except AttributeError: return False def __str__(self): - """ Covariance in string representation """ - struct_repr = ", ".join([ - "covariance_matrix: " + str(self.covariance_matrix) - ]) + """Covariance in string representation""" + struct_repr = ", ".join(["covariance_matrix: " + str(self.covariance_matrix)]) return f"Covariance: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcCovariance): - """ Translates a gRPC struct to the SDK equivalent """ - return Covariance( - - rpcCovariance.covariance_matrix - ) + """Translates a gRPC struct to the SDK equivalent""" + return Covariance(rpcCovariance.covariance_matrix) def translate_to_rpc(self, rpcCovariance): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - for elem in self.covariance_matrix: - rpcCovariance.covariance_matrix.append(elem) - - - + rpcCovariance.covariance_matrix.append(elem) class VelocityBody: """ - Velocity type, represented in the Body (X Y Z) frame and in metres/second. + Velocity type, represented in the Body (X Y Z) frame and in metres/second. - Parameters - ---------- - x_m_s : float - Velocity in X in metres/second + Parameters + ---------- + x_m_s : float + Velocity in X in metres/second - y_m_s : float - Velocity in Y in metres/second + y_m_s : float + Velocity in Y in metres/second - z_m_s : float - Velocity in Z in metres/second + z_m_s : float + Velocity in Z in metres/second - """ - - + """ - def __init__( - self, - x_m_s, - y_m_s, - z_m_s): - """ Initializes the VelocityBody object """ + def __init__(self, x_m_s, y_m_s, z_m_s): + """Initializes the VelocityBody object""" self.x_m_s = x_m_s self.y_m_s = y_m_s self.z_m_s = z_m_s def __eq__(self, to_compare): - """ Checks if two VelocityBody are the same """ + """Checks if two VelocityBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # VelocityBody object - return \ - (self.x_m_s == to_compare.x_m_s) and \ - (self.y_m_s == to_compare.y_m_s) and \ - (self.z_m_s == to_compare.z_m_s) + return ( + (self.x_m_s == to_compare.x_m_s) + and (self.y_m_s == to_compare.y_m_s) + and (self.z_m_s == to_compare.z_m_s) + ) except AttributeError: return False def __str__(self): - """ VelocityBody in string representation """ - struct_repr = ", ".join([ + """VelocityBody in string representation""" + struct_repr = ", ".join( + [ "x_m_s: " + str(self.x_m_s), "y_m_s: " + str(self.y_m_s), - "z_m_s: " + str(self.z_m_s) - ]) + "z_m_s: " + str(self.z_m_s), + ] + ) return f"VelocityBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVelocityBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VelocityBody( - - rpcVelocityBody.x_m_s, - - - rpcVelocityBody.y_m_s, - - - rpcVelocityBody.z_m_s - ) + rpcVelocityBody.x_m_s, rpcVelocityBody.y_m_s, rpcVelocityBody.z_m_s + ) def translate_to_rpc(self, rpcVelocityBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVelocityBody.x_m_s = self.x_m_s - - - - - + rpcVelocityBody.y_m_s = self.y_m_s - - - - - + rpcVelocityBody.z_m_s = self.z_m_s - - - class PositionBody: """ - Position type, represented in the Body (X Y Z) frame + Position type, represented in the Body (X Y Z) frame - Parameters - ---------- - x_m : float - X Position in metres. + Parameters + ---------- + x_m : float + X Position in metres. - y_m : float - Y Position in metres. + y_m : float + Y Position in metres. - z_m : float - Z Position in metres. + z_m : float + Z Position in metres. - """ - - + """ - def __init__( - self, - x_m, - y_m, - z_m): - """ Initializes the PositionBody object """ + def __init__(self, x_m, y_m, z_m): + """Initializes the PositionBody object""" self.x_m = x_m self.y_m = y_m self.z_m = z_m def __eq__(self, to_compare): - """ Checks if two PositionBody are the same """ + """Checks if two PositionBody are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionBody object - return \ - (self.x_m == to_compare.x_m) and \ - (self.y_m == to_compare.y_m) and \ - (self.z_m == to_compare.z_m) + return ( + (self.x_m == to_compare.x_m) + and (self.y_m == to_compare.y_m) + and (self.z_m == to_compare.z_m) + ) except AttributeError: return False def __str__(self): - """ PositionBody in string representation """ - struct_repr = ", ".join([ - "x_m: " + str(self.x_m), - "y_m: " + str(self.y_m), - "z_m: " + str(self.z_m) - ]) + """PositionBody in string representation""" + struct_repr = ", ".join( + ["x_m: " + str(self.x_m), "y_m: " + str(self.y_m), "z_m: " + str(self.z_m)] + ) return f"PositionBody: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionBody): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionBody( - - rpcPositionBody.x_m, - - - rpcPositionBody.y_m, - - - rpcPositionBody.z_m - ) + rpcPositionBody.x_m, rpcPositionBody.y_m, rpcPositionBody.z_m + ) def translate_to_rpc(self, rpcPositionBody): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionBody.x_m = self.x_m - - - - - + rpcPositionBody.y_m = self.y_m - - - - - + rpcPositionBody.z_m = self.z_m - - - class Odometry: """ - Odometry message type. + Odometry message type. - Parameters - ---------- - time_usec : uint64_t - Timestamp (0 to use Backend timestamp). + Parameters + ---------- + time_usec : uint64_t + Timestamp (0 to use Backend timestamp). - frame_id : MavFrame - Coordinate frame of reference for the pose data. + frame_id : MavFrame + Coordinate frame of reference for the pose data. - child_frame_id : MavFrame - Coordinate frame of reference for the velocity in free space (twist) data. + child_frame_id : MavFrame + Coordinate frame of reference for the velocity in free space (twist) data. - position_body : PositionBody - Position. + position_body : PositionBody + Position. - q : Quaternion - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). + q : Quaternion + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). - velocity_body : VelocityBody - Linear velocity (m/s). + velocity_body : VelocityBody + Linear velocity (m/s). - angular_velocity_body : AngularVelocityBody - Angular velocity (rad/s). + angular_velocity_body : AngularVelocityBody + Angular velocity (rad/s). - pose_covariance : Covariance - Pose cross-covariance matrix. + pose_covariance : Covariance + Pose cross-covariance matrix. - velocity_covariance : Covariance - Velocity cross-covariance matrix. + velocity_covariance : Covariance + Velocity cross-covariance matrix. - """ + """ - - class MavFrame(Enum): """ - Mavlink frame id + Mavlink frame id - Values - ------ - UNDEF - Frame is undefined. + Values + ------ + UNDEF + Frame is undefined. - BODY_NED - Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + BODY_NED + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. - VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down). + VISION_NED + Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down). - ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down). + ESTIM_NED + Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down). - """ + """ - UNDEF = 0 BODY_NED = 1 VISION_NED = 2 @@ -1829,7 +1423,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == telemetry_server_pb2.Odometry.MAV_FRAME_UNDEF: return Odometry.MavFrame.UNDEF if rpc_enum_value == telemetry_server_pb2.Odometry.MAV_FRAME_BODY_NED: @@ -1841,20 +1435,20 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - def __init__( - self, - time_usec, - frame_id, - child_frame_id, - position_body, - q, - velocity_body, - angular_velocity_body, - pose_covariance, - velocity_covariance): - """ Initializes the Odometry object """ + self, + time_usec, + frame_id, + child_frame_id, + position_body, + q, + velocity_body, + angular_velocity_body, + pose_covariance, + velocity_covariance, + ): + """Initializes the Odometry object""" self.time_usec = time_usec self.frame_id = frame_id self.child_frame_id = child_frame_id @@ -1866,27 +1460,29 @@ def __init__( self.velocity_covariance = velocity_covariance def __eq__(self, to_compare): - """ Checks if two Odometry are the same """ + """Checks if two Odometry are the same""" try: # Try to compare - this likely fails when it is compared to a non # Odometry object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.frame_id == to_compare.frame_id) and \ - (self.child_frame_id == to_compare.child_frame_id) and \ - (self.position_body == to_compare.position_body) and \ - (self.q == to_compare.q) and \ - (self.velocity_body == to_compare.velocity_body) and \ - (self.angular_velocity_body == to_compare.angular_velocity_body) and \ - (self.pose_covariance == to_compare.pose_covariance) and \ - (self.velocity_covariance == to_compare.velocity_covariance) + return ( + (self.time_usec == to_compare.time_usec) + and (self.frame_id == to_compare.frame_id) + and (self.child_frame_id == to_compare.child_frame_id) + and (self.position_body == to_compare.position_body) + and (self.q == to_compare.q) + and (self.velocity_body == to_compare.velocity_body) + and (self.angular_velocity_body == to_compare.angular_velocity_body) + and (self.pose_covariance == to_compare.pose_covariance) + and (self.velocity_covariance == to_compare.velocity_covariance) + ) except AttributeError: return False def __str__(self): - """ Odometry in string representation """ - struct_repr = ", ".join([ + """Odometry in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "frame_id: " + str(self.frame_id), "child_frame_id: " + str(self.child_frame_id), @@ -1895,696 +1491,512 @@ def __str__(self): "velocity_body: " + str(self.velocity_body), "angular_velocity_body: " + str(self.angular_velocity_body), "pose_covariance: " + str(self.pose_covariance), - "velocity_covariance: " + str(self.velocity_covariance) - ]) + "velocity_covariance: " + str(self.velocity_covariance), + ] + ) return f"Odometry: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcOdometry): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Odometry( - - rpcOdometry.time_usec, - - - Odometry.MavFrame.translate_from_rpc(rpcOdometry.frame_id), - - - Odometry.MavFrame.translate_from_rpc(rpcOdometry.child_frame_id), - - - PositionBody.translate_from_rpc(rpcOdometry.position_body), - - - Quaternion.translate_from_rpc(rpcOdometry.q), - - - VelocityBody.translate_from_rpc(rpcOdometry.velocity_body), - - - AngularVelocityBody.translate_from_rpc(rpcOdometry.angular_velocity_body), - - - Covariance.translate_from_rpc(rpcOdometry.pose_covariance), - - - Covariance.translate_from_rpc(rpcOdometry.velocity_covariance) - ) + rpcOdometry.time_usec, + Odometry.MavFrame.translate_from_rpc(rpcOdometry.frame_id), + Odometry.MavFrame.translate_from_rpc(rpcOdometry.child_frame_id), + PositionBody.translate_from_rpc(rpcOdometry.position_body), + Quaternion.translate_from_rpc(rpcOdometry.q), + VelocityBody.translate_from_rpc(rpcOdometry.velocity_body), + AngularVelocityBody.translate_from_rpc(rpcOdometry.angular_velocity_body), + Covariance.translate_from_rpc(rpcOdometry.pose_covariance), + Covariance.translate_from_rpc(rpcOdometry.velocity_covariance), + ) def translate_to_rpc(self, rpcOdometry): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcOdometry.time_usec = self.time_usec - - - - - + rpcOdometry.frame_id = self.frame_id.translate_to_rpc() - - - - - + rpcOdometry.child_frame_id = self.child_frame_id.translate_to_rpc() - - - - - + self.position_body.translate_to_rpc(rpcOdometry.position_body) - - - - - + self.q.translate_to_rpc(rpcOdometry.q) - - - - - + self.velocity_body.translate_to_rpc(rpcOdometry.velocity_body) - - - - - + self.angular_velocity_body.translate_to_rpc(rpcOdometry.angular_velocity_body) - - - - - + self.pose_covariance.translate_to_rpc(rpcOdometry.pose_covariance) - - - - - + self.velocity_covariance.translate_to_rpc(rpcOdometry.velocity_covariance) - - - class DistanceSensor: """ - DistanceSensor message type. - - Parameters - ---------- - minimum_distance_m : float - Minimum distance the sensor can measure, NaN if unknown. + DistanceSensor message type. - maximum_distance_m : float - Maximum distance the sensor can measure, NaN if unknown. + Parameters + ---------- + minimum_distance_m : float + Minimum distance the sensor can measure, NaN if unknown. - current_distance_m : float - Current distance reading, NaN if unknown. + maximum_distance_m : float + Maximum distance the sensor can measure, NaN if unknown. - """ + current_distance_m : float + Current distance reading, NaN if unknown. - + """ - def __init__( - self, - minimum_distance_m, - maximum_distance_m, - current_distance_m): - """ Initializes the DistanceSensor object """ + def __init__(self, minimum_distance_m, maximum_distance_m, current_distance_m): + """Initializes the DistanceSensor object""" self.minimum_distance_m = minimum_distance_m self.maximum_distance_m = maximum_distance_m self.current_distance_m = current_distance_m def __eq__(self, to_compare): - """ Checks if two DistanceSensor are the same """ + """Checks if two DistanceSensor are the same""" try: # Try to compare - this likely fails when it is compared to a non # DistanceSensor object - return \ - (self.minimum_distance_m == to_compare.minimum_distance_m) and \ - (self.maximum_distance_m == to_compare.maximum_distance_m) and \ - (self.current_distance_m == to_compare.current_distance_m) + return ( + (self.minimum_distance_m == to_compare.minimum_distance_m) + and (self.maximum_distance_m == to_compare.maximum_distance_m) + and (self.current_distance_m == to_compare.current_distance_m) + ) except AttributeError: return False def __str__(self): - """ DistanceSensor in string representation """ - struct_repr = ", ".join([ + """DistanceSensor in string representation""" + struct_repr = ", ".join( + [ "minimum_distance_m: " + str(self.minimum_distance_m), "maximum_distance_m: " + str(self.maximum_distance_m), - "current_distance_m: " + str(self.current_distance_m) - ]) + "current_distance_m: " + str(self.current_distance_m), + ] + ) return f"DistanceSensor: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcDistanceSensor): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return DistanceSensor( - - rpcDistanceSensor.minimum_distance_m, - - - rpcDistanceSensor.maximum_distance_m, - - - rpcDistanceSensor.current_distance_m - ) + rpcDistanceSensor.minimum_distance_m, + rpcDistanceSensor.maximum_distance_m, + rpcDistanceSensor.current_distance_m, + ) def translate_to_rpc(self, rpcDistanceSensor): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcDistanceSensor.minimum_distance_m = self.minimum_distance_m - - - - - + rpcDistanceSensor.maximum_distance_m = self.maximum_distance_m - - - - - + rpcDistanceSensor.current_distance_m = self.current_distance_m - - - class ScaledPressure: """ - Scaled Pressure message type. - - Parameters - ---------- - timestamp_us : uint64_t - Timestamp (time since system boot) + Scaled Pressure message type. - absolute_pressure_hpa : float - Absolute pressure in hPa + Parameters + ---------- + timestamp_us : uint64_t + Timestamp (time since system boot) - differential_pressure_hpa : float - Differential pressure 1 in hPa + absolute_pressure_hpa : float + Absolute pressure in hPa - temperature_deg : float - Absolute pressure temperature (in celsius) + differential_pressure_hpa : float + Differential pressure 1 in hPa - differential_pressure_temperature_deg : float - Differential pressure temperature (in celsius, 0 if not available) + temperature_deg : float + Absolute pressure temperature (in celsius) - """ + differential_pressure_temperature_deg : float + Differential pressure temperature (in celsius, 0 if not available) - + """ def __init__( - self, - timestamp_us, - absolute_pressure_hpa, - differential_pressure_hpa, - temperature_deg, - differential_pressure_temperature_deg): - """ Initializes the ScaledPressure object """ + self, + timestamp_us, + absolute_pressure_hpa, + differential_pressure_hpa, + temperature_deg, + differential_pressure_temperature_deg, + ): + """Initializes the ScaledPressure object""" self.timestamp_us = timestamp_us self.absolute_pressure_hpa = absolute_pressure_hpa self.differential_pressure_hpa = differential_pressure_hpa self.temperature_deg = temperature_deg - self.differential_pressure_temperature_deg = differential_pressure_temperature_deg + self.differential_pressure_temperature_deg = ( + differential_pressure_temperature_deg + ) def __eq__(self, to_compare): - """ Checks if two ScaledPressure are the same """ + """Checks if two ScaledPressure are the same""" try: # Try to compare - this likely fails when it is compared to a non # ScaledPressure object - return \ - (self.timestamp_us == to_compare.timestamp_us) and \ - (self.absolute_pressure_hpa == to_compare.absolute_pressure_hpa) and \ - (self.differential_pressure_hpa == to_compare.differential_pressure_hpa) and \ - (self.temperature_deg == to_compare.temperature_deg) and \ - (self.differential_pressure_temperature_deg == to_compare.differential_pressure_temperature_deg) + return ( + (self.timestamp_us == to_compare.timestamp_us) + and (self.absolute_pressure_hpa == to_compare.absolute_pressure_hpa) + and ( + self.differential_pressure_hpa + == to_compare.differential_pressure_hpa + ) + and (self.temperature_deg == to_compare.temperature_deg) + and ( + self.differential_pressure_temperature_deg + == to_compare.differential_pressure_temperature_deg + ) + ) except AttributeError: return False def __str__(self): - """ ScaledPressure in string representation """ - struct_repr = ", ".join([ + """ScaledPressure in string representation""" + struct_repr = ", ".join( + [ "timestamp_us: " + str(self.timestamp_us), "absolute_pressure_hpa: " + str(self.absolute_pressure_hpa), "differential_pressure_hpa: " + str(self.differential_pressure_hpa), "temperature_deg: " + str(self.temperature_deg), - "differential_pressure_temperature_deg: " + str(self.differential_pressure_temperature_deg) - ]) + "differential_pressure_temperature_deg: " + + str(self.differential_pressure_temperature_deg), + ] + ) return f"ScaledPressure: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcScaledPressure): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return ScaledPressure( - - rpcScaledPressure.timestamp_us, - - - rpcScaledPressure.absolute_pressure_hpa, - - - rpcScaledPressure.differential_pressure_hpa, - - - rpcScaledPressure.temperature_deg, - - - rpcScaledPressure.differential_pressure_temperature_deg - ) + rpcScaledPressure.timestamp_us, + rpcScaledPressure.absolute_pressure_hpa, + rpcScaledPressure.differential_pressure_hpa, + rpcScaledPressure.temperature_deg, + rpcScaledPressure.differential_pressure_temperature_deg, + ) def translate_to_rpc(self, rpcScaledPressure): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcScaledPressure.timestamp_us = self.timestamp_us - - - - - + rpcScaledPressure.absolute_pressure_hpa = self.absolute_pressure_hpa - - - - - + rpcScaledPressure.differential_pressure_hpa = self.differential_pressure_hpa - - - - - + rpcScaledPressure.temperature_deg = self.temperature_deg - - - - - - rpcScaledPressure.differential_pressure_temperature_deg = self.differential_pressure_temperature_deg - - - + + rpcScaledPressure.differential_pressure_temperature_deg = ( + self.differential_pressure_temperature_deg + ) class PositionNed: """ - PositionNed message type. + PositionNed message type. - Parameters - ---------- - north_m : float - Position along north direction in metres + Parameters + ---------- + north_m : float + Position along north direction in metres - east_m : float - Position along east direction in metres + east_m : float + Position along east direction in metres - down_m : float - Position along down direction in metres + down_m : float + Position along down direction in metres - """ - - + """ - def __init__( - self, - north_m, - east_m, - down_m): - """ Initializes the PositionNed object """ + def __init__(self, north_m, east_m, down_m): + """Initializes the PositionNed object""" self.north_m = north_m self.east_m = east_m self.down_m = down_m def __eq__(self, to_compare): - """ Checks if two PositionNed are the same """ + """Checks if two PositionNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionNed object - return \ - (self.north_m == to_compare.north_m) and \ - (self.east_m == to_compare.east_m) and \ - (self.down_m == to_compare.down_m) + return ( + (self.north_m == to_compare.north_m) + and (self.east_m == to_compare.east_m) + and (self.down_m == to_compare.down_m) + ) except AttributeError: return False def __str__(self): - """ PositionNed in string representation """ - struct_repr = ", ".join([ + """PositionNed in string representation""" + struct_repr = ", ".join( + [ "north_m: " + str(self.north_m), "east_m: " + str(self.east_m), - "down_m: " + str(self.down_m) - ]) + "down_m: " + str(self.down_m), + ] + ) return f"PositionNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionNed( - - rpcPositionNed.north_m, - - - rpcPositionNed.east_m, - - - rpcPositionNed.down_m - ) + rpcPositionNed.north_m, rpcPositionNed.east_m, rpcPositionNed.down_m + ) def translate_to_rpc(self, rpcPositionNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcPositionNed.north_m = self.north_m - - - - - + rpcPositionNed.east_m = self.east_m - - - - - + rpcPositionNed.down_m = self.down_m - - - class VelocityNed: """ - VelocityNed message type. + VelocityNed message type. - Parameters - ---------- - north_m_s : float - Velocity along north direction in metres per second + Parameters + ---------- + north_m_s : float + Velocity along north direction in metres per second - east_m_s : float - Velocity along east direction in metres per second + east_m_s : float + Velocity along east direction in metres per second - down_m_s : float - Velocity along down direction in metres per second + down_m_s : float + Velocity along down direction in metres per second - """ - - + """ - def __init__( - self, - north_m_s, - east_m_s, - down_m_s): - """ Initializes the VelocityNed object """ + def __init__(self, north_m_s, east_m_s, down_m_s): + """Initializes the VelocityNed object""" self.north_m_s = north_m_s self.east_m_s = east_m_s self.down_m_s = down_m_s def __eq__(self, to_compare): - """ Checks if two VelocityNed are the same """ + """Checks if two VelocityNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # VelocityNed object - return \ - (self.north_m_s == to_compare.north_m_s) and \ - (self.east_m_s == to_compare.east_m_s) and \ - (self.down_m_s == to_compare.down_m_s) + return ( + (self.north_m_s == to_compare.north_m_s) + and (self.east_m_s == to_compare.east_m_s) + and (self.down_m_s == to_compare.down_m_s) + ) except AttributeError: return False def __str__(self): - """ VelocityNed in string representation """ - struct_repr = ", ".join([ + """VelocityNed in string representation""" + struct_repr = ", ".join( + [ "north_m_s: " + str(self.north_m_s), "east_m_s: " + str(self.east_m_s), - "down_m_s: " + str(self.down_m_s) - ]) + "down_m_s: " + str(self.down_m_s), + ] + ) return f"VelocityNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcVelocityNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return VelocityNed( - - rpcVelocityNed.north_m_s, - - - rpcVelocityNed.east_m_s, - - - rpcVelocityNed.down_m_s - ) + rpcVelocityNed.north_m_s, rpcVelocityNed.east_m_s, rpcVelocityNed.down_m_s + ) def translate_to_rpc(self, rpcVelocityNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcVelocityNed.north_m_s = self.north_m_s - - - - - + rpcVelocityNed.east_m_s = self.east_m_s - - - - - + rpcVelocityNed.down_m_s = self.down_m_s - - - class PositionVelocityNed: """ - PositionVelocityNed message type. + PositionVelocityNed message type. - Parameters - ---------- - position : PositionNed - Position (NED) + Parameters + ---------- + position : PositionNed + Position (NED) - velocity : VelocityNed - Velocity (NED) + velocity : VelocityNed + Velocity (NED) - """ - - + """ - def __init__( - self, - position, - velocity): - """ Initializes the PositionVelocityNed object """ + def __init__(self, position, velocity): + """Initializes the PositionVelocityNed object""" self.position = position self.velocity = velocity def __eq__(self, to_compare): - """ Checks if two PositionVelocityNed are the same """ + """Checks if two PositionVelocityNed are the same""" try: # Try to compare - this likely fails when it is compared to a non # PositionVelocityNed object - return \ - (self.position == to_compare.position) and \ - (self.velocity == to_compare.velocity) + return (self.position == to_compare.position) and ( + self.velocity == to_compare.velocity + ) except AttributeError: return False def __str__(self): - """ PositionVelocityNed in string representation """ - struct_repr = ", ".join([ - "position: " + str(self.position), - "velocity: " + str(self.velocity) - ]) + """PositionVelocityNed in string representation""" + struct_repr = ", ".join( + ["position: " + str(self.position), "velocity: " + str(self.velocity)] + ) return f"PositionVelocityNed: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcPositionVelocityNed): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return PositionVelocityNed( - - PositionNed.translate_from_rpc(rpcPositionVelocityNed.position), - - - VelocityNed.translate_from_rpc(rpcPositionVelocityNed.velocity) - ) + PositionNed.translate_from_rpc(rpcPositionVelocityNed.position), + VelocityNed.translate_from_rpc(rpcPositionVelocityNed.velocity), + ) def translate_to_rpc(self, rpcPositionVelocityNed): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - self.position.translate_to_rpc(rpcPositionVelocityNed.position) - - - - - + self.velocity.translate_to_rpc(rpcPositionVelocityNed.velocity) - - - class GroundTruth: """ - GroundTruth message type. - - Parameters - ---------- - latitude_deg : double - Latitude in degrees (range: -90 to +90) + GroundTruth message type. - longitude_deg : double - Longitude in degrees (range: -180 to 180) + Parameters + ---------- + latitude_deg : double + Latitude in degrees (range: -90 to +90) - absolute_altitude_m : float - Altitude AMSL (above mean sea level) in metres + longitude_deg : double + Longitude in degrees (range: -180 to 180) - """ + absolute_altitude_m : float + Altitude AMSL (above mean sea level) in metres - + """ - def __init__( - self, - latitude_deg, - longitude_deg, - absolute_altitude_m): - """ Initializes the GroundTruth object """ + def __init__(self, latitude_deg, longitude_deg, absolute_altitude_m): + """Initializes the GroundTruth object""" self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m def __eq__(self, to_compare): - """ Checks if two GroundTruth are the same """ + """Checks if two GroundTruth are the same""" try: # Try to compare - this likely fails when it is compared to a non # GroundTruth object - return \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) + return ( + (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + ) except AttributeError: return False def __str__(self): - """ GroundTruth in string representation """ - struct_repr = ", ".join([ + """GroundTruth in string representation""" + struct_repr = ", ".join( + [ "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), - "absolute_altitude_m: " + str(self.absolute_altitude_m) - ]) + "absolute_altitude_m: " + str(self.absolute_altitude_m), + ] + ) return f"GroundTruth: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcGroundTruth): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return GroundTruth( - - rpcGroundTruth.latitude_deg, - - - rpcGroundTruth.longitude_deg, - - - rpcGroundTruth.absolute_altitude_m - ) + rpcGroundTruth.latitude_deg, + rpcGroundTruth.longitude_deg, + rpcGroundTruth.absolute_altitude_m, + ) def translate_to_rpc(self, rpcGroundTruth): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcGroundTruth.latitude_deg = self.latitude_deg - - - - - + rpcGroundTruth.longitude_deg = self.longitude_deg - - - - - + rpcGroundTruth.absolute_altitude_m = self.absolute_altitude_m - - - class FixedwingMetrics: """ - FixedwingMetrics message type. - - Parameters - ---------- - airspeed_m_s : float - Current indicated airspeed (IAS) in metres per second + FixedwingMetrics message type. - throttle_percentage : float - Current throttle setting (0 to 100) + Parameters + ---------- + airspeed_m_s : float + Current indicated airspeed (IAS) in metres per second - climb_rate_m_s : float - Current climb rate in metres per second + throttle_percentage : float + Current throttle setting (0 to 100) - groundspeed_m_s : float - Current groundspeed metres per second + climb_rate_m_s : float + Current climb rate in metres per second - heading_deg : float - Current heading in compass units (0-360, 0=north) + groundspeed_m_s : float + Current groundspeed metres per second - absolute_altitude_m : float - Current altitude in metres (MSL) + heading_deg : float + Current heading in compass units (0-360, 0=north) - """ + absolute_altitude_m : float + Current altitude in metres (MSL) - + """ def __init__( - self, - airspeed_m_s, - throttle_percentage, - climb_rate_m_s, - groundspeed_m_s, - heading_deg, - absolute_altitude_m): - """ Initializes the FixedwingMetrics object """ + self, + airspeed_m_s, + throttle_percentage, + climb_rate_m_s, + groundspeed_m_s, + heading_deg, + absolute_altitude_m, + ): + """Initializes the FixedwingMetrics object""" self.airspeed_m_s = airspeed_m_s self.throttle_percentage = throttle_percentage self.climb_rate_m_s = climb_rate_m_s @@ -2593,402 +2005,301 @@ def __init__( self.absolute_altitude_m = absolute_altitude_m def __eq__(self, to_compare): - """ Checks if two FixedwingMetrics are the same """ + """Checks if two FixedwingMetrics are the same""" try: # Try to compare - this likely fails when it is compared to a non # FixedwingMetrics object - return \ - (self.airspeed_m_s == to_compare.airspeed_m_s) and \ - (self.throttle_percentage == to_compare.throttle_percentage) and \ - (self.climb_rate_m_s == to_compare.climb_rate_m_s) and \ - (self.groundspeed_m_s == to_compare.groundspeed_m_s) and \ - (self.heading_deg == to_compare.heading_deg) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) + return ( + (self.airspeed_m_s == to_compare.airspeed_m_s) + and (self.throttle_percentage == to_compare.throttle_percentage) + and (self.climb_rate_m_s == to_compare.climb_rate_m_s) + and (self.groundspeed_m_s == to_compare.groundspeed_m_s) + and (self.heading_deg == to_compare.heading_deg) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + ) except AttributeError: return False def __str__(self): - """ FixedwingMetrics in string representation """ - struct_repr = ", ".join([ + """FixedwingMetrics in string representation""" + struct_repr = ", ".join( + [ "airspeed_m_s: " + str(self.airspeed_m_s), "throttle_percentage: " + str(self.throttle_percentage), "climb_rate_m_s: " + str(self.climb_rate_m_s), "groundspeed_m_s: " + str(self.groundspeed_m_s), "heading_deg: " + str(self.heading_deg), - "absolute_altitude_m: " + str(self.absolute_altitude_m) - ]) + "absolute_altitude_m: " + str(self.absolute_altitude_m), + ] + ) return f"FixedwingMetrics: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcFixedwingMetrics): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return FixedwingMetrics( - - rpcFixedwingMetrics.airspeed_m_s, - - - rpcFixedwingMetrics.throttle_percentage, - - - rpcFixedwingMetrics.climb_rate_m_s, - - - rpcFixedwingMetrics.groundspeed_m_s, - - - rpcFixedwingMetrics.heading_deg, - - - rpcFixedwingMetrics.absolute_altitude_m - ) + rpcFixedwingMetrics.airspeed_m_s, + rpcFixedwingMetrics.throttle_percentage, + rpcFixedwingMetrics.climb_rate_m_s, + rpcFixedwingMetrics.groundspeed_m_s, + rpcFixedwingMetrics.heading_deg, + rpcFixedwingMetrics.absolute_altitude_m, + ) def translate_to_rpc(self, rpcFixedwingMetrics): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcFixedwingMetrics.airspeed_m_s = self.airspeed_m_s - - - - - + rpcFixedwingMetrics.throttle_percentage = self.throttle_percentage - - - - - + rpcFixedwingMetrics.climb_rate_m_s = self.climb_rate_m_s - - - - - + rpcFixedwingMetrics.groundspeed_m_s = self.groundspeed_m_s - - - - - + rpcFixedwingMetrics.heading_deg = self.heading_deg - - - - - + rpcFixedwingMetrics.absolute_altitude_m = self.absolute_altitude_m - - - class AccelerationFrd: """ - AccelerationFrd message type. + AccelerationFrd message type. - Parameters - ---------- - forward_m_s2 : float - Acceleration in forward direction in metres per second^2 + Parameters + ---------- + forward_m_s2 : float + Acceleration in forward direction in metres per second^2 - right_m_s2 : float - Acceleration in right direction in metres per second^2 + right_m_s2 : float + Acceleration in right direction in metres per second^2 - down_m_s2 : float - Acceleration in down direction in metres per second^2 + down_m_s2 : float + Acceleration in down direction in metres per second^2 - """ - - + """ - def __init__( - self, - forward_m_s2, - right_m_s2, - down_m_s2): - """ Initializes the AccelerationFrd object """ + def __init__(self, forward_m_s2, right_m_s2, down_m_s2): + """Initializes the AccelerationFrd object""" self.forward_m_s2 = forward_m_s2 self.right_m_s2 = right_m_s2 self.down_m_s2 = down_m_s2 def __eq__(self, to_compare): - """ Checks if two AccelerationFrd are the same """ + """Checks if two AccelerationFrd are the same""" try: # Try to compare - this likely fails when it is compared to a non # AccelerationFrd object - return \ - (self.forward_m_s2 == to_compare.forward_m_s2) and \ - (self.right_m_s2 == to_compare.right_m_s2) and \ - (self.down_m_s2 == to_compare.down_m_s2) + return ( + (self.forward_m_s2 == to_compare.forward_m_s2) + and (self.right_m_s2 == to_compare.right_m_s2) + and (self.down_m_s2 == to_compare.down_m_s2) + ) except AttributeError: return False def __str__(self): - """ AccelerationFrd in string representation """ - struct_repr = ", ".join([ + """AccelerationFrd in string representation""" + struct_repr = ", ".join( + [ "forward_m_s2: " + str(self.forward_m_s2), "right_m_s2: " + str(self.right_m_s2), - "down_m_s2: " + str(self.down_m_s2) - ]) + "down_m_s2: " + str(self.down_m_s2), + ] + ) return f"AccelerationFrd: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAccelerationFrd): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AccelerationFrd( - - rpcAccelerationFrd.forward_m_s2, - - - rpcAccelerationFrd.right_m_s2, - - - rpcAccelerationFrd.down_m_s2 - ) + rpcAccelerationFrd.forward_m_s2, + rpcAccelerationFrd.right_m_s2, + rpcAccelerationFrd.down_m_s2, + ) def translate_to_rpc(self, rpcAccelerationFrd): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAccelerationFrd.forward_m_s2 = self.forward_m_s2 - - - - - + rpcAccelerationFrd.right_m_s2 = self.right_m_s2 - - - - - + rpcAccelerationFrd.down_m_s2 = self.down_m_s2 - - - class AngularVelocityFrd: """ - AngularVelocityFrd message type. + AngularVelocityFrd message type. - Parameters - ---------- - forward_rad_s : float - Angular velocity in forward direction in radians per second + Parameters + ---------- + forward_rad_s : float + Angular velocity in forward direction in radians per second - right_rad_s : float - Angular velocity in right direction in radians per second + right_rad_s : float + Angular velocity in right direction in radians per second - down_rad_s : float - Angular velocity in Down direction in radians per second + down_rad_s : float + Angular velocity in Down direction in radians per second - """ - - + """ - def __init__( - self, - forward_rad_s, - right_rad_s, - down_rad_s): - """ Initializes the AngularVelocityFrd object """ + def __init__(self, forward_rad_s, right_rad_s, down_rad_s): + """Initializes the AngularVelocityFrd object""" self.forward_rad_s = forward_rad_s self.right_rad_s = right_rad_s self.down_rad_s = down_rad_s def __eq__(self, to_compare): - """ Checks if two AngularVelocityFrd are the same """ + """Checks if two AngularVelocityFrd are the same""" try: # Try to compare - this likely fails when it is compared to a non # AngularVelocityFrd object - return \ - (self.forward_rad_s == to_compare.forward_rad_s) and \ - (self.right_rad_s == to_compare.right_rad_s) and \ - (self.down_rad_s == to_compare.down_rad_s) + return ( + (self.forward_rad_s == to_compare.forward_rad_s) + and (self.right_rad_s == to_compare.right_rad_s) + and (self.down_rad_s == to_compare.down_rad_s) + ) except AttributeError: return False def __str__(self): - """ AngularVelocityFrd in string representation """ - struct_repr = ", ".join([ + """AngularVelocityFrd in string representation""" + struct_repr = ", ".join( + [ "forward_rad_s: " + str(self.forward_rad_s), "right_rad_s: " + str(self.right_rad_s), - "down_rad_s: " + str(self.down_rad_s) - ]) + "down_rad_s: " + str(self.down_rad_s), + ] + ) return f"AngularVelocityFrd: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAngularVelocityFrd): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AngularVelocityFrd( - - rpcAngularVelocityFrd.forward_rad_s, - - - rpcAngularVelocityFrd.right_rad_s, - - - rpcAngularVelocityFrd.down_rad_s - ) + rpcAngularVelocityFrd.forward_rad_s, + rpcAngularVelocityFrd.right_rad_s, + rpcAngularVelocityFrd.down_rad_s, + ) def translate_to_rpc(self, rpcAngularVelocityFrd): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAngularVelocityFrd.forward_rad_s = self.forward_rad_s - - - - - + rpcAngularVelocityFrd.right_rad_s = self.right_rad_s - - - - - + rpcAngularVelocityFrd.down_rad_s = self.down_rad_s - - - class MagneticFieldFrd: """ - MagneticFieldFrd message type. + MagneticFieldFrd message type. - Parameters - ---------- - forward_gauss : float - Magnetic field in forward direction measured in Gauss + Parameters + ---------- + forward_gauss : float + Magnetic field in forward direction measured in Gauss - right_gauss : float - Magnetic field in East direction measured in Gauss + right_gauss : float + Magnetic field in East direction measured in Gauss - down_gauss : float - Magnetic field in Down direction measured in Gauss + down_gauss : float + Magnetic field in Down direction measured in Gauss - """ - - + """ - def __init__( - self, - forward_gauss, - right_gauss, - down_gauss): - """ Initializes the MagneticFieldFrd object """ + def __init__(self, forward_gauss, right_gauss, down_gauss): + """Initializes the MagneticFieldFrd object""" self.forward_gauss = forward_gauss self.right_gauss = right_gauss self.down_gauss = down_gauss def __eq__(self, to_compare): - """ Checks if two MagneticFieldFrd are the same """ + """Checks if two MagneticFieldFrd are the same""" try: # Try to compare - this likely fails when it is compared to a non # MagneticFieldFrd object - return \ - (self.forward_gauss == to_compare.forward_gauss) and \ - (self.right_gauss == to_compare.right_gauss) and \ - (self.down_gauss == to_compare.down_gauss) + return ( + (self.forward_gauss == to_compare.forward_gauss) + and (self.right_gauss == to_compare.right_gauss) + and (self.down_gauss == to_compare.down_gauss) + ) except AttributeError: return False def __str__(self): - """ MagneticFieldFrd in string representation """ - struct_repr = ", ".join([ + """MagneticFieldFrd in string representation""" + struct_repr = ", ".join( + [ "forward_gauss: " + str(self.forward_gauss), "right_gauss: " + str(self.right_gauss), - "down_gauss: " + str(self.down_gauss) - ]) + "down_gauss: " + str(self.down_gauss), + ] + ) return f"MagneticFieldFrd: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcMagneticFieldFrd): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return MagneticFieldFrd( - - rpcMagneticFieldFrd.forward_gauss, - - - rpcMagneticFieldFrd.right_gauss, - - - rpcMagneticFieldFrd.down_gauss - ) + rpcMagneticFieldFrd.forward_gauss, + rpcMagneticFieldFrd.right_gauss, + rpcMagneticFieldFrd.down_gauss, + ) def translate_to_rpc(self, rpcMagneticFieldFrd): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcMagneticFieldFrd.forward_gauss = self.forward_gauss - - - - - + rpcMagneticFieldFrd.right_gauss = self.right_gauss - - - - - + rpcMagneticFieldFrd.down_gauss = self.down_gauss - - - class Imu: """ - Imu message type. + Imu message type. - Parameters - ---------- - acceleration_frd : AccelerationFrd - Acceleration + Parameters + ---------- + acceleration_frd : AccelerationFrd + Acceleration - angular_velocity_frd : AngularVelocityFrd - Angular velocity + angular_velocity_frd : AngularVelocityFrd + Angular velocity - magnetic_field_frd : MagneticFieldFrd - Magnetic field + magnetic_field_frd : MagneticFieldFrd + Magnetic field - temperature_degc : float - Temperature + temperature_degc : float + Temperature - timestamp_us : uint64_t - Timestamp in microseconds + timestamp_us : uint64_t + Timestamp in microseconds - """ - - + """ def __init__( - self, - acceleration_frd, - angular_velocity_frd, - magnetic_field_frd, - temperature_degc, - timestamp_us): - """ Initializes the Imu object """ + self, + acceleration_frd, + angular_velocity_frd, + magnetic_field_frd, + temperature_degc, + timestamp_us, + ): + """Initializes the Imu object""" self.acceleration_frd = acceleration_frd self.angular_velocity_frd = angular_velocity_frd self.magnetic_field_frd = magnetic_field_frd @@ -2996,137 +2307,106 @@ def __init__( self.timestamp_us = timestamp_us def __eq__(self, to_compare): - """ Checks if two Imu are the same """ + """Checks if two Imu are the same""" try: # Try to compare - this likely fails when it is compared to a non # Imu object - return \ - (self.acceleration_frd == to_compare.acceleration_frd) and \ - (self.angular_velocity_frd == to_compare.angular_velocity_frd) and \ - (self.magnetic_field_frd == to_compare.magnetic_field_frd) and \ - (self.temperature_degc == to_compare.temperature_degc) and \ - (self.timestamp_us == to_compare.timestamp_us) + return ( + (self.acceleration_frd == to_compare.acceleration_frd) + and (self.angular_velocity_frd == to_compare.angular_velocity_frd) + and (self.magnetic_field_frd == to_compare.magnetic_field_frd) + and (self.temperature_degc == to_compare.temperature_degc) + and (self.timestamp_us == to_compare.timestamp_us) + ) except AttributeError: return False def __str__(self): - """ Imu in string representation """ - struct_repr = ", ".join([ + """Imu in string representation""" + struct_repr = ", ".join( + [ "acceleration_frd: " + str(self.acceleration_frd), "angular_velocity_frd: " + str(self.angular_velocity_frd), "magnetic_field_frd: " + str(self.magnetic_field_frd), "temperature_degc: " + str(self.temperature_degc), - "timestamp_us: " + str(self.timestamp_us) - ]) + "timestamp_us: " + str(self.timestamp_us), + ] + ) return f"Imu: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcImu): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Imu( - - AccelerationFrd.translate_from_rpc(rpcImu.acceleration_frd), - - - AngularVelocityFrd.translate_from_rpc(rpcImu.angular_velocity_frd), - - - MagneticFieldFrd.translate_from_rpc(rpcImu.magnetic_field_frd), - - - rpcImu.temperature_degc, - - - rpcImu.timestamp_us - ) + AccelerationFrd.translate_from_rpc(rpcImu.acceleration_frd), + AngularVelocityFrd.translate_from_rpc(rpcImu.angular_velocity_frd), + MagneticFieldFrd.translate_from_rpc(rpcImu.magnetic_field_frd), + rpcImu.temperature_degc, + rpcImu.timestamp_us, + ) def translate_to_rpc(self, rpcImu): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - self.acceleration_frd.translate_to_rpc(rpcImu.acceleration_frd) - - - - - + self.angular_velocity_frd.translate_to_rpc(rpcImu.angular_velocity_frd) - - - - - + self.magnetic_field_frd.translate_to_rpc(rpcImu.magnetic_field_frd) - - - - - + rpcImu.temperature_degc = self.temperature_degc - - - - - + rpcImu.timestamp_us = self.timestamp_us - - - class TelemetryServerResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for telemetry requests. + Possible results returned for telemetry requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Success: the telemetry command was accepted by the vehicle + SUCCESS + Success: the telemetry command was accepted by the vehicle - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - TIMEOUT - Request timed out + TIMEOUT + Request timed out - UNSUPPORTED - Request not supported + UNSUPPORTED + Request not supported - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -3144,7 +2424,9 @@ def translate_to_rpc(self): if self == TelemetryServerResult.Result.NO_SYSTEM: return telemetry_server_pb2.TelemetryServerResult.RESULT_NO_SYSTEM if self == TelemetryServerResult.Result.CONNECTION_ERROR: - return telemetry_server_pb2.TelemetryServerResult.RESULT_CONNECTION_ERROR + return ( + telemetry_server_pb2.TelemetryServerResult.RESULT_CONNECTION_ERROR + ) if self == TelemetryServerResult.Result.BUSY: return telemetry_server_pb2.TelemetryServerResult.RESULT_BUSY if self == TelemetryServerResult.Result.COMMAND_DENIED: @@ -3156,89 +2438,93 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_UNKNOWN + ): return TelemetryServerResult.Result.UNKNOWN - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_SUCCESS: + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_SUCCESS + ): return TelemetryServerResult.Result.SUCCESS - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_NO_SYSTEM + ): return TelemetryServerResult.Result.NO_SYSTEM - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_CONNECTION_ERROR + ): return TelemetryServerResult.Result.CONNECTION_ERROR if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_BUSY: return TelemetryServerResult.Result.BUSY - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_COMMAND_DENIED: + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_COMMAND_DENIED + ): return TelemetryServerResult.Result.COMMAND_DENIED - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_TIMEOUT: + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_TIMEOUT + ): return TelemetryServerResult.Result.TIMEOUT - if rpc_enum_value == telemetry_server_pb2.TelemetryServerResult.RESULT_UNSUPPORTED: + if ( + rpc_enum_value + == telemetry_server_pb2.TelemetryServerResult.RESULT_UNSUPPORTED + ): return TelemetryServerResult.Result.UNSUPPORTED def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the TelemetryServerResult object """ + def __init__(self, result, result_str): + """Initializes the TelemetryServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two TelemetryServerResult are the same """ + """Checks if two TelemetryServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # TelemetryServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ TelemetryServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """TelemetryServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"TelemetryServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTelemetryServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TelemetryServerResult( - - TelemetryServerResult.Result.translate_from_rpc(rpcTelemetryServerResult.result), - - - rpcTelemetryServerResult.result_str - ) + TelemetryServerResult.Result.translate_from_rpc( + rpcTelemetryServerResult.result + ), + rpcTelemetryServerResult.result_str, + ) def translate_to_rpc(self, rpcTelemetryServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTelemetryServerResult.result = self.result.translate_to_rpc() - - - - - - rpcTelemetryServerResult.result_str = self.result_str - - - + rpcTelemetryServerResult.result_str = self.result_str class TelemetryServerError(Exception): - """ Raised when a TelemetryServerResult is a fail code """ + """Raised when a TelemetryServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -3251,128 +2537,127 @@ def __str__(self): class TelemetryServer(AsyncBase): """ - Allow users to provide vehicle telemetry and state information - (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates. + Allow users to provide vehicle telemetry and state information + (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates. - Generated by dcsdkgen - MAVSDK TelemetryServer API + Generated by dcsdkgen - MAVSDK TelemetryServer API """ # Plugin name name = "TelemetryServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = telemetry_server_pb2_grpc.TelemetryServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ - return TelemetryServerResult.translate_from_rpc(response.telemetry_server_result) - + """Returns the response status and description""" + return TelemetryServerResult.translate_from_rpc( + response.telemetry_server_result + ) async def publish_position(self, position, velocity_ned, heading): """ - Publish to 'position' updates. + Publish to 'position' updates. - Parameters - ---------- - position : Position - The next position + Parameters + ---------- + position : Position + The next position - velocity_ned : VelocityNed - The next velocity (NED) + velocity_ned : VelocityNed + The next velocity (NED) - heading : Heading - Heading (yaw) in degrees + heading : Heading + Heading (yaw) in degrees - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishPositionRequest() - + position.translate_to_rpc(request.position) - - - + velocity_ned.translate_to_rpc(request.velocity_ned) - - - + heading.translate_to_rpc(request.heading) - - + response = await self._stub.PublishPosition(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_position()", position, velocity_ned, heading) - + raise TelemetryServerError( + result, "publish_position()", position, velocity_ned, heading + ) async def publish_home(self, home): """ - Publish to 'home position' updates. + Publish to 'home position' updates. - Parameters - ---------- - home : Position - The next home position + Parameters + ---------- + home : Position + The next home position - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishHomeRequest() - + home.translate_to_rpc(request.home) - - + response = await self._stub.PublishHome(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_home()", home) - - async def publish_sys_status(self, battery, rc_receiver_status, gyro_status, accel_status, mag_status, gps_status): + async def publish_sys_status( + self, + battery, + rc_receiver_status, + gyro_status, + accel_status, + mag_status, + gps_status, + ): """ - Publish 'sys status' updates. - - Parameters - ---------- - battery : Battery - The next 'battery' state - - rc_receiver_status : bool - rc receiver status - - gyro_status : bool - - accel_status : bool - - mag_status : bool - - gps_status : bool - - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Publish 'sys status' updates. + + Parameters + ---------- + battery : Battery + The next 'battery' state + + rc_receiver_status : bool + rc receiver status + + gyro_status : bool + + accel_status : bool + + mag_status : bool + + gps_status : bool + + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishSysStatusRequest() - + battery.translate_to_rpc(request.battery) - - + request.rc_receiver_status = rc_receiver_status request.gyro_status = gyro_status request.accel_status = accel_status @@ -3380,430 +2665,400 @@ async def publish_sys_status(self, battery, rc_receiver_status, gyro_status, acc request.gps_status = gps_status response = await self._stub.PublishSysStatus(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_sys_status()", battery, rc_receiver_status, gyro_status, accel_status, mag_status, gps_status) - + raise TelemetryServerError( + result, + "publish_sys_status()", + battery, + rc_receiver_status, + gyro_status, + accel_status, + mag_status, + gps_status, + ) async def publish_extended_sys_state(self, vtol_state, landed_state): """ - Publish 'extended sys state' updates. - - Parameters - ---------- - vtol_state : VtolState - - landed_state : LandedState - - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Publish 'extended sys state' updates. + + Parameters + ---------- + vtol_state : VtolState + + landed_state : LandedState + + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishExtendedSysStateRequest() - + request.vtol_state = vtol_state.translate_to_rpc() - - - + request.landed_state = landed_state.translate_to_rpc() - - + response = await self._stub.PublishExtendedSysState(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_extended_sys_state()", vtol_state, landed_state) - + raise TelemetryServerError( + result, "publish_extended_sys_state()", vtol_state, landed_state + ) async def publish_raw_gps(self, raw_gps, gps_info): """ - Publish to 'Raw GPS' updates. + Publish to 'Raw GPS' updates. - Parameters - ---------- - raw_gps : RawGps - The next 'Raw GPS' state. Warning: this is an advanced feature, use `Position` updates to get the location of the drone! + Parameters + ---------- + raw_gps : RawGps + The next 'Raw GPS' state. Warning: this is an advanced feature, use `Position` updates to get the location of the drone! - gps_info : GpsInfo - The next 'GPS info' state + gps_info : GpsInfo + The next 'GPS info' state - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishRawGpsRequest() - + raw_gps.translate_to_rpc(request.raw_gps) - - - + gps_info.translate_to_rpc(request.gps_info) - - + response = await self._stub.PublishRawGps(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_raw_gps()", raw_gps, gps_info) - async def publish_battery(self, battery): """ - Publish to 'battery' updates. + Publish to 'battery' updates. - Parameters - ---------- - battery : Battery - The next 'battery' state + Parameters + ---------- + battery : Battery + The next 'battery' state - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishBatteryRequest() - + battery.translate_to_rpc(request.battery) - - + response = await self._stub.PublishBattery(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_battery()", battery) - async def publish_status_text(self, status_text): """ - Publish to 'status text' updates. + Publish to 'status text' updates. - Parameters - ---------- - status_text : StatusText - The next 'status text' + Parameters + ---------- + status_text : StatusText + The next 'status text' - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishStatusTextRequest() - + status_text.translate_to_rpc(request.status_text) - - + response = await self._stub.PublishStatusText(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_status_text()", status_text) - async def publish_odometry(self, odometry): """ - Publish to 'odometry' updates. + Publish to 'odometry' updates. - Parameters - ---------- - odometry : Odometry - The next odometry status + Parameters + ---------- + odometry : Odometry + The next odometry status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishOdometryRequest() - + odometry.translate_to_rpc(request.odometry) - - + response = await self._stub.PublishOdometry(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_odometry()", odometry) - async def publish_position_velocity_ned(self, position_velocity_ned): """ - Publish to 'position velocity' updates. + Publish to 'position velocity' updates. - Parameters - ---------- - position_velocity_ned : PositionVelocityNed - The next position and velocity status + Parameters + ---------- + position_velocity_ned : PositionVelocityNed + The next position and velocity status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishPositionVelocityNedRequest() - + position_velocity_ned.translate_to_rpc(request.position_velocity_ned) - - + response = await self._stub.PublishPositionVelocityNed(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_position_velocity_ned()", position_velocity_ned) - + raise TelemetryServerError( + result, "publish_position_velocity_ned()", position_velocity_ned + ) async def publish_ground_truth(self, ground_truth): """ - Publish to 'ground truth' updates. + Publish to 'ground truth' updates. - Parameters - ---------- - ground_truth : GroundTruth - Ground truth position information available in simulation + Parameters + ---------- + ground_truth : GroundTruth + Ground truth position information available in simulation - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishGroundTruthRequest() - + ground_truth.translate_to_rpc(request.ground_truth) - - + response = await self._stub.PublishGroundTruth(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_ground_truth()", ground_truth) - async def publish_imu(self, imu): """ - Publish to 'IMU' updates (in SI units in NED body frame). + Publish to 'IMU' updates (in SI units in NED body frame). - Parameters - ---------- - imu : Imu - The next IMU status + Parameters + ---------- + imu : Imu + The next IMU status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishImuRequest() - + imu.translate_to_rpc(request.imu) - - + response = await self._stub.PublishImu(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_imu()", imu) - async def publish_scaled_imu(self, imu): """ - Publish to 'Scaled IMU' updates. + Publish to 'Scaled IMU' updates. - Parameters - ---------- - imu : Imu - The next scaled IMU status + Parameters + ---------- + imu : Imu + The next scaled IMU status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishScaledImuRequest() - + imu.translate_to_rpc(request.imu) - - + response = await self._stub.PublishScaledImu(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_scaled_imu()", imu) - async def publish_raw_imu(self, imu): """ - Publish to 'Raw IMU' updates. + Publish to 'Raw IMU' updates. - Parameters - ---------- - imu : Imu - The next raw IMU status + Parameters + ---------- + imu : Imu + The next raw IMU status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishRawImuRequest() - + imu.translate_to_rpc(request.imu) - - + response = await self._stub.PublishRawImu(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_raw_imu()", imu) - async def publish_unix_epoch_time(self, time_us): """ - Publish to 'unix epoch time' updates. + Publish to 'unix epoch time' updates. - Parameters - ---------- - time_us : uint64_t - The next 'unix epoch time' status + Parameters + ---------- + time_us : uint64_t + The next 'unix epoch time' status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishUnixEpochTimeRequest() request.time_us = time_us response = await self._stub.PublishUnixEpochTime(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_unix_epoch_time()", time_us) - async def publish_distance_sensor(self, distance_sensor): """ - Publish to "distance sensor" updates. + Publish to "distance sensor" updates. - Parameters - ---------- - distance_sensor : DistanceSensor - The next 'Distance Sensor' status + Parameters + ---------- + distance_sensor : DistanceSensor + The next 'Distance Sensor' status - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishDistanceSensorRequest() - + distance_sensor.translate_to_rpc(request.distance_sensor) - - + response = await self._stub.PublishDistanceSensor(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_distance_sensor()", distance_sensor) - + raise TelemetryServerError( + result, "publish_distance_sensor()", distance_sensor + ) async def publish_attitude(self, angle, angular_velocity): """ - Publish to "attitude" updates. + Publish to "attitude" updates. - Parameters - ---------- - angle : EulerAngle - roll/pitch/yaw body angles + Parameters + ---------- + angle : EulerAngle + roll/pitch/yaw body angles - angular_velocity : AngularVelocityBody - roll/pitch/yaw angular velocities + angular_velocity : AngularVelocityBody + roll/pitch/yaw angular velocities - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishAttitudeRequest() - + angle.translate_to_rpc(request.angle) - - - + angular_velocity.translate_to_rpc(request.angular_velocity) - - + response = await self._stub.PublishAttitude(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_attitude()", angle, angular_velocity) - + raise TelemetryServerError( + result, "publish_attitude()", angle, angular_velocity + ) async def publish_visual_flight_rules_hud(self, fixed_wing_metrics): """ - Publish to "Visual Flight Rules HUD" updates. - - Parameters - ---------- - fixed_wing_metrics : FixedwingMetrics - - Raises - ------ - TelemetryServerError - If the request fails. The error contains the reason for the failure. + Publish to "Visual Flight Rules HUD" updates. + + Parameters + ---------- + fixed_wing_metrics : FixedwingMetrics + + Raises + ------ + TelemetryServerError + If the request fails. The error contains the reason for the failure. """ request = telemetry_server_pb2.PublishVisualFlightRulesHudRequest() - + fixed_wing_metrics.translate_to_rpc(request.fixed_wing_metrics) - - + response = await self._stub.PublishVisualFlightRulesHud(request) - result = self._extract_result(response) if result.result != TelemetryServerResult.Result.SUCCESS: - raise TelemetryServerError(result, "publish_visual_flight_rules_hud()", fixed_wing_metrics) - \ No newline at end of file + raise TelemetryServerError( + result, "publish_visual_flight_rules_hud()", fixed_wing_metrics + ) diff --git a/mavsdk/telemetry_server_pb2.py b/mavsdk/telemetry_server_pb2.py index dd70097a..d5c311ac 100644 --- a/mavsdk/telemetry_server_pb2.py +++ b/mavsdk/telemetry_server_pb2.py @@ -4,18 +4,20 @@ # source: telemetry_server/telemetry_server.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( _runtime_version.Domain.PUBLIC, 5, 29, 0, - '', - 'telemetry_server/telemetry_server.proto' + "", + "telemetry_server/telemetry_server.proto", ) # @@protoc_insertion_point(imports) @@ -25,286 +27,478 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\'telemetry_server/telemetry_server.proto\x12\x1bmavsdk.rpc.telemetry_server\x1a\x14mavsdk_options.proto\"\xc8\x01\n\x16PublishPositionRequest\x12\x37\n\x08position\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.Position\x12>\n\x0cvelocity_ned\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.VelocityNed\x12\x35\n\x07heading\x18\x03 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.Heading\"I\n\x12PublishHomeRequest\x12\x33\n\x04home\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.Position\"\xbf\x01\n\x17PublishSysStatusRequest\x12\x35\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.Battery\x12\x1a\n\x12rc_receiver_status\x18\x02 \x01(\x08\x12\x13\n\x0bgyro_status\x18\x03 \x01(\x08\x12\x14\n\x0c\x61\x63\x63\x65l_status\x18\x04 \x01(\x08\x12\x12\n\nmag_status\x18\x05 \x01(\x08\x12\x12\n\ngps_status\x18\x06 \x01(\x08\"\x9c\x01\n\x1ePublishExtendedSysStateRequest\x12:\n\nvtol_state\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.telemetry_server.VtolState\x12>\n\x0clanded_state\x18\x02 \x01(\x0e\x32(.mavsdk.rpc.telemetry_server.LandedState\"(\n\x13PublishInAirRequest\x12\x11\n\tis_in_air\x18\x01 \x01(\x08\"[\n\x19PublishLandedStateRequest\x12>\n\x0clanded_state\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.telemetry_server.LandedState\"\x84\x01\n\x14PublishRawGpsRequest\x12\x34\n\x07raw_gps\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.telemetry_server.RawGps\x12\x36\n\x08gps_info\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.GpsInfo\"N\n\x15PublishBatteryRequest\x12\x35\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.Battery\"R\n\x16PublishRcStatusRequest\x12\x38\n\trc_status\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.RcStatus\"X\n\x18PublishStatusTextRequest\x12<\n\x0bstatus_text\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.StatusText\"Q\n\x16PublishOdometryRequest\x12\x37\n\x08odometry\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.Odometry\"t\n!PublishPositionVelocityNedRequest\x12O\n\x15position_velocity_ned\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.telemetry_server.PositionVelocityNed\"[\n\x19PublishGroundTruthRequest\x12>\n\x0cground_truth\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.GroundTruth\"B\n\x11PublishImuRequest\x12-\n\x03imu\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry_server.Imu\"H\n\x17PublishScaledImuRequest\x12-\n\x03imu\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry_server.Imu\"E\n\x14PublishRawImuRequest\x12-\n\x03imu\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry_server.Imu\".\n\x1bPublishUnixEpochTimeRequest\x12\x0f\n\x07time_us\x18\x01 \x01(\x04\"d\n\x1cPublishDistanceSensorRequest\x12\x44\n\x0f\x64istance_sensor\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.telemetry_server.DistanceSensor\"\x9c\x01\n\x16PublishAttitudeRequest\x12\x36\n\x05\x61ngle\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.EulerAngle\x12J\n\x10\x61ngular_velocity\x18\x02 \x01(\x0b\x32\x30.mavsdk.rpc.telemetry_server.AngularVelocityBody\"o\n\"PublishVisualFlightRulesHudRequest\x12I\n\x12\x66ixed_wing_metrics\x18\x01 \x01(\x0b\x32-.mavsdk.rpc.telemetry_server.FixedwingMetrics\"n\n\x17PublishPositionResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"j\n\x13PublishHomeResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"o\n\x18PublishSysStatusResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"v\n\x1fPublishExtendedSysStateResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"l\n\x15PublishRawGpsResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"m\n\x16PublishBatteryResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"p\n\x19PublishStatusTextResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"n\n\x17PublishOdometryResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"y\n\"PublishPositionVelocityNedResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"q\n\x1aPublishGroundTruthResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"i\n\x12PublishImuResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"o\n\x18PublishScaledImuResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"l\n\x15PublishRawImuResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"s\n\x1cPublishUnixEpochTimeResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"t\n\x1dPublishDistanceSensorResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"n\n\x17PublishAttitudeResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"z\n#PublishVisualFlightRulesHudResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult\"\x95\x01\n\x08Position\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13relative_altitude_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\'\n\x07Heading\x12\x1c\n\x0bheading_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\"r\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04\"s\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x04 \x01(\x04\"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"`\n\x07GpsInfo\x12\x1d\n\x0enum_satellites\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x36\n\x08\x66ix_type\x18\x02 \x01(\x0e\x32$.mavsdk.rpc.telemetry_server.FixType\"\xdf\x02\n\x06RawGps\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x04 \x01(\x02\x12\x0c\n\x04hdop\x18\x05 \x01(\x02\x12\x0c\n\x04vdop\x18\x06 \x01(\x02\x12\x14\n\x0cvelocity_m_s\x18\x07 \x01(\x02\x12\x0f\n\x07\x63og_deg\x18\x08 \x01(\x02\x12\x1c\n\x14\x61ltitude_ellipsoid_m\x18\t \x01(\x02\x12 \n\x18horizontal_uncertainty_m\x18\n \x01(\x02\x12\x1e\n\x16vertical_uncertainty_m\x18\x0b \x01(\x02\x12 \n\x18velocity_uncertainty_m_s\x18\x0c \x01(\x02\x12\x1f\n\x17heading_uncertainty_deg\x18\r \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x0e \x01(\x02\"I\n\x07\x42\x61ttery\x12\x1a\n\tvoltage_v\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x11remaining_percent\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"|\n\x08RcStatus\x12%\n\x12was_available_once\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1f\n\x0cis_available\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x17signal_strength_percent\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"U\n\nStatusText\x12\x39\n\x04type\x18\x01 \x01(\x0e\x32+.mavsdk.rpc.telemetry_server.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t\"?\n\x15\x41\x63tuatorControlTarget\x12\x14\n\x05group\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x63ontrols\x18\x02 \x03(\x02\"?\n\x14\x41\x63tuatorOutputStatus\x12\x15\n\x06\x61\x63tive\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x61\x63tuator\x18\x02 \x03(\x02\"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02\";\n\x0cVelocityBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02\"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02\"\xa4\x05\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12@\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32..mavsdk.rpc.telemetry_server.Odometry.MavFrame\x12\x46\n\x0e\x63hild_frame_id\x18\x03 \x01(\x0e\x32..mavsdk.rpc.telemetry_server.Odometry.MavFrame\x12@\n\rposition_body\x18\x04 \x01(\x0b\x32).mavsdk.rpc.telemetry_server.PositionBody\x12\x32\n\x01q\x18\x05 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.Quaternion\x12@\n\rvelocity_body\x18\x06 \x01(\x0b\x32).mavsdk.rpc.telemetry_server.VelocityBody\x12O\n\x15\x61ngular_velocity_body\x18\x07 \x01(\x0b\x32\x30.mavsdk.rpc.telemetry_server.AngularVelocityBody\x12@\n\x0fpose_covariance\x18\x08 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.Covariance\x12\x44\n\x13velocity_covariance\x18\t \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.Covariance\"j\n\x08MavFrame\x12\x13\n\x0fMAV_FRAME_UNDEF\x10\x00\x12\x16\n\x12MAV_FRAME_BODY_NED\x10\x08\x12\x18\n\x14MAV_FRAME_VISION_NED\x10\x10\x12\x17\n\x13MAV_FRAME_ESTIM_NED\x10\x12\"\x7f\n\x0e\x44istanceSensor\x12#\n\x12minimum_distance_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12maximum_distance_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x63urrent_distance_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xb0\x01\n\x0eScaledPressure\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x1d\n\x15\x61\x62solute_pressure_hpa\x18\x02 \x01(\x02\x12!\n\x19\x64ifferential_pressure_hpa\x18\x03 \x01(\x02\x12\x17\n\x0ftemperature_deg\x18\x04 \x01(\x02\x12-\n%differential_pressure_temperature_deg\x18\x05 \x01(\x02\"Y\n\x0bPositionNed\x12\x18\n\x07north_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x64own_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"D\n\x0bVelocityNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\"\x8d\x01\n\x13PositionVelocityNed\x12:\n\x08position\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.PositionNed\x12:\n\x08velocity\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.VelocityNed\"r\n\x0bGroundTruth\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xde\x01\n\x10\x46ixedwingMetrics\x12\x1d\n\x0c\x61irspeed_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13throttle_percentage\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0e\x63limb_rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12 \n\x0fgroundspeed_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bheading_deg\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"i\n\x0f\x41\x63\x63\x65lerationFrd\x12\x1d\n\x0c\x66orward_m_s2\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\nright_m_s2\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tdown_m_s2\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"o\n\x12\x41ngularVelocityFrd\x12\x1e\n\rforward_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"m\n\x10MagneticFieldFrd\x12\x1e\n\rforward_gauss\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_gauss\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_gauss\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xa0\x02\n\x03Imu\x12\x46\n\x10\x61\x63\x63\x65leration_frd\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.telemetry_server.AccelerationFrd\x12M\n\x14\x61ngular_velocity_frd\x18\x02 \x01(\x0b\x32/.mavsdk.rpc.telemetry_server.AngularVelocityFrd\x12I\n\x12magnetic_field_frd\x18\x03 \x01(\x0b\x32-.mavsdk.rpc.telemetry_server.MagneticFieldFrd\x12!\n\x10temperature_degc\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04\"\xb4\x02\n\x15TelemetryServerResult\x12I\n\x06result\x18\x01 \x01(\x0e\x32\x39.mavsdk.rpc.telemetry_server.TelemetryServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xbb\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\x16\n\x12RESULT_UNSUPPORTED\x10\x07*\xa4\x01\n\x07\x46ixType\x12\x13\n\x0f\x46IX_TYPE_NO_GPS\x10\x00\x12\x13\n\x0f\x46IX_TYPE_NO_FIX\x10\x01\x12\x13\n\x0f\x46IX_TYPE_FIX_2D\x10\x02\x12\x13\n\x0f\x46IX_TYPE_FIX_3D\x10\x03\x12\x15\n\x11\x46IX_TYPE_FIX_DGPS\x10\x04\x12\x16\n\x12\x46IX_TYPE_RTK_FLOAT\x10\x05\x12\x16\n\x12\x46IX_TYPE_RTK_FIXED\x10\x06*\x8d\x01\n\tVtolState\x12\x18\n\x14VTOL_STATE_UNDEFINED\x10\x00\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_FW\x10\x01\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_MC\x10\x02\x12\x11\n\rVTOL_STATE_MC\x10\x03\x12\x11\n\rVTOL_STATE_FW\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*\x93\x01\n\x0bLandedState\x12\x18\n\x14LANDED_STATE_UNKNOWN\x10\x00\x12\x1a\n\x16LANDED_STATE_ON_GROUND\x10\x01\x12\x17\n\x13LANDED_STATE_IN_AIR\x10\x02\x12\x1b\n\x17LANDED_STATE_TAKING_OFF\x10\x03\x12\x18\n\x14LANDED_STATE_LANDING\x10\x04\x32\xd1\x12\n\x16TelemetryServerService\x12\x82\x01\n\x0fPublishPosition\x12\x33.mavsdk.rpc.telemetry_server.PublishPositionRequest\x1a\x34.mavsdk.rpc.telemetry_server.PublishPositionResponse\"\x04\x80\xb5\x18\x01\x12v\n\x0bPublishHome\x12/.mavsdk.rpc.telemetry_server.PublishHomeRequest\x1a\x30.mavsdk.rpc.telemetry_server.PublishHomeResponse\"\x04\x80\xb5\x18\x01\x12\x85\x01\n\x10PublishSysStatus\x12\x34.mavsdk.rpc.telemetry_server.PublishSysStatusRequest\x1a\x35.mavsdk.rpc.telemetry_server.PublishSysStatusResponse\"\x04\x80\xb5\x18\x01\x12\x9a\x01\n\x17PublishExtendedSysState\x12;.mavsdk.rpc.telemetry_server.PublishExtendedSysStateRequest\x1a<.mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse\"\x04\x80\xb5\x18\x01\x12|\n\rPublishRawGps\x12\x31.mavsdk.rpc.telemetry_server.PublishRawGpsRequest\x1a\x32.mavsdk.rpc.telemetry_server.PublishRawGpsResponse\"\x04\x80\xb5\x18\x01\x12\x7f\n\x0ePublishBattery\x12\x32.mavsdk.rpc.telemetry_server.PublishBatteryRequest\x1a\x33.mavsdk.rpc.telemetry_server.PublishBatteryResponse\"\x04\x80\xb5\x18\x01\x12\x88\x01\n\x11PublishStatusText\x12\x35.mavsdk.rpc.telemetry_server.PublishStatusTextRequest\x1a\x36.mavsdk.rpc.telemetry_server.PublishStatusTextResponse\"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x0fPublishOdometry\x12\x33.mavsdk.rpc.telemetry_server.PublishOdometryRequest\x1a\x34.mavsdk.rpc.telemetry_server.PublishOdometryResponse\"\x04\x80\xb5\x18\x01\x12\xa3\x01\n\x1aPublishPositionVelocityNed\x12>.mavsdk.rpc.telemetry_server.PublishPositionVelocityNedRequest\x1a?.mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse\"\x04\x80\xb5\x18\x01\x12\x8b\x01\n\x12PublishGroundTruth\x12\x36.mavsdk.rpc.telemetry_server.PublishGroundTruthRequest\x1a\x37.mavsdk.rpc.telemetry_server.PublishGroundTruthResponse\"\x04\x80\xb5\x18\x01\x12s\n\nPublishImu\x12..mavsdk.rpc.telemetry_server.PublishImuRequest\x1a/.mavsdk.rpc.telemetry_server.PublishImuResponse\"\x04\x80\xb5\x18\x01\x12\x85\x01\n\x10PublishScaledImu\x12\x34.mavsdk.rpc.telemetry_server.PublishScaledImuRequest\x1a\x35.mavsdk.rpc.telemetry_server.PublishScaledImuResponse\"\x04\x80\xb5\x18\x01\x12|\n\rPublishRawImu\x12\x31.mavsdk.rpc.telemetry_server.PublishRawImuRequest\x1a\x32.mavsdk.rpc.telemetry_server.PublishRawImuResponse\"\x04\x80\xb5\x18\x01\x12\x91\x01\n\x14PublishUnixEpochTime\x12\x38.mavsdk.rpc.telemetry_server.PublishUnixEpochTimeRequest\x1a\x39.mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse\"\x04\x80\xb5\x18\x01\x12\x94\x01\n\x15PublishDistanceSensor\x12\x39.mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest\x1a:.mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse\"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x0fPublishAttitude\x12\x33.mavsdk.rpc.telemetry_server.PublishAttitudeRequest\x1a\x34.mavsdk.rpc.telemetry_server.PublishAttitudeResponse\"\x04\x80\xb5\x18\x01\x12\xa6\x01\n\x1bPublishVisualFlightRulesHud\x12?.mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest\x1a@.mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse\"\x04\x80\xb5\x18\x01\x42\x32\n\x1aio.mavsdk.telemetry_serverB\x14TelemetryServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\'telemetry_server/telemetry_server.proto\x12\x1bmavsdk.rpc.telemetry_server\x1a\x14mavsdk_options.proto"\xc8\x01\n\x16PublishPositionRequest\x12\x37\n\x08position\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.Position\x12>\n\x0cvelocity_ned\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.VelocityNed\x12\x35\n\x07heading\x18\x03 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.Heading"I\n\x12PublishHomeRequest\x12\x33\n\x04home\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.Position"\xbf\x01\n\x17PublishSysStatusRequest\x12\x35\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.Battery\x12\x1a\n\x12rc_receiver_status\x18\x02 \x01(\x08\x12\x13\n\x0bgyro_status\x18\x03 \x01(\x08\x12\x14\n\x0c\x61\x63\x63\x65l_status\x18\x04 \x01(\x08\x12\x12\n\nmag_status\x18\x05 \x01(\x08\x12\x12\n\ngps_status\x18\x06 \x01(\x08"\x9c\x01\n\x1ePublishExtendedSysStateRequest\x12:\n\nvtol_state\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.telemetry_server.VtolState\x12>\n\x0clanded_state\x18\x02 \x01(\x0e\x32(.mavsdk.rpc.telemetry_server.LandedState"(\n\x13PublishInAirRequest\x12\x11\n\tis_in_air\x18\x01 \x01(\x08"[\n\x19PublishLandedStateRequest\x12>\n\x0clanded_state\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.telemetry_server.LandedState"\x84\x01\n\x14PublishRawGpsRequest\x12\x34\n\x07raw_gps\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.telemetry_server.RawGps\x12\x36\n\x08gps_info\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.GpsInfo"N\n\x15PublishBatteryRequest\x12\x35\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry_server.Battery"R\n\x16PublishRcStatusRequest\x12\x38\n\trc_status\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.RcStatus"X\n\x18PublishStatusTextRequest\x12<\n\x0bstatus_text\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.StatusText"Q\n\x16PublishOdometryRequest\x12\x37\n\x08odometry\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry_server.Odometry"t\n!PublishPositionVelocityNedRequest\x12O\n\x15position_velocity_ned\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.telemetry_server.PositionVelocityNed"[\n\x19PublishGroundTruthRequest\x12>\n\x0cground_truth\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.GroundTruth"B\n\x11PublishImuRequest\x12-\n\x03imu\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry_server.Imu"H\n\x17PublishScaledImuRequest\x12-\n\x03imu\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry_server.Imu"E\n\x14PublishRawImuRequest\x12-\n\x03imu\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry_server.Imu".\n\x1bPublishUnixEpochTimeRequest\x12\x0f\n\x07time_us\x18\x01 \x01(\x04"d\n\x1cPublishDistanceSensorRequest\x12\x44\n\x0f\x64istance_sensor\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.telemetry_server.DistanceSensor"\x9c\x01\n\x16PublishAttitudeRequest\x12\x36\n\x05\x61ngle\x18\x01 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.EulerAngle\x12J\n\x10\x61ngular_velocity\x18\x02 \x01(\x0b\x32\x30.mavsdk.rpc.telemetry_server.AngularVelocityBody"o\n"PublishVisualFlightRulesHudRequest\x12I\n\x12\x66ixed_wing_metrics\x18\x01 \x01(\x0b\x32-.mavsdk.rpc.telemetry_server.FixedwingMetrics"n\n\x17PublishPositionResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"j\n\x13PublishHomeResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"o\n\x18PublishSysStatusResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"v\n\x1fPublishExtendedSysStateResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"l\n\x15PublishRawGpsResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"m\n\x16PublishBatteryResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"p\n\x19PublishStatusTextResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"n\n\x17PublishOdometryResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"y\n"PublishPositionVelocityNedResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"q\n\x1aPublishGroundTruthResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"i\n\x12PublishImuResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"o\n\x18PublishScaledImuResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"l\n\x15PublishRawImuResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"s\n\x1cPublishUnixEpochTimeResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"t\n\x1dPublishDistanceSensorResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"n\n\x17PublishAttitudeResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"z\n#PublishVisualFlightRulesHudResponse\x12S\n\x17telemetry_server_result\x18\x01 \x01(\x0b\x32\x32.mavsdk.rpc.telemetry_server.TelemetryServerResult"\x95\x01\n\x08Position\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13relative_altitude_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\'\n\x07Heading\x12\x1c\n\x0bheading_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN"r\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04"s\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x04 \x01(\x04"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"`\n\x07GpsInfo\x12\x1d\n\x0enum_satellites\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x36\n\x08\x66ix_type\x18\x02 \x01(\x0e\x32$.mavsdk.rpc.telemetry_server.FixType"\xdf\x02\n\x06RawGps\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x04 \x01(\x02\x12\x0c\n\x04hdop\x18\x05 \x01(\x02\x12\x0c\n\x04vdop\x18\x06 \x01(\x02\x12\x14\n\x0cvelocity_m_s\x18\x07 \x01(\x02\x12\x0f\n\x07\x63og_deg\x18\x08 \x01(\x02\x12\x1c\n\x14\x61ltitude_ellipsoid_m\x18\t \x01(\x02\x12 \n\x18horizontal_uncertainty_m\x18\n \x01(\x02\x12\x1e\n\x16vertical_uncertainty_m\x18\x0b \x01(\x02\x12 \n\x18velocity_uncertainty_m_s\x18\x0c \x01(\x02\x12\x1f\n\x17heading_uncertainty_deg\x18\r \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x0e \x01(\x02"I\n\x07\x42\x61ttery\x12\x1a\n\tvoltage_v\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12"\n\x11remaining_percent\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"|\n\x08RcStatus\x12%\n\x12was_available_once\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1f\n\x0cis_available\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x17signal_strength_percent\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"U\n\nStatusText\x12\x39\n\x04type\x18\x01 \x01(\x0e\x32+.mavsdk.rpc.telemetry_server.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t"?\n\x15\x41\x63tuatorControlTarget\x12\x14\n\x05group\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x63ontrols\x18\x02 \x03(\x02"?\n\x14\x41\x63tuatorOutputStatus\x12\x15\n\x06\x61\x63tive\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x61\x63tuator\x18\x02 \x03(\x02"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02";\n\x0cVelocityBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02"\xa4\x05\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12@\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32..mavsdk.rpc.telemetry_server.Odometry.MavFrame\x12\x46\n\x0e\x63hild_frame_id\x18\x03 \x01(\x0e\x32..mavsdk.rpc.telemetry_server.Odometry.MavFrame\x12@\n\rposition_body\x18\x04 \x01(\x0b\x32).mavsdk.rpc.telemetry_server.PositionBody\x12\x32\n\x01q\x18\x05 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.Quaternion\x12@\n\rvelocity_body\x18\x06 \x01(\x0b\x32).mavsdk.rpc.telemetry_server.VelocityBody\x12O\n\x15\x61ngular_velocity_body\x18\x07 \x01(\x0b\x32\x30.mavsdk.rpc.telemetry_server.AngularVelocityBody\x12@\n\x0fpose_covariance\x18\x08 \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.Covariance\x12\x44\n\x13velocity_covariance\x18\t \x01(\x0b\x32\'.mavsdk.rpc.telemetry_server.Covariance"j\n\x08MavFrame\x12\x13\n\x0fMAV_FRAME_UNDEF\x10\x00\x12\x16\n\x12MAV_FRAME_BODY_NED\x10\x08\x12\x18\n\x14MAV_FRAME_VISION_NED\x10\x10\x12\x17\n\x13MAV_FRAME_ESTIM_NED\x10\x12"\x7f\n\x0e\x44istanceSensor\x12#\n\x12minimum_distance_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12maximum_distance_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x63urrent_distance_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xb0\x01\n\x0eScaledPressure\x12\x14\n\x0ctimestamp_us\x18\x01 \x01(\x04\x12\x1d\n\x15\x61\x62solute_pressure_hpa\x18\x02 \x01(\x02\x12!\n\x19\x64ifferential_pressure_hpa\x18\x03 \x01(\x02\x12\x17\n\x0ftemperature_deg\x18\x04 \x01(\x02\x12-\n%differential_pressure_temperature_deg\x18\x05 \x01(\x02"Y\n\x0bPositionNed\x12\x18\n\x07north_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x64own_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"D\n\x0bVelocityNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02"\x8d\x01\n\x13PositionVelocityNed\x12:\n\x08position\x18\x01 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.PositionNed\x12:\n\x08velocity\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry_server.VelocityNed"r\n\x0bGroundTruth\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xde\x01\n\x10\x46ixedwingMetrics\x12\x1d\n\x0c\x61irspeed_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13throttle_percentage\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0e\x63limb_rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12 \n\x0fgroundspeed_m_s\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bheading_deg\x18\x05 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x06 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"i\n\x0f\x41\x63\x63\x65lerationFrd\x12\x1d\n\x0c\x66orward_m_s2\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\nright_m_s2\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tdown_m_s2\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"o\n\x12\x41ngularVelocityFrd\x12\x1e\n\rforward_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"m\n\x10MagneticFieldFrd\x12\x1e\n\rforward_gauss\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_gauss\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_gauss\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"\xa0\x02\n\x03Imu\x12\x46\n\x10\x61\x63\x63\x65leration_frd\x18\x01 \x01(\x0b\x32,.mavsdk.rpc.telemetry_server.AccelerationFrd\x12M\n\x14\x61ngular_velocity_frd\x18\x02 \x01(\x0b\x32/.mavsdk.rpc.telemetry_server.AngularVelocityFrd\x12I\n\x12magnetic_field_frd\x18\x03 \x01(\x0b\x32-.mavsdk.rpc.telemetry_server.MagneticFieldFrd\x12!\n\x10temperature_degc\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04"\xb4\x02\n\x15TelemetryServerResult\x12I\n\x06result\x18\x01 \x01(\x0e\x32\x39.mavsdk.rpc.telemetry_server.TelemetryServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xbb\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\x16\n\x12RESULT_UNSUPPORTED\x10\x07*\xa4\x01\n\x07\x46ixType\x12\x13\n\x0f\x46IX_TYPE_NO_GPS\x10\x00\x12\x13\n\x0f\x46IX_TYPE_NO_FIX\x10\x01\x12\x13\n\x0f\x46IX_TYPE_FIX_2D\x10\x02\x12\x13\n\x0f\x46IX_TYPE_FIX_3D\x10\x03\x12\x15\n\x11\x46IX_TYPE_FIX_DGPS\x10\x04\x12\x16\n\x12\x46IX_TYPE_RTK_FLOAT\x10\x05\x12\x16\n\x12\x46IX_TYPE_RTK_FIXED\x10\x06*\x8d\x01\n\tVtolState\x12\x18\n\x14VTOL_STATE_UNDEFINED\x10\x00\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_FW\x10\x01\x12\x1f\n\x1bVTOL_STATE_TRANSITION_TO_MC\x10\x02\x12\x11\n\rVTOL_STATE_MC\x10\x03\x12\x11\n\rVTOL_STATE_FW\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*\x93\x01\n\x0bLandedState\x12\x18\n\x14LANDED_STATE_UNKNOWN\x10\x00\x12\x1a\n\x16LANDED_STATE_ON_GROUND\x10\x01\x12\x17\n\x13LANDED_STATE_IN_AIR\x10\x02\x12\x1b\n\x17LANDED_STATE_TAKING_OFF\x10\x03\x12\x18\n\x14LANDED_STATE_LANDING\x10\x04\x32\xd1\x12\n\x16TelemetryServerService\x12\x82\x01\n\x0fPublishPosition\x12\x33.mavsdk.rpc.telemetry_server.PublishPositionRequest\x1a\x34.mavsdk.rpc.telemetry_server.PublishPositionResponse"\x04\x80\xb5\x18\x01\x12v\n\x0bPublishHome\x12/.mavsdk.rpc.telemetry_server.PublishHomeRequest\x1a\x30.mavsdk.rpc.telemetry_server.PublishHomeResponse"\x04\x80\xb5\x18\x01\x12\x85\x01\n\x10PublishSysStatus\x12\x34.mavsdk.rpc.telemetry_server.PublishSysStatusRequest\x1a\x35.mavsdk.rpc.telemetry_server.PublishSysStatusResponse"\x04\x80\xb5\x18\x01\x12\x9a\x01\n\x17PublishExtendedSysState\x12;.mavsdk.rpc.telemetry_server.PublishExtendedSysStateRequest\x1a<.mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse"\x04\x80\xb5\x18\x01\x12|\n\rPublishRawGps\x12\x31.mavsdk.rpc.telemetry_server.PublishRawGpsRequest\x1a\x32.mavsdk.rpc.telemetry_server.PublishRawGpsResponse"\x04\x80\xb5\x18\x01\x12\x7f\n\x0ePublishBattery\x12\x32.mavsdk.rpc.telemetry_server.PublishBatteryRequest\x1a\x33.mavsdk.rpc.telemetry_server.PublishBatteryResponse"\x04\x80\xb5\x18\x01\x12\x88\x01\n\x11PublishStatusText\x12\x35.mavsdk.rpc.telemetry_server.PublishStatusTextRequest\x1a\x36.mavsdk.rpc.telemetry_server.PublishStatusTextResponse"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x0fPublishOdometry\x12\x33.mavsdk.rpc.telemetry_server.PublishOdometryRequest\x1a\x34.mavsdk.rpc.telemetry_server.PublishOdometryResponse"\x04\x80\xb5\x18\x01\x12\xa3\x01\n\x1aPublishPositionVelocityNed\x12>.mavsdk.rpc.telemetry_server.PublishPositionVelocityNedRequest\x1a?.mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse"\x04\x80\xb5\x18\x01\x12\x8b\x01\n\x12PublishGroundTruth\x12\x36.mavsdk.rpc.telemetry_server.PublishGroundTruthRequest\x1a\x37.mavsdk.rpc.telemetry_server.PublishGroundTruthResponse"\x04\x80\xb5\x18\x01\x12s\n\nPublishImu\x12..mavsdk.rpc.telemetry_server.PublishImuRequest\x1a/.mavsdk.rpc.telemetry_server.PublishImuResponse"\x04\x80\xb5\x18\x01\x12\x85\x01\n\x10PublishScaledImu\x12\x34.mavsdk.rpc.telemetry_server.PublishScaledImuRequest\x1a\x35.mavsdk.rpc.telemetry_server.PublishScaledImuResponse"\x04\x80\xb5\x18\x01\x12|\n\rPublishRawImu\x12\x31.mavsdk.rpc.telemetry_server.PublishRawImuRequest\x1a\x32.mavsdk.rpc.telemetry_server.PublishRawImuResponse"\x04\x80\xb5\x18\x01\x12\x91\x01\n\x14PublishUnixEpochTime\x12\x38.mavsdk.rpc.telemetry_server.PublishUnixEpochTimeRequest\x1a\x39.mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse"\x04\x80\xb5\x18\x01\x12\x94\x01\n\x15PublishDistanceSensor\x12\x39.mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest\x1a:.mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse"\x04\x80\xb5\x18\x01\x12\x82\x01\n\x0fPublishAttitude\x12\x33.mavsdk.rpc.telemetry_server.PublishAttitudeRequest\x1a\x34.mavsdk.rpc.telemetry_server.PublishAttitudeResponse"\x04\x80\xb5\x18\x01\x12\xa6\x01\n\x1bPublishVisualFlightRulesHud\x12?.mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest\x1a@.mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse"\x04\x80\xb5\x18\x01\x42\x32\n\x1aio.mavsdk.telemetry_serverB\x14TelemetryServerProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'telemetry_server.telemetry_server_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "telemetry_server.telemetry_server_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\032io.mavsdk.telemetry_serverB\024TelemetryServerProto' - _globals['_POSITION'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_POSITION'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITION'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_POSITION'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITION'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_POSITION'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITION'].fields_by_name['relative_altitude_m']._loaded_options = None - _globals['_POSITION'].fields_by_name['relative_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_HEADING'].fields_by_name['heading_deg']._loaded_options = None - _globals['_HEADING'].fields_by_name['heading_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['w']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['w']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['x']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['x']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['y']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['y']._serialized_options = b'\202\265\030\003NaN' - _globals['_QUATERNION'].fields_by_name['z']._loaded_options = None - _globals['_QUATERNION'].fields_by_name['z']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['roll_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['roll_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['pitch_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['pitch_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_EULERANGLE'].fields_by_name['yaw_deg']._loaded_options = None - _globals['_EULERANGLE'].fields_by_name['yaw_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['roll_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['roll_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['pitch_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['pitch_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYBODY'].fields_by_name['yaw_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYBODY'].fields_by_name['yaw_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_GPSINFO'].fields_by_name['num_satellites']._loaded_options = None - _globals['_GPSINFO'].fields_by_name['num_satellites']._serialized_options = b'\202\265\030\0010' - _globals['_BATTERY'].fields_by_name['voltage_v']._loaded_options = None - _globals['_BATTERY'].fields_by_name['voltage_v']._serialized_options = b'\202\265\030\003NaN' - _globals['_BATTERY'].fields_by_name['remaining_percent']._loaded_options = None - _globals['_BATTERY'].fields_by_name['remaining_percent']._serialized_options = b'\202\265\030\003NaN' - _globals['_RCSTATUS'].fields_by_name['was_available_once']._loaded_options = None - _globals['_RCSTATUS'].fields_by_name['was_available_once']._serialized_options = b'\202\265\030\005false' - _globals['_RCSTATUS'].fields_by_name['is_available']._loaded_options = None - _globals['_RCSTATUS'].fields_by_name['is_available']._serialized_options = b'\202\265\030\005false' - _globals['_RCSTATUS'].fields_by_name['signal_strength_percent']._loaded_options = None - _globals['_RCSTATUS'].fields_by_name['signal_strength_percent']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACTUATORCONTROLTARGET'].fields_by_name['group']._loaded_options = None - _globals['_ACTUATORCONTROLTARGET'].fields_by_name['group']._serialized_options = b'\202\265\030\0010' - _globals['_ACTUATOROUTPUTSTATUS'].fields_by_name['active']._loaded_options = None - _globals['_ACTUATOROUTPUTSTATUS'].fields_by_name['active']._serialized_options = b'\202\265\030\0010' - _globals['_DISTANCESENSOR'].fields_by_name['minimum_distance_m']._loaded_options = None - _globals['_DISTANCESENSOR'].fields_by_name['minimum_distance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_DISTANCESENSOR'].fields_by_name['maximum_distance_m']._loaded_options = None - _globals['_DISTANCESENSOR'].fields_by_name['maximum_distance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_DISTANCESENSOR'].fields_by_name['current_distance_m']._loaded_options = None - _globals['_DISTANCESENSOR'].fields_by_name['current_distance_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITIONNED'].fields_by_name['north_m']._loaded_options = None - _globals['_POSITIONNED'].fields_by_name['north_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITIONNED'].fields_by_name['east_m']._loaded_options = None - _globals['_POSITIONNED'].fields_by_name['east_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_POSITIONNED'].fields_by_name['down_m']._loaded_options = None - _globals['_POSITIONNED'].fields_by_name['down_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_GROUNDTRUTH'].fields_by_name['latitude_deg']._loaded_options = None - _globals['_GROUNDTRUTH'].fields_by_name['latitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_GROUNDTRUTH'].fields_by_name['longitude_deg']._loaded_options = None - _globals['_GROUNDTRUTH'].fields_by_name['longitude_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_GROUNDTRUTH'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_GROUNDTRUTH'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['airspeed_m_s']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['airspeed_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['throttle_percentage']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['throttle_percentage']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['climb_rate_m_s']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['climb_rate_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['groundspeed_m_s']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['groundspeed_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['heading_deg']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['heading_deg']._serialized_options = b'\202\265\030\003NaN' - _globals['_FIXEDWINGMETRICS'].fields_by_name['absolute_altitude_m']._loaded_options = None - _globals['_FIXEDWINGMETRICS'].fields_by_name['absolute_altitude_m']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACCELERATIONFRD'].fields_by_name['forward_m_s2']._loaded_options = None - _globals['_ACCELERATIONFRD'].fields_by_name['forward_m_s2']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACCELERATIONFRD'].fields_by_name['right_m_s2']._loaded_options = None - _globals['_ACCELERATIONFRD'].fields_by_name['right_m_s2']._serialized_options = b'\202\265\030\003NaN' - _globals['_ACCELERATIONFRD'].fields_by_name['down_m_s2']._loaded_options = None - _globals['_ACCELERATIONFRD'].fields_by_name['down_m_s2']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYFRD'].fields_by_name['forward_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYFRD'].fields_by_name['forward_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYFRD'].fields_by_name['right_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYFRD'].fields_by_name['right_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_ANGULARVELOCITYFRD'].fields_by_name['down_rad_s']._loaded_options = None - _globals['_ANGULARVELOCITYFRD'].fields_by_name['down_rad_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_MAGNETICFIELDFRD'].fields_by_name['forward_gauss']._loaded_options = None - _globals['_MAGNETICFIELDFRD'].fields_by_name['forward_gauss']._serialized_options = b'\202\265\030\003NaN' - _globals['_MAGNETICFIELDFRD'].fields_by_name['right_gauss']._loaded_options = None - _globals['_MAGNETICFIELDFRD'].fields_by_name['right_gauss']._serialized_options = b'\202\265\030\003NaN' - _globals['_MAGNETICFIELDFRD'].fields_by_name['down_gauss']._loaded_options = None - _globals['_MAGNETICFIELDFRD'].fields_by_name['down_gauss']._serialized_options = b'\202\265\030\003NaN' - _globals['_IMU'].fields_by_name['temperature_degc']._loaded_options = None - _globals['_IMU'].fields_by_name['temperature_degc']._serialized_options = b'\202\265\030\003NaN' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishPosition']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishPosition']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishHome']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishHome']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishSysStatus']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishSysStatus']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishExtendedSysState']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishExtendedSysState']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishRawGps']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishRawGps']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishBattery']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishBattery']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishStatusText']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishStatusText']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishOdometry']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishOdometry']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishPositionVelocityNed']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishPositionVelocityNed']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishGroundTruth']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishGroundTruth']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishImu']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishImu']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishScaledImu']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishScaledImu']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishRawImu']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishRawImu']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishUnixEpochTime']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishUnixEpochTime']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishDistanceSensor']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishDistanceSensor']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishAttitude']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishAttitude']._serialized_options = b'\200\265\030\001' - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishVisualFlightRulesHud']._loaded_options = None - _globals['_TELEMETRYSERVERSERVICE'].methods_by_name['PublishVisualFlightRulesHud']._serialized_options = b'\200\265\030\001' - _globals['_FIXTYPE']._serialized_start=8247 - _globals['_FIXTYPE']._serialized_end=8411 - _globals['_VTOLSTATE']._serialized_start=8414 - _globals['_VTOLSTATE']._serialized_end=8555 - _globals['_STATUSTEXTTYPE']._serialized_start=8558 - _globals['_STATUSTEXTTYPE']._serialized_end=8807 - _globals['_LANDEDSTATE']._serialized_start=8810 - _globals['_LANDEDSTATE']._serialized_end=8957 - _globals['_PUBLISHPOSITIONREQUEST']._serialized_start=95 - _globals['_PUBLISHPOSITIONREQUEST']._serialized_end=295 - _globals['_PUBLISHHOMEREQUEST']._serialized_start=297 - _globals['_PUBLISHHOMEREQUEST']._serialized_end=370 - _globals['_PUBLISHSYSSTATUSREQUEST']._serialized_start=373 - _globals['_PUBLISHSYSSTATUSREQUEST']._serialized_end=564 - _globals['_PUBLISHEXTENDEDSYSSTATEREQUEST']._serialized_start=567 - _globals['_PUBLISHEXTENDEDSYSSTATEREQUEST']._serialized_end=723 - _globals['_PUBLISHINAIRREQUEST']._serialized_start=725 - _globals['_PUBLISHINAIRREQUEST']._serialized_end=765 - _globals['_PUBLISHLANDEDSTATEREQUEST']._serialized_start=767 - _globals['_PUBLISHLANDEDSTATEREQUEST']._serialized_end=858 - _globals['_PUBLISHRAWGPSREQUEST']._serialized_start=861 - _globals['_PUBLISHRAWGPSREQUEST']._serialized_end=993 - _globals['_PUBLISHBATTERYREQUEST']._serialized_start=995 - _globals['_PUBLISHBATTERYREQUEST']._serialized_end=1073 - _globals['_PUBLISHRCSTATUSREQUEST']._serialized_start=1075 - _globals['_PUBLISHRCSTATUSREQUEST']._serialized_end=1157 - _globals['_PUBLISHSTATUSTEXTREQUEST']._serialized_start=1159 - _globals['_PUBLISHSTATUSTEXTREQUEST']._serialized_end=1247 - _globals['_PUBLISHODOMETRYREQUEST']._serialized_start=1249 - _globals['_PUBLISHODOMETRYREQUEST']._serialized_end=1330 - _globals['_PUBLISHPOSITIONVELOCITYNEDREQUEST']._serialized_start=1332 - _globals['_PUBLISHPOSITIONVELOCITYNEDREQUEST']._serialized_end=1448 - _globals['_PUBLISHGROUNDTRUTHREQUEST']._serialized_start=1450 - _globals['_PUBLISHGROUNDTRUTHREQUEST']._serialized_end=1541 - _globals['_PUBLISHIMUREQUEST']._serialized_start=1543 - _globals['_PUBLISHIMUREQUEST']._serialized_end=1609 - _globals['_PUBLISHSCALEDIMUREQUEST']._serialized_start=1611 - _globals['_PUBLISHSCALEDIMUREQUEST']._serialized_end=1683 - _globals['_PUBLISHRAWIMUREQUEST']._serialized_start=1685 - _globals['_PUBLISHRAWIMUREQUEST']._serialized_end=1754 - _globals['_PUBLISHUNIXEPOCHTIMEREQUEST']._serialized_start=1756 - _globals['_PUBLISHUNIXEPOCHTIMEREQUEST']._serialized_end=1802 - _globals['_PUBLISHDISTANCESENSORREQUEST']._serialized_start=1804 - _globals['_PUBLISHDISTANCESENSORREQUEST']._serialized_end=1904 - _globals['_PUBLISHATTITUDEREQUEST']._serialized_start=1907 - _globals['_PUBLISHATTITUDEREQUEST']._serialized_end=2063 - _globals['_PUBLISHVISUALFLIGHTRULESHUDREQUEST']._serialized_start=2065 - _globals['_PUBLISHVISUALFLIGHTRULESHUDREQUEST']._serialized_end=2176 - _globals['_PUBLISHPOSITIONRESPONSE']._serialized_start=2178 - _globals['_PUBLISHPOSITIONRESPONSE']._serialized_end=2288 - _globals['_PUBLISHHOMERESPONSE']._serialized_start=2290 - _globals['_PUBLISHHOMERESPONSE']._serialized_end=2396 - _globals['_PUBLISHSYSSTATUSRESPONSE']._serialized_start=2398 - _globals['_PUBLISHSYSSTATUSRESPONSE']._serialized_end=2509 - _globals['_PUBLISHEXTENDEDSYSSTATERESPONSE']._serialized_start=2511 - _globals['_PUBLISHEXTENDEDSYSSTATERESPONSE']._serialized_end=2629 - _globals['_PUBLISHRAWGPSRESPONSE']._serialized_start=2631 - _globals['_PUBLISHRAWGPSRESPONSE']._serialized_end=2739 - _globals['_PUBLISHBATTERYRESPONSE']._serialized_start=2741 - _globals['_PUBLISHBATTERYRESPONSE']._serialized_end=2850 - _globals['_PUBLISHSTATUSTEXTRESPONSE']._serialized_start=2852 - _globals['_PUBLISHSTATUSTEXTRESPONSE']._serialized_end=2964 - _globals['_PUBLISHODOMETRYRESPONSE']._serialized_start=2966 - _globals['_PUBLISHODOMETRYRESPONSE']._serialized_end=3076 - _globals['_PUBLISHPOSITIONVELOCITYNEDRESPONSE']._serialized_start=3078 - _globals['_PUBLISHPOSITIONVELOCITYNEDRESPONSE']._serialized_end=3199 - _globals['_PUBLISHGROUNDTRUTHRESPONSE']._serialized_start=3201 - _globals['_PUBLISHGROUNDTRUTHRESPONSE']._serialized_end=3314 - _globals['_PUBLISHIMURESPONSE']._serialized_start=3316 - _globals['_PUBLISHIMURESPONSE']._serialized_end=3421 - _globals['_PUBLISHSCALEDIMURESPONSE']._serialized_start=3423 - _globals['_PUBLISHSCALEDIMURESPONSE']._serialized_end=3534 - _globals['_PUBLISHRAWIMURESPONSE']._serialized_start=3536 - _globals['_PUBLISHRAWIMURESPONSE']._serialized_end=3644 - _globals['_PUBLISHUNIXEPOCHTIMERESPONSE']._serialized_start=3646 - _globals['_PUBLISHUNIXEPOCHTIMERESPONSE']._serialized_end=3761 - _globals['_PUBLISHDISTANCESENSORRESPONSE']._serialized_start=3763 - _globals['_PUBLISHDISTANCESENSORRESPONSE']._serialized_end=3879 - _globals['_PUBLISHATTITUDERESPONSE']._serialized_start=3881 - _globals['_PUBLISHATTITUDERESPONSE']._serialized_end=3991 - _globals['_PUBLISHVISUALFLIGHTRULESHUDRESPONSE']._serialized_start=3993 - _globals['_PUBLISHVISUALFLIGHTRULESHUDRESPONSE']._serialized_end=4115 - _globals['_POSITION']._serialized_start=4118 - _globals['_POSITION']._serialized_end=4267 - _globals['_HEADING']._serialized_start=4269 - _globals['_HEADING']._serialized_end=4308 - _globals['_QUATERNION']._serialized_start=4310 - _globals['_QUATERNION']._serialized_end=4424 - _globals['_EULERANGLE']._serialized_start=4426 - _globals['_EULERANGLE']._serialized_end=4541 - _globals['_ANGULARVELOCITYBODY']._serialized_start=4543 - _globals['_ANGULARVELOCITYBODY']._serialized_end=4651 - _globals['_GPSINFO']._serialized_start=4653 - _globals['_GPSINFO']._serialized_end=4749 - _globals['_RAWGPS']._serialized_start=4752 - _globals['_RAWGPS']._serialized_end=5103 - _globals['_BATTERY']._serialized_start=5105 - _globals['_BATTERY']._serialized_end=5178 - _globals['_RCSTATUS']._serialized_start=5180 - _globals['_RCSTATUS']._serialized_end=5304 - _globals['_STATUSTEXT']._serialized_start=5306 - _globals['_STATUSTEXT']._serialized_end=5391 - _globals['_ACTUATORCONTROLTARGET']._serialized_start=5393 - _globals['_ACTUATORCONTROLTARGET']._serialized_end=5456 - _globals['_ACTUATOROUTPUTSTATUS']._serialized_start=5458 - _globals['_ACTUATOROUTPUTSTATUS']._serialized_end=5521 - _globals['_COVARIANCE']._serialized_start=5523 - _globals['_COVARIANCE']._serialized_end=5562 - _globals['_VELOCITYBODY']._serialized_start=5564 - _globals['_VELOCITYBODY']._serialized_end=5623 - _globals['_POSITIONBODY']._serialized_start=5625 - _globals['_POSITIONBODY']._serialized_end=5678 - _globals['_ODOMETRY']._serialized_start=5681 - _globals['_ODOMETRY']._serialized_end=6357 - _globals['_ODOMETRY_MAVFRAME']._serialized_start=6251 - _globals['_ODOMETRY_MAVFRAME']._serialized_end=6357 - _globals['_DISTANCESENSOR']._serialized_start=6359 - _globals['_DISTANCESENSOR']._serialized_end=6486 - _globals['_SCALEDPRESSURE']._serialized_start=6489 - _globals['_SCALEDPRESSURE']._serialized_end=6665 - _globals['_POSITIONNED']._serialized_start=6667 - _globals['_POSITIONNED']._serialized_end=6756 - _globals['_VELOCITYNED']._serialized_start=6758 - _globals['_VELOCITYNED']._serialized_end=6826 - _globals['_POSITIONVELOCITYNED']._serialized_start=6829 - _globals['_POSITIONVELOCITYNED']._serialized_end=6970 - _globals['_GROUNDTRUTH']._serialized_start=6972 - _globals['_GROUNDTRUTH']._serialized_end=7086 - _globals['_FIXEDWINGMETRICS']._serialized_start=7089 - _globals['_FIXEDWINGMETRICS']._serialized_end=7311 - _globals['_ACCELERATIONFRD']._serialized_start=7313 - _globals['_ACCELERATIONFRD']._serialized_end=7418 - _globals['_ANGULARVELOCITYFRD']._serialized_start=7420 - _globals['_ANGULARVELOCITYFRD']._serialized_end=7531 - _globals['_MAGNETICFIELDFRD']._serialized_start=7533 - _globals['_MAGNETICFIELDFRD']._serialized_end=7642 - _globals['_IMU']._serialized_start=7645 - _globals['_IMU']._serialized_end=7933 - _globals['_TELEMETRYSERVERRESULT']._serialized_start=7936 - _globals['_TELEMETRYSERVERRESULT']._serialized_end=8244 - _globals['_TELEMETRYSERVERRESULT_RESULT']._serialized_start=8057 - _globals['_TELEMETRYSERVERRESULT_RESULT']._serialized_end=8244 - _globals['_TELEMETRYSERVERSERVICE']._serialized_start=8960 - _globals['_TELEMETRYSERVERSERVICE']._serialized_end=11345 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\032io.mavsdk.telemetry_serverB\024TelemetryServerProto" + _globals["_POSITION"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITION"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITION"].fields_by_name["absolute_altitude_m"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITION"].fields_by_name["relative_altitude_m"]._loaded_options = None + _globals["_POSITION"].fields_by_name[ + "relative_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_HEADING"].fields_by_name["heading_deg"]._loaded_options = None + _globals["_HEADING"].fields_by_name[ + "heading_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["w"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "w" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["x"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "x" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["y"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "y" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_QUATERNION"].fields_by_name["z"]._loaded_options = None + _globals["_QUATERNION"].fields_by_name[ + "z" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["roll_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "roll_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["pitch_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "pitch_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_EULERANGLE"].fields_by_name["yaw_deg"]._loaded_options = None + _globals["_EULERANGLE"].fields_by_name[ + "yaw_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name["roll_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "roll_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "pitch_rad_s" + ]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "pitch_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYBODY"].fields_by_name["yaw_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYBODY"].fields_by_name[ + "yaw_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GPSINFO"].fields_by_name["num_satellites"]._loaded_options = None + _globals["_GPSINFO"].fields_by_name[ + "num_satellites" + ]._serialized_options = b"\202\265\030\0010" + _globals["_BATTERY"].fields_by_name["voltage_v"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "voltage_v" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_BATTERY"].fields_by_name["remaining_percent"]._loaded_options = None + _globals["_BATTERY"].fields_by_name[ + "remaining_percent" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_RCSTATUS"].fields_by_name["was_available_once"]._loaded_options = None + _globals["_RCSTATUS"].fields_by_name[ + "was_available_once" + ]._serialized_options = b"\202\265\030\005false" + _globals["_RCSTATUS"].fields_by_name["is_available"]._loaded_options = None + _globals["_RCSTATUS"].fields_by_name[ + "is_available" + ]._serialized_options = b"\202\265\030\005false" + _globals["_RCSTATUS"].fields_by_name[ + "signal_strength_percent" + ]._loaded_options = None + _globals["_RCSTATUS"].fields_by_name[ + "signal_strength_percent" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACTUATORCONTROLTARGET"].fields_by_name["group"]._loaded_options = None + _globals["_ACTUATORCONTROLTARGET"].fields_by_name[ + "group" + ]._serialized_options = b"\202\265\030\0010" + _globals["_ACTUATOROUTPUTSTATUS"].fields_by_name["active"]._loaded_options = None + _globals["_ACTUATOROUTPUTSTATUS"].fields_by_name[ + "active" + ]._serialized_options = b"\202\265\030\0010" + _globals["_DISTANCESENSOR"].fields_by_name[ + "minimum_distance_m" + ]._loaded_options = None + _globals["_DISTANCESENSOR"].fields_by_name[ + "minimum_distance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_DISTANCESENSOR"].fields_by_name[ + "maximum_distance_m" + ]._loaded_options = None + _globals["_DISTANCESENSOR"].fields_by_name[ + "maximum_distance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_DISTANCESENSOR"].fields_by_name[ + "current_distance_m" + ]._loaded_options = None + _globals["_DISTANCESENSOR"].fields_by_name[ + "current_distance_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITIONNED"].fields_by_name["north_m"]._loaded_options = None + _globals["_POSITIONNED"].fields_by_name[ + "north_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITIONNED"].fields_by_name["east_m"]._loaded_options = None + _globals["_POSITIONNED"].fields_by_name[ + "east_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_POSITIONNED"].fields_by_name["down_m"]._loaded_options = None + _globals["_POSITIONNED"].fields_by_name[ + "down_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GROUNDTRUTH"].fields_by_name["latitude_deg"]._loaded_options = None + _globals["_GROUNDTRUTH"].fields_by_name[ + "latitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GROUNDTRUTH"].fields_by_name["longitude_deg"]._loaded_options = None + _globals["_GROUNDTRUTH"].fields_by_name[ + "longitude_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_GROUNDTRUTH"].fields_by_name[ + "absolute_altitude_m" + ]._loaded_options = None + _globals["_GROUNDTRUTH"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name["airspeed_m_s"]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "airspeed_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "throttle_percentage" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "throttle_percentage" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "climb_rate_m_s" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "climb_rate_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "groundspeed_m_s" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "groundspeed_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name["heading_deg"]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "heading_deg" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "absolute_altitude_m" + ]._loaded_options = None + _globals["_FIXEDWINGMETRICS"].fields_by_name[ + "absolute_altitude_m" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACCELERATIONFRD"].fields_by_name["forward_m_s2"]._loaded_options = None + _globals["_ACCELERATIONFRD"].fields_by_name[ + "forward_m_s2" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACCELERATIONFRD"].fields_by_name["right_m_s2"]._loaded_options = None + _globals["_ACCELERATIONFRD"].fields_by_name[ + "right_m_s2" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ACCELERATIONFRD"].fields_by_name["down_m_s2"]._loaded_options = None + _globals["_ACCELERATIONFRD"].fields_by_name[ + "down_m_s2" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "forward_rad_s" + ]._loaded_options = None + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "forward_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYFRD"].fields_by_name["right_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "right_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_ANGULARVELOCITYFRD"].fields_by_name["down_rad_s"]._loaded_options = None + _globals["_ANGULARVELOCITYFRD"].fields_by_name[ + "down_rad_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MAGNETICFIELDFRD"].fields_by_name["forward_gauss"]._loaded_options = None + _globals["_MAGNETICFIELDFRD"].fields_by_name[ + "forward_gauss" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MAGNETICFIELDFRD"].fields_by_name["right_gauss"]._loaded_options = None + _globals["_MAGNETICFIELDFRD"].fields_by_name[ + "right_gauss" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_MAGNETICFIELDFRD"].fields_by_name["down_gauss"]._loaded_options = None + _globals["_MAGNETICFIELDFRD"].fields_by_name[ + "down_gauss" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_IMU"].fields_by_name["temperature_degc"]._loaded_options = None + _globals["_IMU"].fields_by_name[ + "temperature_degc" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishPosition" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishPosition" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishHome" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishHome" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishSysStatus" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishSysStatus" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishExtendedSysState" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishExtendedSysState" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishRawGps" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishRawGps" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishBattery" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishBattery" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishStatusText" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishStatusText" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishOdometry" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishOdometry" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishPositionVelocityNed" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishPositionVelocityNed" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishGroundTruth" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishGroundTruth" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishImu" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishImu" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishScaledImu" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishScaledImu" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishRawImu" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishRawImu" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishUnixEpochTime" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishUnixEpochTime" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishDistanceSensor" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishDistanceSensor" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishAttitude" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishAttitude" + ]._serialized_options = b"\200\265\030\001" + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishVisualFlightRulesHud" + ]._loaded_options = None + _globals["_TELEMETRYSERVERSERVICE"].methods_by_name[ + "PublishVisualFlightRulesHud" + ]._serialized_options = b"\200\265\030\001" + _globals["_FIXTYPE"]._serialized_start = 8247 + _globals["_FIXTYPE"]._serialized_end = 8411 + _globals["_VTOLSTATE"]._serialized_start = 8414 + _globals["_VTOLSTATE"]._serialized_end = 8555 + _globals["_STATUSTEXTTYPE"]._serialized_start = 8558 + _globals["_STATUSTEXTTYPE"]._serialized_end = 8807 + _globals["_LANDEDSTATE"]._serialized_start = 8810 + _globals["_LANDEDSTATE"]._serialized_end = 8957 + _globals["_PUBLISHPOSITIONREQUEST"]._serialized_start = 95 + _globals["_PUBLISHPOSITIONREQUEST"]._serialized_end = 295 + _globals["_PUBLISHHOMEREQUEST"]._serialized_start = 297 + _globals["_PUBLISHHOMEREQUEST"]._serialized_end = 370 + _globals["_PUBLISHSYSSTATUSREQUEST"]._serialized_start = 373 + _globals["_PUBLISHSYSSTATUSREQUEST"]._serialized_end = 564 + _globals["_PUBLISHEXTENDEDSYSSTATEREQUEST"]._serialized_start = 567 + _globals["_PUBLISHEXTENDEDSYSSTATEREQUEST"]._serialized_end = 723 + _globals["_PUBLISHINAIRREQUEST"]._serialized_start = 725 + _globals["_PUBLISHINAIRREQUEST"]._serialized_end = 765 + _globals["_PUBLISHLANDEDSTATEREQUEST"]._serialized_start = 767 + _globals["_PUBLISHLANDEDSTATEREQUEST"]._serialized_end = 858 + _globals["_PUBLISHRAWGPSREQUEST"]._serialized_start = 861 + _globals["_PUBLISHRAWGPSREQUEST"]._serialized_end = 993 + _globals["_PUBLISHBATTERYREQUEST"]._serialized_start = 995 + _globals["_PUBLISHBATTERYREQUEST"]._serialized_end = 1073 + _globals["_PUBLISHRCSTATUSREQUEST"]._serialized_start = 1075 + _globals["_PUBLISHRCSTATUSREQUEST"]._serialized_end = 1157 + _globals["_PUBLISHSTATUSTEXTREQUEST"]._serialized_start = 1159 + _globals["_PUBLISHSTATUSTEXTREQUEST"]._serialized_end = 1247 + _globals["_PUBLISHODOMETRYREQUEST"]._serialized_start = 1249 + _globals["_PUBLISHODOMETRYREQUEST"]._serialized_end = 1330 + _globals["_PUBLISHPOSITIONVELOCITYNEDREQUEST"]._serialized_start = 1332 + _globals["_PUBLISHPOSITIONVELOCITYNEDREQUEST"]._serialized_end = 1448 + _globals["_PUBLISHGROUNDTRUTHREQUEST"]._serialized_start = 1450 + _globals["_PUBLISHGROUNDTRUTHREQUEST"]._serialized_end = 1541 + _globals["_PUBLISHIMUREQUEST"]._serialized_start = 1543 + _globals["_PUBLISHIMUREQUEST"]._serialized_end = 1609 + _globals["_PUBLISHSCALEDIMUREQUEST"]._serialized_start = 1611 + _globals["_PUBLISHSCALEDIMUREQUEST"]._serialized_end = 1683 + _globals["_PUBLISHRAWIMUREQUEST"]._serialized_start = 1685 + _globals["_PUBLISHRAWIMUREQUEST"]._serialized_end = 1754 + _globals["_PUBLISHUNIXEPOCHTIMEREQUEST"]._serialized_start = 1756 + _globals["_PUBLISHUNIXEPOCHTIMEREQUEST"]._serialized_end = 1802 + _globals["_PUBLISHDISTANCESENSORREQUEST"]._serialized_start = 1804 + _globals["_PUBLISHDISTANCESENSORREQUEST"]._serialized_end = 1904 + _globals["_PUBLISHATTITUDEREQUEST"]._serialized_start = 1907 + _globals["_PUBLISHATTITUDEREQUEST"]._serialized_end = 2063 + _globals["_PUBLISHVISUALFLIGHTRULESHUDREQUEST"]._serialized_start = 2065 + _globals["_PUBLISHVISUALFLIGHTRULESHUDREQUEST"]._serialized_end = 2176 + _globals["_PUBLISHPOSITIONRESPONSE"]._serialized_start = 2178 + _globals["_PUBLISHPOSITIONRESPONSE"]._serialized_end = 2288 + _globals["_PUBLISHHOMERESPONSE"]._serialized_start = 2290 + _globals["_PUBLISHHOMERESPONSE"]._serialized_end = 2396 + _globals["_PUBLISHSYSSTATUSRESPONSE"]._serialized_start = 2398 + _globals["_PUBLISHSYSSTATUSRESPONSE"]._serialized_end = 2509 + _globals["_PUBLISHEXTENDEDSYSSTATERESPONSE"]._serialized_start = 2511 + _globals["_PUBLISHEXTENDEDSYSSTATERESPONSE"]._serialized_end = 2629 + _globals["_PUBLISHRAWGPSRESPONSE"]._serialized_start = 2631 + _globals["_PUBLISHRAWGPSRESPONSE"]._serialized_end = 2739 + _globals["_PUBLISHBATTERYRESPONSE"]._serialized_start = 2741 + _globals["_PUBLISHBATTERYRESPONSE"]._serialized_end = 2850 + _globals["_PUBLISHSTATUSTEXTRESPONSE"]._serialized_start = 2852 + _globals["_PUBLISHSTATUSTEXTRESPONSE"]._serialized_end = 2964 + _globals["_PUBLISHODOMETRYRESPONSE"]._serialized_start = 2966 + _globals["_PUBLISHODOMETRYRESPONSE"]._serialized_end = 3076 + _globals["_PUBLISHPOSITIONVELOCITYNEDRESPONSE"]._serialized_start = 3078 + _globals["_PUBLISHPOSITIONVELOCITYNEDRESPONSE"]._serialized_end = 3199 + _globals["_PUBLISHGROUNDTRUTHRESPONSE"]._serialized_start = 3201 + _globals["_PUBLISHGROUNDTRUTHRESPONSE"]._serialized_end = 3314 + _globals["_PUBLISHIMURESPONSE"]._serialized_start = 3316 + _globals["_PUBLISHIMURESPONSE"]._serialized_end = 3421 + _globals["_PUBLISHSCALEDIMURESPONSE"]._serialized_start = 3423 + _globals["_PUBLISHSCALEDIMURESPONSE"]._serialized_end = 3534 + _globals["_PUBLISHRAWIMURESPONSE"]._serialized_start = 3536 + _globals["_PUBLISHRAWIMURESPONSE"]._serialized_end = 3644 + _globals["_PUBLISHUNIXEPOCHTIMERESPONSE"]._serialized_start = 3646 + _globals["_PUBLISHUNIXEPOCHTIMERESPONSE"]._serialized_end = 3761 + _globals["_PUBLISHDISTANCESENSORRESPONSE"]._serialized_start = 3763 + _globals["_PUBLISHDISTANCESENSORRESPONSE"]._serialized_end = 3879 + _globals["_PUBLISHATTITUDERESPONSE"]._serialized_start = 3881 + _globals["_PUBLISHATTITUDERESPONSE"]._serialized_end = 3991 + _globals["_PUBLISHVISUALFLIGHTRULESHUDRESPONSE"]._serialized_start = 3993 + _globals["_PUBLISHVISUALFLIGHTRULESHUDRESPONSE"]._serialized_end = 4115 + _globals["_POSITION"]._serialized_start = 4118 + _globals["_POSITION"]._serialized_end = 4267 + _globals["_HEADING"]._serialized_start = 4269 + _globals["_HEADING"]._serialized_end = 4308 + _globals["_QUATERNION"]._serialized_start = 4310 + _globals["_QUATERNION"]._serialized_end = 4424 + _globals["_EULERANGLE"]._serialized_start = 4426 + _globals["_EULERANGLE"]._serialized_end = 4541 + _globals["_ANGULARVELOCITYBODY"]._serialized_start = 4543 + _globals["_ANGULARVELOCITYBODY"]._serialized_end = 4651 + _globals["_GPSINFO"]._serialized_start = 4653 + _globals["_GPSINFO"]._serialized_end = 4749 + _globals["_RAWGPS"]._serialized_start = 4752 + _globals["_RAWGPS"]._serialized_end = 5103 + _globals["_BATTERY"]._serialized_start = 5105 + _globals["_BATTERY"]._serialized_end = 5178 + _globals["_RCSTATUS"]._serialized_start = 5180 + _globals["_RCSTATUS"]._serialized_end = 5304 + _globals["_STATUSTEXT"]._serialized_start = 5306 + _globals["_STATUSTEXT"]._serialized_end = 5391 + _globals["_ACTUATORCONTROLTARGET"]._serialized_start = 5393 + _globals["_ACTUATORCONTROLTARGET"]._serialized_end = 5456 + _globals["_ACTUATOROUTPUTSTATUS"]._serialized_start = 5458 + _globals["_ACTUATOROUTPUTSTATUS"]._serialized_end = 5521 + _globals["_COVARIANCE"]._serialized_start = 5523 + _globals["_COVARIANCE"]._serialized_end = 5562 + _globals["_VELOCITYBODY"]._serialized_start = 5564 + _globals["_VELOCITYBODY"]._serialized_end = 5623 + _globals["_POSITIONBODY"]._serialized_start = 5625 + _globals["_POSITIONBODY"]._serialized_end = 5678 + _globals["_ODOMETRY"]._serialized_start = 5681 + _globals["_ODOMETRY"]._serialized_end = 6357 + _globals["_ODOMETRY_MAVFRAME"]._serialized_start = 6251 + _globals["_ODOMETRY_MAVFRAME"]._serialized_end = 6357 + _globals["_DISTANCESENSOR"]._serialized_start = 6359 + _globals["_DISTANCESENSOR"]._serialized_end = 6486 + _globals["_SCALEDPRESSURE"]._serialized_start = 6489 + _globals["_SCALEDPRESSURE"]._serialized_end = 6665 + _globals["_POSITIONNED"]._serialized_start = 6667 + _globals["_POSITIONNED"]._serialized_end = 6756 + _globals["_VELOCITYNED"]._serialized_start = 6758 + _globals["_VELOCITYNED"]._serialized_end = 6826 + _globals["_POSITIONVELOCITYNED"]._serialized_start = 6829 + _globals["_POSITIONVELOCITYNED"]._serialized_end = 6970 + _globals["_GROUNDTRUTH"]._serialized_start = 6972 + _globals["_GROUNDTRUTH"]._serialized_end = 7086 + _globals["_FIXEDWINGMETRICS"]._serialized_start = 7089 + _globals["_FIXEDWINGMETRICS"]._serialized_end = 7311 + _globals["_ACCELERATIONFRD"]._serialized_start = 7313 + _globals["_ACCELERATIONFRD"]._serialized_end = 7418 + _globals["_ANGULARVELOCITYFRD"]._serialized_start = 7420 + _globals["_ANGULARVELOCITYFRD"]._serialized_end = 7531 + _globals["_MAGNETICFIELDFRD"]._serialized_start = 7533 + _globals["_MAGNETICFIELDFRD"]._serialized_end = 7642 + _globals["_IMU"]._serialized_start = 7645 + _globals["_IMU"]._serialized_end = 7933 + _globals["_TELEMETRYSERVERRESULT"]._serialized_start = 7936 + _globals["_TELEMETRYSERVERRESULT"]._serialized_end = 8244 + _globals["_TELEMETRYSERVERRESULT_RESULT"]._serialized_start = 8057 + _globals["_TELEMETRYSERVERRESULT_RESULT"]._serialized_end = 8244 + _globals["_TELEMETRYSERVERSERVICE"]._serialized_start = 8960 + _globals["_TELEMETRYSERVERSERVICE"]._serialized_end = 11345 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/telemetry_server_pb2_grpc.py b/mavsdk/telemetry_server_pb2_grpc.py index a402d849..937d29e1 100644 --- a/mavsdk/telemetry_server_pb2_grpc.py +++ b/mavsdk/telemetry_server_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import telemetry_server_pb2 as telemetry__server_dot_telemetry__server__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in telemetry_server/telemetry_server_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in telemetry_server/telemetry_server_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -38,90 +42,107 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.PublishPosition = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPosition', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPosition", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionResponse.FromString, + _registered_method=True, + ) self.PublishHome = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishHome', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishHome", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeResponse.FromString, + _registered_method=True, + ) self.PublishSysStatus = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishSysStatus', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishSysStatus", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusResponse.FromString, + _registered_method=True, + ) self.PublishExtendedSysState = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishExtendedSysState', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishExtendedSysState", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateResponse.FromString, + _registered_method=True, + ) self.PublishRawGps = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawGps', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawGps", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsResponse.FromString, + _registered_method=True, + ) self.PublishBattery = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishBattery', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishBattery", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryResponse.FromString, + _registered_method=True, + ) self.PublishStatusText = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishStatusText', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishStatusText", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextResponse.FromString, + _registered_method=True, + ) self.PublishOdometry = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishOdometry', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishOdometry", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryResponse.FromString, + _registered_method=True, + ) self.PublishPositionVelocityNed = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPositionVelocityNed', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPositionVelocityNed", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedResponse.FromString, + _registered_method=True, + ) self.PublishGroundTruth = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishGroundTruth', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishGroundTruth", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthResponse.FromString, + _registered_method=True, + ) self.PublishImu = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishImu', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishImuRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishImu", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishImuRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishImuResponse.FromString, + _registered_method=True, + ) self.PublishScaledImu = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishScaledImu', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishScaledImu", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuResponse.FromString, + _registered_method=True, + ) self.PublishRawImu = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawImu', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawImu", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuResponse.FromString, + _registered_method=True, + ) self.PublishUnixEpochTime = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishUnixEpochTime', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishUnixEpochTime", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeResponse.FromString, + _registered_method=True, + ) self.PublishDistanceSensor = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishDistanceSensor', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishDistanceSensor", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorResponse.FromString, + _registered_method=True, + ) self.PublishAttitude = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishAttitude', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishAttitude", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeResponse.FromString, + _registered_method=True, + ) self.PublishVisualFlightRulesHud = channel.unary_unary( - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishVisualFlightRulesHud', - request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudRequest.SerializeToString, - response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishVisualFlightRulesHud", + request_serializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudRequest.SerializeToString, + response_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudResponse.FromString, + _registered_method=True, + ) class TelemetryServerServiceServicer(object): @@ -131,220 +152,206 @@ class TelemetryServerServiceServicer(object): """ def PublishPosition(self, request, context): - """Publish to 'position' updates. - """ + """Publish to 'position' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishHome(self, request, context): - """Publish to 'home position' updates. - """ + """Publish to 'home position' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishSysStatus(self, request, context): - """Publish 'sys status' updates. - """ + """Publish 'sys status' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishExtendedSysState(self, request, context): - """Publish 'extended sys state' updates. - """ + """Publish 'extended sys state' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishRawGps(self, request, context): - """Publish to 'Raw GPS' updates. - """ + """Publish to 'Raw GPS' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishBattery(self, request, context): - """Publish to 'battery' updates. - """ + """Publish to 'battery' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishStatusText(self, request, context): - """Publish to 'status text' updates. - """ + """Publish to 'status text' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishOdometry(self, request, context): - """Publish to 'odometry' updates. - """ + """Publish to 'odometry' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishPositionVelocityNed(self, request, context): - """Publish to 'position velocity' updates. - """ + """Publish to 'position velocity' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishGroundTruth(self, request, context): - """Publish to 'ground truth' updates. - """ + """Publish to 'ground truth' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishImu(self, request, context): - """Publish to 'IMU' updates (in SI units in NED body frame). - """ + """Publish to 'IMU' updates (in SI units in NED body frame).""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishScaledImu(self, request, context): - """Publish to 'Scaled IMU' updates. - """ + """Publish to 'Scaled IMU' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishRawImu(self, request, context): - """Publish to 'Raw IMU' updates. - """ + """Publish to 'Raw IMU' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishUnixEpochTime(self, request, context): - """Publish to 'unix epoch time' updates. - """ + """Publish to 'unix epoch time' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishDistanceSensor(self, request, context): - """Publish to "distance sensor" updates. - """ + """Publish to "distance sensor" updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishAttitude(self, request, context): - """Publish to "attitude" updates. - """ + """Publish to "attitude" updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def PublishVisualFlightRulesHud(self, request, context): - """Publish to "Visual Flight Rules HUD" updates. - """ + """Publish to "Visual Flight Rules HUD" updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_TelemetryServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'PublishPosition': grpc.unary_unary_rpc_method_handler( - servicer.PublishPosition, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionResponse.SerializeToString, - ), - 'PublishHome': grpc.unary_unary_rpc_method_handler( - servicer.PublishHome, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeResponse.SerializeToString, - ), - 'PublishSysStatus': grpc.unary_unary_rpc_method_handler( - servicer.PublishSysStatus, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusResponse.SerializeToString, - ), - 'PublishExtendedSysState': grpc.unary_unary_rpc_method_handler( - servicer.PublishExtendedSysState, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateResponse.SerializeToString, - ), - 'PublishRawGps': grpc.unary_unary_rpc_method_handler( - servicer.PublishRawGps, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsResponse.SerializeToString, - ), - 'PublishBattery': grpc.unary_unary_rpc_method_handler( - servicer.PublishBattery, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryResponse.SerializeToString, - ), - 'PublishStatusText': grpc.unary_unary_rpc_method_handler( - servicer.PublishStatusText, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextResponse.SerializeToString, - ), - 'PublishOdometry': grpc.unary_unary_rpc_method_handler( - servicer.PublishOdometry, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryResponse.SerializeToString, - ), - 'PublishPositionVelocityNed': grpc.unary_unary_rpc_method_handler( - servicer.PublishPositionVelocityNed, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedResponse.SerializeToString, - ), - 'PublishGroundTruth': grpc.unary_unary_rpc_method_handler( - servicer.PublishGroundTruth, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthResponse.SerializeToString, - ), - 'PublishImu': grpc.unary_unary_rpc_method_handler( - servicer.PublishImu, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishImuRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishImuResponse.SerializeToString, - ), - 'PublishScaledImu': grpc.unary_unary_rpc_method_handler( - servicer.PublishScaledImu, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuResponse.SerializeToString, - ), - 'PublishRawImu': grpc.unary_unary_rpc_method_handler( - servicer.PublishRawImu, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuResponse.SerializeToString, - ), - 'PublishUnixEpochTime': grpc.unary_unary_rpc_method_handler( - servicer.PublishUnixEpochTime, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeResponse.SerializeToString, - ), - 'PublishDistanceSensor': grpc.unary_unary_rpc_method_handler( - servicer.PublishDistanceSensor, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorResponse.SerializeToString, - ), - 'PublishAttitude': grpc.unary_unary_rpc_method_handler( - servicer.PublishAttitude, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeResponse.SerializeToString, - ), - 'PublishVisualFlightRulesHud': grpc.unary_unary_rpc_method_handler( - servicer.PublishVisualFlightRulesHud, - request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudRequest.FromString, - response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudResponse.SerializeToString, - ), + "PublishPosition": grpc.unary_unary_rpc_method_handler( + servicer.PublishPosition, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionResponse.SerializeToString, + ), + "PublishHome": grpc.unary_unary_rpc_method_handler( + servicer.PublishHome, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishHomeResponse.SerializeToString, + ), + "PublishSysStatus": grpc.unary_unary_rpc_method_handler( + servicer.PublishSysStatus, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishSysStatusResponse.SerializeToString, + ), + "PublishExtendedSysState": grpc.unary_unary_rpc_method_handler( + servicer.PublishExtendedSysState, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateResponse.SerializeToString, + ), + "PublishRawGps": grpc.unary_unary_rpc_method_handler( + servicer.PublishRawGps, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawGpsResponse.SerializeToString, + ), + "PublishBattery": grpc.unary_unary_rpc_method_handler( + servicer.PublishBattery, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishBatteryResponse.SerializeToString, + ), + "PublishStatusText": grpc.unary_unary_rpc_method_handler( + servicer.PublishStatusText, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishStatusTextResponse.SerializeToString, + ), + "PublishOdometry": grpc.unary_unary_rpc_method_handler( + servicer.PublishOdometry, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishOdometryResponse.SerializeToString, + ), + "PublishPositionVelocityNed": grpc.unary_unary_rpc_method_handler( + servicer.PublishPositionVelocityNed, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedResponse.SerializeToString, + ), + "PublishGroundTruth": grpc.unary_unary_rpc_method_handler( + servicer.PublishGroundTruth, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthResponse.SerializeToString, + ), + "PublishImu": grpc.unary_unary_rpc_method_handler( + servicer.PublishImu, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishImuRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishImuResponse.SerializeToString, + ), + "PublishScaledImu": grpc.unary_unary_rpc_method_handler( + servicer.PublishScaledImu, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishScaledImuResponse.SerializeToString, + ), + "PublishRawImu": grpc.unary_unary_rpc_method_handler( + servicer.PublishRawImu, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishRawImuResponse.SerializeToString, + ), + "PublishUnixEpochTime": grpc.unary_unary_rpc_method_handler( + servicer.PublishUnixEpochTime, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeResponse.SerializeToString, + ), + "PublishDistanceSensor": grpc.unary_unary_rpc_method_handler( + servicer.PublishDistanceSensor, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorResponse.SerializeToString, + ), + "PublishAttitude": grpc.unary_unary_rpc_method_handler( + servicer.PublishAttitude, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishAttitudeResponse.SerializeToString, + ), + "PublishVisualFlightRulesHud": grpc.unary_unary_rpc_method_handler( + servicer.PublishVisualFlightRulesHud, + request_deserializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudRequest.FromString, + response_serializer=telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.telemetry_server.TelemetryServerService', rpc_method_handlers) + "mavsdk.rpc.telemetry_server.TelemetryServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.telemetry_server.TelemetryServerService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.telemetry_server.TelemetryServerService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class TelemetryServerService(object): """ Allow users to provide vehicle telemetry and state information @@ -352,20 +359,22 @@ class TelemetryServerService(object): """ @staticmethod - def PublishPosition(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishPosition( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPosition', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPosition", telemetry__server_dot_telemetry__server__pb2.PublishPositionRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishPositionResponse.FromString, options, @@ -376,23 +385,26 @@ def PublishPosition(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishHome(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishHome( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishHome', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishHome", telemetry__server_dot_telemetry__server__pb2.PublishHomeRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishHomeResponse.FromString, options, @@ -403,23 +415,26 @@ def PublishHome(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishSysStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishSysStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishSysStatus', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishSysStatus", telemetry__server_dot_telemetry__server__pb2.PublishSysStatusRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishSysStatusResponse.FromString, options, @@ -430,23 +445,26 @@ def PublishSysStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishExtendedSysState(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishExtendedSysState( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishExtendedSysState', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishExtendedSysState", telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishExtendedSysStateResponse.FromString, options, @@ -457,23 +475,26 @@ def PublishExtendedSysState(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishRawGps(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishRawGps( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawGps', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawGps", telemetry__server_dot_telemetry__server__pb2.PublishRawGpsRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishRawGpsResponse.FromString, options, @@ -484,23 +505,26 @@ def PublishRawGps(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishBattery(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishBattery( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishBattery', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishBattery", telemetry__server_dot_telemetry__server__pb2.PublishBatteryRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishBatteryResponse.FromString, options, @@ -511,23 +535,26 @@ def PublishBattery(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishStatusText(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishStatusText( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishStatusText', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishStatusText", telemetry__server_dot_telemetry__server__pb2.PublishStatusTextRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishStatusTextResponse.FromString, options, @@ -538,23 +565,26 @@ def PublishStatusText(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishOdometry(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishOdometry( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishOdometry', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishOdometry", telemetry__server_dot_telemetry__server__pb2.PublishOdometryRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishOdometryResponse.FromString, options, @@ -565,23 +595,26 @@ def PublishOdometry(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishPositionVelocityNed(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishPositionVelocityNed( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPositionVelocityNed', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishPositionVelocityNed", telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishPositionVelocityNedResponse.FromString, options, @@ -592,23 +625,26 @@ def PublishPositionVelocityNed(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishGroundTruth(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishGroundTruth( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishGroundTruth', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishGroundTruth", telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishGroundTruthResponse.FromString, options, @@ -619,23 +655,26 @@ def PublishGroundTruth(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishImu', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishImu", telemetry__server_dot_telemetry__server__pb2.PublishImuRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishImuResponse.FromString, options, @@ -646,23 +685,26 @@ def PublishImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishScaledImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishScaledImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishScaledImu', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishScaledImu", telemetry__server_dot_telemetry__server__pb2.PublishScaledImuRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishScaledImuResponse.FromString, options, @@ -673,23 +715,26 @@ def PublishScaledImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishRawImu(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishRawImu( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawImu', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawImu", telemetry__server_dot_telemetry__server__pb2.PublishRawImuRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishRawImuResponse.FromString, options, @@ -700,23 +745,26 @@ def PublishRawImu(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishUnixEpochTime(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishUnixEpochTime( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishUnixEpochTime', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishUnixEpochTime", telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishUnixEpochTimeResponse.FromString, options, @@ -727,23 +775,26 @@ def PublishUnixEpochTime(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishDistanceSensor(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishDistanceSensor( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishDistanceSensor', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishDistanceSensor", telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishDistanceSensorResponse.FromString, options, @@ -754,23 +805,26 @@ def PublishDistanceSensor(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishAttitude(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishAttitude( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishAttitude', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishAttitude", telemetry__server_dot_telemetry__server__pb2.PublishAttitudeRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishAttitudeResponse.FromString, options, @@ -781,23 +835,26 @@ def PublishAttitude(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def PublishVisualFlightRulesHud(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PublishVisualFlightRulesHud( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishVisualFlightRulesHud', + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishVisualFlightRulesHud", telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudRequest.SerializeToString, telemetry__server_dot_telemetry__server__pb2.PublishVisualFlightRulesHudResponse.FromString, options, @@ -808,4 +865,5 @@ def PublishVisualFlightRulesHud(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/tracking_server.py b/mavsdk/tracking_server.py index 607fabd4..06bc5960 100644 --- a/mavsdk/tracking_server.py +++ b/mavsdk/tracking_server.py @@ -8,28 +8,27 @@ class CommandAnswer(Enum): """ - Answer to respond to an incoming command + Answer to respond to an incoming command - Values - ------ - ACCEPTED - Command accepted + Values + ------ + ACCEPTED + Command accepted - TEMPORARILY_REJECTED - Command temporarily rejected + TEMPORARILY_REJECTED + Command temporarily rejected - DENIED - Command denied + DENIED + Command denied - UNSUPPORTED - Command unsupported + UNSUPPORTED + Command unsupported - FAILED - Command failed + FAILED + Command failed - """ + """ - ACCEPTED = 0 TEMPORARILY_REJECTED = 1 DENIED = 2 @@ -50,7 +49,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == tracking_server_pb2.COMMAND_ANSWER_ACCEPTED: return CommandAnswer.ACCEPTED if rpc_enum_value == tracking_server_pb2.COMMAND_ANSWER_TEMPORARILY_REJECTED: @@ -68,237 +67,187 @@ def __str__(self): class TrackPoint: """ - Point description type - - Parameters - ---------- - point_x : float - Point to track x value (normalized 0..1, 0 is left, 1 is right). + Point description type - point_y : float - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + Parameters + ---------- + point_x : float + Point to track x value (normalized 0..1, 0 is left, 1 is right). - radius : float - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). + point_y : float + Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - """ + radius : float + Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - + """ - def __init__( - self, - point_x, - point_y, - radius): - """ Initializes the TrackPoint object """ + def __init__(self, point_x, point_y, radius): + """Initializes the TrackPoint object""" self.point_x = point_x self.point_y = point_y self.radius = radius def __eq__(self, to_compare): - """ Checks if two TrackPoint are the same """ + """Checks if two TrackPoint are the same""" try: # Try to compare - this likely fails when it is compared to a non # TrackPoint object - return \ - (self.point_x == to_compare.point_x) and \ - (self.point_y == to_compare.point_y) and \ - (self.radius == to_compare.radius) + return ( + (self.point_x == to_compare.point_x) + and (self.point_y == to_compare.point_y) + and (self.radius == to_compare.radius) + ) except AttributeError: return False def __str__(self): - """ TrackPoint in string representation """ - struct_repr = ", ".join([ + """TrackPoint in string representation""" + struct_repr = ", ".join( + [ "point_x: " + str(self.point_x), "point_y: " + str(self.point_y), - "radius: " + str(self.radius) - ]) + "radius: " + str(self.radius), + ] + ) return f"TrackPoint: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTrackPoint): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TrackPoint( - - rpcTrackPoint.point_x, - - - rpcTrackPoint.point_y, - - - rpcTrackPoint.radius - ) + rpcTrackPoint.point_x, rpcTrackPoint.point_y, rpcTrackPoint.radius + ) def translate_to_rpc(self, rpcTrackPoint): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTrackPoint.point_x = self.point_x - - - - - + rpcTrackPoint.point_y = self.point_y - - - - - + rpcTrackPoint.radius = self.radius - - - class TrackRectangle: """ - Rectangle description type - - Parameters - ---------- - top_left_corner_x : float - Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + Rectangle description type - top_left_corner_y : float - Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + Parameters + ---------- + top_left_corner_x : float + Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - bottom_right_corner_x : float - Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). + top_left_corner_y : float + Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - bottom_right_corner_y : float - Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). + bottom_right_corner_x : float + Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - """ + bottom_right_corner_y : float + Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - + """ def __init__( - self, - top_left_corner_x, - top_left_corner_y, - bottom_right_corner_x, - bottom_right_corner_y): - """ Initializes the TrackRectangle object """ + self, + top_left_corner_x, + top_left_corner_y, + bottom_right_corner_x, + bottom_right_corner_y, + ): + """Initializes the TrackRectangle object""" self.top_left_corner_x = top_left_corner_x self.top_left_corner_y = top_left_corner_y self.bottom_right_corner_x = bottom_right_corner_x self.bottom_right_corner_y = bottom_right_corner_y def __eq__(self, to_compare): - """ Checks if two TrackRectangle are the same """ + """Checks if two TrackRectangle are the same""" try: # Try to compare - this likely fails when it is compared to a non # TrackRectangle object - return \ - (self.top_left_corner_x == to_compare.top_left_corner_x) and \ - (self.top_left_corner_y == to_compare.top_left_corner_y) and \ - (self.bottom_right_corner_x == to_compare.bottom_right_corner_x) and \ - (self.bottom_right_corner_y == to_compare.bottom_right_corner_y) + return ( + (self.top_left_corner_x == to_compare.top_left_corner_x) + and (self.top_left_corner_y == to_compare.top_left_corner_y) + and (self.bottom_right_corner_x == to_compare.bottom_right_corner_x) + and (self.bottom_right_corner_y == to_compare.bottom_right_corner_y) + ) except AttributeError: return False def __str__(self): - """ TrackRectangle in string representation """ - struct_repr = ", ".join([ + """TrackRectangle in string representation""" + struct_repr = ", ".join( + [ "top_left_corner_x: " + str(self.top_left_corner_x), "top_left_corner_y: " + str(self.top_left_corner_y), "bottom_right_corner_x: " + str(self.bottom_right_corner_x), - "bottom_right_corner_y: " + str(self.bottom_right_corner_y) - ]) + "bottom_right_corner_y: " + str(self.bottom_right_corner_y), + ] + ) return f"TrackRectangle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTrackRectangle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TrackRectangle( - - rpcTrackRectangle.top_left_corner_x, - - - rpcTrackRectangle.top_left_corner_y, - - - rpcTrackRectangle.bottom_right_corner_x, - - - rpcTrackRectangle.bottom_right_corner_y - ) + rpcTrackRectangle.top_left_corner_x, + rpcTrackRectangle.top_left_corner_y, + rpcTrackRectangle.bottom_right_corner_x, + rpcTrackRectangle.bottom_right_corner_y, + ) def translate_to_rpc(self, rpcTrackRectangle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTrackRectangle.top_left_corner_x = self.top_left_corner_x - - - - - + rpcTrackRectangle.top_left_corner_y = self.top_left_corner_y - - - - - + rpcTrackRectangle.bottom_right_corner_x = self.bottom_right_corner_x - - - - - + rpcTrackRectangle.bottom_right_corner_y = self.bottom_right_corner_y - - - class TrackingServerResult: """ - Result type + Result type - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for tracking_server requests. + Possible results returned for tracking_server requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -316,81 +265,76 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ - if rpc_enum_value == tracking_server_pb2.TrackingServerResult.RESULT_UNKNOWN: + """Parses a gRPC response""" + if ( + rpc_enum_value + == tracking_server_pb2.TrackingServerResult.RESULT_UNKNOWN + ): return TrackingServerResult.Result.UNKNOWN - if rpc_enum_value == tracking_server_pb2.TrackingServerResult.RESULT_SUCCESS: + if ( + rpc_enum_value + == tracking_server_pb2.TrackingServerResult.RESULT_SUCCESS + ): return TrackingServerResult.Result.SUCCESS - if rpc_enum_value == tracking_server_pb2.TrackingServerResult.RESULT_NO_SYSTEM: + if ( + rpc_enum_value + == tracking_server_pb2.TrackingServerResult.RESULT_NO_SYSTEM + ): return TrackingServerResult.Result.NO_SYSTEM - if rpc_enum_value == tracking_server_pb2.TrackingServerResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == tracking_server_pb2.TrackingServerResult.RESULT_CONNECTION_ERROR + ): return TrackingServerResult.Result.CONNECTION_ERROR def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the TrackingServerResult object """ + def __init__(self, result, result_str): + """Initializes the TrackingServerResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two TrackingServerResult are the same """ + """Checks if two TrackingServerResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # TrackingServerResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ TrackingServerResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """TrackingServerResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"TrackingServerResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTrackingServerResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TrackingServerResult( - - TrackingServerResult.Result.translate_from_rpc(rpcTrackingServerResult.result), - - - rpcTrackingServerResult.result_str - ) + TrackingServerResult.Result.translate_from_rpc( + rpcTrackingServerResult.result + ), + rpcTrackingServerResult.result_str, + ) def translate_to_rpc(self, rpcTrackingServerResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTrackingServerResult.result = self.result.translate_to_rpc() - - - - - - rpcTrackingServerResult.result_str = self.result_str - - - + rpcTrackingServerResult.result_str = self.result_str class TrackingServerError(Exception): - """ Raised when a TrackingServerResult is a fail code """ + """Raised when a TrackingServerResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -403,136 +347,124 @@ def __str__(self): class TrackingServer(AsyncBase): """ - API for an onboard image tracking software. + API for an onboard image tracking software. - Generated by dcsdkgen - MAVSDK TrackingServer API + Generated by dcsdkgen - MAVSDK TrackingServer API """ # Plugin name name = "TrackingServer" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = tracking_server_pb2_grpc.TrackingServerServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return TrackingServerResult.translate_from_rpc(response.tracking_server_result) - async def set_tracking_point_status(self, tracked_point): """ - Set/update the current point tracking status. + Set/update the current point tracking status. + + Parameters + ---------- + tracked_point : TrackPoint + The tracked point - Parameters - ---------- - tracked_point : TrackPoint - The tracked point - """ request = tracking_server_pb2.SetTrackingPointStatusRequest() - + tracked_point.translate_to_rpc(request.tracked_point) - - - response = await self._stub.SetTrackingPointStatus(request) - + response = await self._stub.SetTrackingPointStatus(request) async def set_tracking_rectangle_status(self, tracked_rectangle): """ - Set/update the current rectangle tracking status. + Set/update the current rectangle tracking status. + + Parameters + ---------- + tracked_rectangle : TrackRectangle + The tracked rectangle - Parameters - ---------- - tracked_rectangle : TrackRectangle - The tracked rectangle - """ request = tracking_server_pb2.SetTrackingRectangleStatusRequest() - + tracked_rectangle.translate_to_rpc(request.tracked_rectangle) - - - response = await self._stub.SetTrackingRectangleStatus(request) - + response = await self._stub.SetTrackingRectangleStatus(request) async def set_tracking_off_status(self): """ - Set the current tracking status to off. + Set the current tracking status to off. + - """ request = tracking_server_pb2.SetTrackingOffStatusRequest() response = await self._stub.SetTrackingOffStatus(request) - - async def tracking_point_command(self): """ - Subscribe to incoming tracking point command. + Subscribe to incoming tracking point command. + + Yields + ------- + track_point : TrackPoint + The point to track if a point is to be tracked - Yields - ------- - track_point : TrackPoint - The point to track if a point is to be tracked - """ request = tracking_server_pb2.SubscribeTrackingPointCommandRequest() - tracking_point_command_stream = self._stub.SubscribeTrackingPointCommand(request) + tracking_point_command_stream = self._stub.SubscribeTrackingPointCommand( + request + ) try: async for response in tracking_point_command_stream: - - - yield TrackPoint.translate_from_rpc(response.track_point) finally: tracking_point_command_stream.cancel() async def tracking_rectangle_command(self): """ - Subscribe to incoming tracking rectangle command. + Subscribe to incoming tracking rectangle command. + + Yields + ------- + track_rectangle : TrackRectangle + The point to track if a point is to be tracked - Yields - ------- - track_rectangle : TrackRectangle - The point to track if a point is to be tracked - """ request = tracking_server_pb2.SubscribeTrackingRectangleCommandRequest() - tracking_rectangle_command_stream = self._stub.SubscribeTrackingRectangleCommand(request) + tracking_rectangle_command_stream = ( + self._stub.SubscribeTrackingRectangleCommand(request) + ) try: async for response in tracking_rectangle_command_stream: - - - yield TrackRectangle.translate_from_rpc(response.track_rectangle) finally: tracking_rectangle_command_stream.cancel() async def tracking_off_command(self): """ - Subscribe to incoming tracking off command. + Subscribe to incoming tracking off command. + + Yields + ------- + dummy : int32_t + Unused - Yields - ------- - dummy : int32_t - Unused - """ request = tracking_server_pb2.SubscribeTrackingOffCommandRequest() @@ -540,96 +472,90 @@ async def tracking_off_command(self): try: async for response in tracking_off_command_stream: - - - yield response.dummy finally: tracking_off_command_stream.cancel() async def respond_tracking_point_command(self, command_answer): """ - Respond to an incoming tracking point command. + Respond to an incoming tracking point command. - Parameters - ---------- - command_answer : CommandAnswer - The ack to answer to the incoming command + Parameters + ---------- + command_answer : CommandAnswer + The ack to answer to the incoming command - Raises - ------ - TrackingServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TrackingServerError + If the request fails. The error contains the reason for the failure. """ request = tracking_server_pb2.RespondTrackingPointCommandRequest() - + request.command_answer = command_answer.translate_to_rpc() - - + response = await self._stub.RespondTrackingPointCommand(request) - result = self._extract_result(response) if result.result != TrackingServerResult.Result.SUCCESS: - raise TrackingServerError(result, "respond_tracking_point_command()", command_answer) - + raise TrackingServerError( + result, "respond_tracking_point_command()", command_answer + ) async def respond_tracking_rectangle_command(self, command_answer): """ - Respond to an incoming tracking rectangle command. + Respond to an incoming tracking rectangle command. - Parameters - ---------- - command_answer : CommandAnswer - The ack to answer to the incoming command + Parameters + ---------- + command_answer : CommandAnswer + The ack to answer to the incoming command - Raises - ------ - TrackingServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TrackingServerError + If the request fails. The error contains the reason for the failure. """ request = tracking_server_pb2.RespondTrackingRectangleCommandRequest() - + request.command_answer = command_answer.translate_to_rpc() - - + response = await self._stub.RespondTrackingRectangleCommand(request) - result = self._extract_result(response) if result.result != TrackingServerResult.Result.SUCCESS: - raise TrackingServerError(result, "respond_tracking_rectangle_command()", command_answer) - + raise TrackingServerError( + result, "respond_tracking_rectangle_command()", command_answer + ) async def respond_tracking_off_command(self, command_answer): """ - Respond to an incoming tracking off command. + Respond to an incoming tracking off command. - Parameters - ---------- - command_answer : CommandAnswer - The ack to answer to the incoming command + Parameters + ---------- + command_answer : CommandAnswer + The ack to answer to the incoming command - Raises - ------ - TrackingServerError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TrackingServerError + If the request fails. The error contains the reason for the failure. """ request = tracking_server_pb2.RespondTrackingOffCommandRequest() - + request.command_answer = command_answer.translate_to_rpc() - - + response = await self._stub.RespondTrackingOffCommand(request) - result = self._extract_result(response) if result.result != TrackingServerResult.Result.SUCCESS: - raise TrackingServerError(result, "respond_tracking_off_command()", command_answer) - \ No newline at end of file + raise TrackingServerError( + result, "respond_tracking_off_command()", command_answer + ) diff --git a/mavsdk/tracking_server_pb2.py b/mavsdk/tracking_server_pb2.py index b793393b..4a7dfadb 100644 --- a/mavsdk/tracking_server_pb2.py +++ b/mavsdk/tracking_server_pb2.py @@ -2,6 +2,7 @@ # Generated by the protocol buffer compiler. DO NOT EDIT! # source: tracking_server/tracking_server.proto """Generated protocol buffer code.""" + from google.protobuf.internal import enum_type_wrapper from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool @@ -16,9 +17,11 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n%tracking_server/tracking_server.proto\x12\x1amavsdk.rpc.tracking_server\x1a\x14mavsdk_options.proto\"^\n\x1dSetTrackingPointStatusRequest\x12=\n\rtracked_point\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.tracking_server.TrackPoint\" \n\x1eSetTrackingPointStatusResponse\"j\n!SetTrackingRectangleStatusRequest\x12\x45\n\x11tracked_rectangle\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.tracking_server.TrackRectangle\"$\n\"SetTrackingRectangleStatusResponse\"\x1d\n\x1bSetTrackingOffStatusRequest\"\x1e\n\x1cSetTrackingOffStatusResponse\"&\n$SubscribeTrackingPointCommandRequest\"[\n\x1cTrackingPointCommandResponse\x12;\n\x0btrack_point\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.tracking_server.TrackPoint\"*\n(SubscribeTrackingRectangleCommandRequest\"g\n TrackingRectangleCommandResponse\x12\x43\n\x0ftrack_rectangle\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.tracking_server.TrackRectangle\"$\n\"SubscribeTrackingOffCommandRequest\"+\n\x1aTrackingOffCommandResponse\x12\r\n\x05\x64ummy\x18\x01 \x01(\x05\"g\n\"RespondTrackingPointCommandRequest\x12\x41\n\x0e\x63ommand_answer\x18\x01 \x01(\x0e\x32).mavsdk.rpc.tracking_server.CommandAnswer\"w\n#RespondTrackingPointCommandResponse\x12P\n\x16tracking_server_result\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.tracking_server.TrackingServerResult\"k\n&RespondTrackingRectangleCommandRequest\x12\x41\n\x0e\x63ommand_answer\x18\x01 \x01(\x0e\x32).mavsdk.rpc.tracking_server.CommandAnswer\"{\n\'RespondTrackingRectangleCommandResponse\x12P\n\x16tracking_server_result\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.tracking_server.TrackingServerResult\"e\n RespondTrackingOffCommandRequest\x12\x41\n\x0e\x63ommand_answer\x18\x01 \x01(\x0e\x32).mavsdk.rpc.tracking_server.CommandAnswer\"u\n!RespondTrackingOffCommandResponse\x12P\n\x16tracking_server_result\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.tracking_server.TrackingServerResult\">\n\nTrackPoint\x12\x0f\n\x07point_x\x18\x01 \x01(\x02\x12\x0f\n\x07point_y\x18\x02 \x01(\x02\x12\x0e\n\x06radius\x18\x03 \x01(\x02\"\x84\x01\n\x0eTrackRectangle\x12\x19\n\x11top_left_corner_x\x18\x01 \x01(\x02\x12\x19\n\x11top_left_corner_y\x18\x02 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_x\x18\x03 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_y\x18\x04 \x01(\x02\"\xd8\x01\n\x14TrackingServerResult\x12G\n\x06result\x18\x01 \x01(\x0e\x32\x37.mavsdk.rpc.tracking_server.TrackingServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"c\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*\xab\x01\n\rCommandAnswer\x12\x1b\n\x17\x43OMMAND_ANSWER_ACCEPTED\x10\x00\x12\'\n#COMMAND_ANSWER_TEMPORARILY_REJECTED\x10\x01\x12\x19\n\x15\x43OMMAND_ANSWER_DENIED\x10\x02\x12\x1e\n\x1a\x43OMMAND_ANSWER_UNSUPPORTED\x10\x03\x12\x19\n\x15\x43OMMAND_ANSWER_FAILED\x10\x04\x32\xd8\x0b\n\x15TrackingServerService\x12\x95\x01\n\x16SetTrackingPointStatus\x12\x39.mavsdk.rpc.tracking_server.SetTrackingPointStatusRequest\x1a:.mavsdk.rpc.tracking_server.SetTrackingPointStatusResponse\"\x04\x80\xb5\x18\x01\x12\xa1\x01\n\x1aSetTrackingRectangleStatus\x12=.mavsdk.rpc.tracking_server.SetTrackingRectangleStatusRequest\x1a>.mavsdk.rpc.tracking_server.SetTrackingRectangleStatusResponse\"\x04\x80\xb5\x18\x01\x12\x8f\x01\n\x14SetTrackingOffStatus\x12\x37.mavsdk.rpc.tracking_server.SetTrackingOffStatusRequest\x1a\x38.mavsdk.rpc.tracking_server.SetTrackingOffStatusResponse\"\x04\x80\xb5\x18\x01\x12\xa3\x01\n\x1dSubscribeTrackingPointCommand\x12@.mavsdk.rpc.tracking_server.SubscribeTrackingPointCommandRequest\x1a\x38.mavsdk.rpc.tracking_server.TrackingPointCommandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\xaf\x01\n!SubscribeTrackingRectangleCommand\x12\x44.mavsdk.rpc.tracking_server.SubscribeTrackingRectangleCommandRequest\x1a<.mavsdk.rpc.tracking_server.TrackingRectangleCommandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\x9d\x01\n\x1bSubscribeTrackingOffCommand\x12>.mavsdk.rpc.tracking_server.SubscribeTrackingOffCommandRequest\x1a\x36.mavsdk.rpc.tracking_server.TrackingOffCommandResponse\"\x04\x80\xb5\x18\x00\x30\x01\x12\xa4\x01\n\x1bRespondTrackingPointCommand\x12>.mavsdk.rpc.tracking_server.RespondTrackingPointCommandRequest\x1a?.mavsdk.rpc.tracking_server.RespondTrackingPointCommandResponse\"\x04\x80\xb5\x18\x01\x12\xb0\x01\n\x1fRespondTrackingRectangleCommand\x12\x42.mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandRequest\x1a\x43.mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandResponse\"\x04\x80\xb5\x18\x01\x12\x9e\x01\n\x19RespondTrackingOffCommand\x12<.mavsdk.rpc.tracking_server.RespondTrackingOffCommandRequest\x1a=.mavsdk.rpc.tracking_server.RespondTrackingOffCommandResponse\"\x04\x80\xb5\x18\x01\x42\x30\n\x19io.mavsdk.tracking_serverB\x13TrackingServerProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n%tracking_server/tracking_server.proto\x12\x1amavsdk.rpc.tracking_server\x1a\x14mavsdk_options.proto"^\n\x1dSetTrackingPointStatusRequest\x12=\n\rtracked_point\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.tracking_server.TrackPoint" \n\x1eSetTrackingPointStatusResponse"j\n!SetTrackingRectangleStatusRequest\x12\x45\n\x11tracked_rectangle\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.tracking_server.TrackRectangle"$\n"SetTrackingRectangleStatusResponse"\x1d\n\x1bSetTrackingOffStatusRequest"\x1e\n\x1cSetTrackingOffStatusResponse"&\n$SubscribeTrackingPointCommandRequest"[\n\x1cTrackingPointCommandResponse\x12;\n\x0btrack_point\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.tracking_server.TrackPoint"*\n(SubscribeTrackingRectangleCommandRequest"g\n TrackingRectangleCommandResponse\x12\x43\n\x0ftrack_rectangle\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.tracking_server.TrackRectangle"$\n"SubscribeTrackingOffCommandRequest"+\n\x1aTrackingOffCommandResponse\x12\r\n\x05\x64ummy\x18\x01 \x01(\x05"g\n"RespondTrackingPointCommandRequest\x12\x41\n\x0e\x63ommand_answer\x18\x01 \x01(\x0e\x32).mavsdk.rpc.tracking_server.CommandAnswer"w\n#RespondTrackingPointCommandResponse\x12P\n\x16tracking_server_result\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.tracking_server.TrackingServerResult"k\n&RespondTrackingRectangleCommandRequest\x12\x41\n\x0e\x63ommand_answer\x18\x01 \x01(\x0e\x32).mavsdk.rpc.tracking_server.CommandAnswer"{\n\'RespondTrackingRectangleCommandResponse\x12P\n\x16tracking_server_result\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.tracking_server.TrackingServerResult"e\n RespondTrackingOffCommandRequest\x12\x41\n\x0e\x63ommand_answer\x18\x01 \x01(\x0e\x32).mavsdk.rpc.tracking_server.CommandAnswer"u\n!RespondTrackingOffCommandResponse\x12P\n\x16tracking_server_result\x18\x01 \x01(\x0b\x32\x30.mavsdk.rpc.tracking_server.TrackingServerResult">\n\nTrackPoint\x12\x0f\n\x07point_x\x18\x01 \x01(\x02\x12\x0f\n\x07point_y\x18\x02 \x01(\x02\x12\x0e\n\x06radius\x18\x03 \x01(\x02"\x84\x01\n\x0eTrackRectangle\x12\x19\n\x11top_left_corner_x\x18\x01 \x01(\x02\x12\x19\n\x11top_left_corner_y\x18\x02 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_x\x18\x03 \x01(\x02\x12\x1d\n\x15\x62ottom_right_corner_y\x18\x04 \x01(\x02"\xd8\x01\n\x14TrackingServerResult\x12G\n\x06result\x18\x01 \x01(\x0e\x32\x37.mavsdk.rpc.tracking_server.TrackingServerResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"c\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*\xab\x01\n\rCommandAnswer\x12\x1b\n\x17\x43OMMAND_ANSWER_ACCEPTED\x10\x00\x12\'\n#COMMAND_ANSWER_TEMPORARILY_REJECTED\x10\x01\x12\x19\n\x15\x43OMMAND_ANSWER_DENIED\x10\x02\x12\x1e\n\x1a\x43OMMAND_ANSWER_UNSUPPORTED\x10\x03\x12\x19\n\x15\x43OMMAND_ANSWER_FAILED\x10\x04\x32\xd8\x0b\n\x15TrackingServerService\x12\x95\x01\n\x16SetTrackingPointStatus\x12\x39.mavsdk.rpc.tracking_server.SetTrackingPointStatusRequest\x1a:.mavsdk.rpc.tracking_server.SetTrackingPointStatusResponse"\x04\x80\xb5\x18\x01\x12\xa1\x01\n\x1aSetTrackingRectangleStatus\x12=.mavsdk.rpc.tracking_server.SetTrackingRectangleStatusRequest\x1a>.mavsdk.rpc.tracking_server.SetTrackingRectangleStatusResponse"\x04\x80\xb5\x18\x01\x12\x8f\x01\n\x14SetTrackingOffStatus\x12\x37.mavsdk.rpc.tracking_server.SetTrackingOffStatusRequest\x1a\x38.mavsdk.rpc.tracking_server.SetTrackingOffStatusResponse"\x04\x80\xb5\x18\x01\x12\xa3\x01\n\x1dSubscribeTrackingPointCommand\x12@.mavsdk.rpc.tracking_server.SubscribeTrackingPointCommandRequest\x1a\x38.mavsdk.rpc.tracking_server.TrackingPointCommandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\xaf\x01\n!SubscribeTrackingRectangleCommand\x12\x44.mavsdk.rpc.tracking_server.SubscribeTrackingRectangleCommandRequest\x1a<.mavsdk.rpc.tracking_server.TrackingRectangleCommandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\x9d\x01\n\x1bSubscribeTrackingOffCommand\x12>.mavsdk.rpc.tracking_server.SubscribeTrackingOffCommandRequest\x1a\x36.mavsdk.rpc.tracking_server.TrackingOffCommandResponse"\x04\x80\xb5\x18\x00\x30\x01\x12\xa4\x01\n\x1bRespondTrackingPointCommand\x12>.mavsdk.rpc.tracking_server.RespondTrackingPointCommandRequest\x1a?.mavsdk.rpc.tracking_server.RespondTrackingPointCommandResponse"\x04\x80\xb5\x18\x01\x12\xb0\x01\n\x1fRespondTrackingRectangleCommand\x12\x42.mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandRequest\x1a\x43.mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandResponse"\x04\x80\xb5\x18\x01\x12\x9e\x01\n\x19RespondTrackingOffCommand\x12<.mavsdk.rpc.tracking_server.RespondTrackingOffCommandRequest\x1a=.mavsdk.rpc.tracking_server.RespondTrackingOffCommandResponse"\x04\x80\xb5\x18\x01\x42\x30\n\x19io.mavsdk.tracking_serverB\x13TrackingServerProtob\x06proto3' +) -_COMMANDANSWER = DESCRIPTOR.enum_types_by_name['CommandAnswer'] +_COMMANDANSWER = DESCRIPTOR.enum_types_by_name["CommandAnswer"] CommandAnswer = enum_type_wrapper.EnumTypeWrapper(_COMMANDANSWER) COMMAND_ANSWER_ACCEPTED = 0 COMMAND_ANSWER_TEMPORARILY_REJECTED = 1 @@ -27,244 +30,393 @@ COMMAND_ANSWER_FAILED = 4 -_SETTRACKINGPOINTSTATUSREQUEST = DESCRIPTOR.message_types_by_name['SetTrackingPointStatusRequest'] -_SETTRACKINGPOINTSTATUSRESPONSE = DESCRIPTOR.message_types_by_name['SetTrackingPointStatusResponse'] -_SETTRACKINGRECTANGLESTATUSREQUEST = DESCRIPTOR.message_types_by_name['SetTrackingRectangleStatusRequest'] -_SETTRACKINGRECTANGLESTATUSRESPONSE = DESCRIPTOR.message_types_by_name['SetTrackingRectangleStatusResponse'] -_SETTRACKINGOFFSTATUSREQUEST = DESCRIPTOR.message_types_by_name['SetTrackingOffStatusRequest'] -_SETTRACKINGOFFSTATUSRESPONSE = DESCRIPTOR.message_types_by_name['SetTrackingOffStatusResponse'] -_SUBSCRIBETRACKINGPOINTCOMMANDREQUEST = DESCRIPTOR.message_types_by_name['SubscribeTrackingPointCommandRequest'] -_TRACKINGPOINTCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name['TrackingPointCommandResponse'] -_SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST = DESCRIPTOR.message_types_by_name['SubscribeTrackingRectangleCommandRequest'] -_TRACKINGRECTANGLECOMMANDRESPONSE = DESCRIPTOR.message_types_by_name['TrackingRectangleCommandResponse'] -_SUBSCRIBETRACKINGOFFCOMMANDREQUEST = DESCRIPTOR.message_types_by_name['SubscribeTrackingOffCommandRequest'] -_TRACKINGOFFCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name['TrackingOffCommandResponse'] -_RESPONDTRACKINGPOINTCOMMANDREQUEST = DESCRIPTOR.message_types_by_name['RespondTrackingPointCommandRequest'] -_RESPONDTRACKINGPOINTCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name['RespondTrackingPointCommandResponse'] -_RESPONDTRACKINGRECTANGLECOMMANDREQUEST = DESCRIPTOR.message_types_by_name['RespondTrackingRectangleCommandRequest'] -_RESPONDTRACKINGRECTANGLECOMMANDRESPONSE = DESCRIPTOR.message_types_by_name['RespondTrackingRectangleCommandResponse'] -_RESPONDTRACKINGOFFCOMMANDREQUEST = DESCRIPTOR.message_types_by_name['RespondTrackingOffCommandRequest'] -_RESPONDTRACKINGOFFCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name['RespondTrackingOffCommandResponse'] -_TRACKPOINT = DESCRIPTOR.message_types_by_name['TrackPoint'] -_TRACKRECTANGLE = DESCRIPTOR.message_types_by_name['TrackRectangle'] -_TRACKINGSERVERRESULT = DESCRIPTOR.message_types_by_name['TrackingServerResult'] -_TRACKINGSERVERRESULT_RESULT = _TRACKINGSERVERRESULT.enum_types_by_name['Result'] -SetTrackingPointStatusRequest = _reflection.GeneratedProtocolMessageType('SetTrackingPointStatusRequest', (_message.Message,), { - 'DESCRIPTOR' : _SETTRACKINGPOINTSTATUSREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingPointStatusRequest) - }) +_SETTRACKINGPOINTSTATUSREQUEST = DESCRIPTOR.message_types_by_name[ + "SetTrackingPointStatusRequest" +] +_SETTRACKINGPOINTSTATUSRESPONSE = DESCRIPTOR.message_types_by_name[ + "SetTrackingPointStatusResponse" +] +_SETTRACKINGRECTANGLESTATUSREQUEST = DESCRIPTOR.message_types_by_name[ + "SetTrackingRectangleStatusRequest" +] +_SETTRACKINGRECTANGLESTATUSRESPONSE = DESCRIPTOR.message_types_by_name[ + "SetTrackingRectangleStatusResponse" +] +_SETTRACKINGOFFSTATUSREQUEST = DESCRIPTOR.message_types_by_name[ + "SetTrackingOffStatusRequest" +] +_SETTRACKINGOFFSTATUSRESPONSE = DESCRIPTOR.message_types_by_name[ + "SetTrackingOffStatusResponse" +] +_SUBSCRIBETRACKINGPOINTCOMMANDREQUEST = DESCRIPTOR.message_types_by_name[ + "SubscribeTrackingPointCommandRequest" +] +_TRACKINGPOINTCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name[ + "TrackingPointCommandResponse" +] +_SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST = DESCRIPTOR.message_types_by_name[ + "SubscribeTrackingRectangleCommandRequest" +] +_TRACKINGRECTANGLECOMMANDRESPONSE = DESCRIPTOR.message_types_by_name[ + "TrackingRectangleCommandResponse" +] +_SUBSCRIBETRACKINGOFFCOMMANDREQUEST = DESCRIPTOR.message_types_by_name[ + "SubscribeTrackingOffCommandRequest" +] +_TRACKINGOFFCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name[ + "TrackingOffCommandResponse" +] +_RESPONDTRACKINGPOINTCOMMANDREQUEST = DESCRIPTOR.message_types_by_name[ + "RespondTrackingPointCommandRequest" +] +_RESPONDTRACKINGPOINTCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name[ + "RespondTrackingPointCommandResponse" +] +_RESPONDTRACKINGRECTANGLECOMMANDREQUEST = DESCRIPTOR.message_types_by_name[ + "RespondTrackingRectangleCommandRequest" +] +_RESPONDTRACKINGRECTANGLECOMMANDRESPONSE = DESCRIPTOR.message_types_by_name[ + "RespondTrackingRectangleCommandResponse" +] +_RESPONDTRACKINGOFFCOMMANDREQUEST = DESCRIPTOR.message_types_by_name[ + "RespondTrackingOffCommandRequest" +] +_RESPONDTRACKINGOFFCOMMANDRESPONSE = DESCRIPTOR.message_types_by_name[ + "RespondTrackingOffCommandResponse" +] +_TRACKPOINT = DESCRIPTOR.message_types_by_name["TrackPoint"] +_TRACKRECTANGLE = DESCRIPTOR.message_types_by_name["TrackRectangle"] +_TRACKINGSERVERRESULT = DESCRIPTOR.message_types_by_name["TrackingServerResult"] +_TRACKINGSERVERRESULT_RESULT = _TRACKINGSERVERRESULT.enum_types_by_name["Result"] +SetTrackingPointStatusRequest = _reflection.GeneratedProtocolMessageType( + "SetTrackingPointStatusRequest", + (_message.Message,), + { + "DESCRIPTOR": _SETTRACKINGPOINTSTATUSREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingPointStatusRequest) + }, +) _sym_db.RegisterMessage(SetTrackingPointStatusRequest) -SetTrackingPointStatusResponse = _reflection.GeneratedProtocolMessageType('SetTrackingPointStatusResponse', (_message.Message,), { - 'DESCRIPTOR' : _SETTRACKINGPOINTSTATUSRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingPointStatusResponse) - }) +SetTrackingPointStatusResponse = _reflection.GeneratedProtocolMessageType( + "SetTrackingPointStatusResponse", + (_message.Message,), + { + "DESCRIPTOR": _SETTRACKINGPOINTSTATUSRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingPointStatusResponse) + }, +) _sym_db.RegisterMessage(SetTrackingPointStatusResponse) -SetTrackingRectangleStatusRequest = _reflection.GeneratedProtocolMessageType('SetTrackingRectangleStatusRequest', (_message.Message,), { - 'DESCRIPTOR' : _SETTRACKINGRECTANGLESTATUSREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingRectangleStatusRequest) - }) +SetTrackingRectangleStatusRequest = _reflection.GeneratedProtocolMessageType( + "SetTrackingRectangleStatusRequest", + (_message.Message,), + { + "DESCRIPTOR": _SETTRACKINGRECTANGLESTATUSREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingRectangleStatusRequest) + }, +) _sym_db.RegisterMessage(SetTrackingRectangleStatusRequest) -SetTrackingRectangleStatusResponse = _reflection.GeneratedProtocolMessageType('SetTrackingRectangleStatusResponse', (_message.Message,), { - 'DESCRIPTOR' : _SETTRACKINGRECTANGLESTATUSRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingRectangleStatusResponse) - }) +SetTrackingRectangleStatusResponse = _reflection.GeneratedProtocolMessageType( + "SetTrackingRectangleStatusResponse", + (_message.Message,), + { + "DESCRIPTOR": _SETTRACKINGRECTANGLESTATUSRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingRectangleStatusResponse) + }, +) _sym_db.RegisterMessage(SetTrackingRectangleStatusResponse) -SetTrackingOffStatusRequest = _reflection.GeneratedProtocolMessageType('SetTrackingOffStatusRequest', (_message.Message,), { - 'DESCRIPTOR' : _SETTRACKINGOFFSTATUSREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingOffStatusRequest) - }) +SetTrackingOffStatusRequest = _reflection.GeneratedProtocolMessageType( + "SetTrackingOffStatusRequest", + (_message.Message,), + { + "DESCRIPTOR": _SETTRACKINGOFFSTATUSREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingOffStatusRequest) + }, +) _sym_db.RegisterMessage(SetTrackingOffStatusRequest) -SetTrackingOffStatusResponse = _reflection.GeneratedProtocolMessageType('SetTrackingOffStatusResponse', (_message.Message,), { - 'DESCRIPTOR' : _SETTRACKINGOFFSTATUSRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingOffStatusResponse) - }) +SetTrackingOffStatusResponse = _reflection.GeneratedProtocolMessageType( + "SetTrackingOffStatusResponse", + (_message.Message,), + { + "DESCRIPTOR": _SETTRACKINGOFFSTATUSRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SetTrackingOffStatusResponse) + }, +) _sym_db.RegisterMessage(SetTrackingOffStatusResponse) -SubscribeTrackingPointCommandRequest = _reflection.GeneratedProtocolMessageType('SubscribeTrackingPointCommandRequest', (_message.Message,), { - 'DESCRIPTOR' : _SUBSCRIBETRACKINGPOINTCOMMANDREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SubscribeTrackingPointCommandRequest) - }) +SubscribeTrackingPointCommandRequest = _reflection.GeneratedProtocolMessageType( + "SubscribeTrackingPointCommandRequest", + (_message.Message,), + { + "DESCRIPTOR": _SUBSCRIBETRACKINGPOINTCOMMANDREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SubscribeTrackingPointCommandRequest) + }, +) _sym_db.RegisterMessage(SubscribeTrackingPointCommandRequest) -TrackingPointCommandResponse = _reflection.GeneratedProtocolMessageType('TrackingPointCommandResponse', (_message.Message,), { - 'DESCRIPTOR' : _TRACKINGPOINTCOMMANDRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingPointCommandResponse) - }) +TrackingPointCommandResponse = _reflection.GeneratedProtocolMessageType( + "TrackingPointCommandResponse", + (_message.Message,), + { + "DESCRIPTOR": _TRACKINGPOINTCOMMANDRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingPointCommandResponse) + }, +) _sym_db.RegisterMessage(TrackingPointCommandResponse) -SubscribeTrackingRectangleCommandRequest = _reflection.GeneratedProtocolMessageType('SubscribeTrackingRectangleCommandRequest', (_message.Message,), { - 'DESCRIPTOR' : _SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SubscribeTrackingRectangleCommandRequest) - }) +SubscribeTrackingRectangleCommandRequest = _reflection.GeneratedProtocolMessageType( + "SubscribeTrackingRectangleCommandRequest", + (_message.Message,), + { + "DESCRIPTOR": _SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SubscribeTrackingRectangleCommandRequest) + }, +) _sym_db.RegisterMessage(SubscribeTrackingRectangleCommandRequest) -TrackingRectangleCommandResponse = _reflection.GeneratedProtocolMessageType('TrackingRectangleCommandResponse', (_message.Message,), { - 'DESCRIPTOR' : _TRACKINGRECTANGLECOMMANDRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingRectangleCommandResponse) - }) +TrackingRectangleCommandResponse = _reflection.GeneratedProtocolMessageType( + "TrackingRectangleCommandResponse", + (_message.Message,), + { + "DESCRIPTOR": _TRACKINGRECTANGLECOMMANDRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingRectangleCommandResponse) + }, +) _sym_db.RegisterMessage(TrackingRectangleCommandResponse) -SubscribeTrackingOffCommandRequest = _reflection.GeneratedProtocolMessageType('SubscribeTrackingOffCommandRequest', (_message.Message,), { - 'DESCRIPTOR' : _SUBSCRIBETRACKINGOFFCOMMANDREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SubscribeTrackingOffCommandRequest) - }) +SubscribeTrackingOffCommandRequest = _reflection.GeneratedProtocolMessageType( + "SubscribeTrackingOffCommandRequest", + (_message.Message,), + { + "DESCRIPTOR": _SUBSCRIBETRACKINGOFFCOMMANDREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.SubscribeTrackingOffCommandRequest) + }, +) _sym_db.RegisterMessage(SubscribeTrackingOffCommandRequest) -TrackingOffCommandResponse = _reflection.GeneratedProtocolMessageType('TrackingOffCommandResponse', (_message.Message,), { - 'DESCRIPTOR' : _TRACKINGOFFCOMMANDRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingOffCommandResponse) - }) +TrackingOffCommandResponse = _reflection.GeneratedProtocolMessageType( + "TrackingOffCommandResponse", + (_message.Message,), + { + "DESCRIPTOR": _TRACKINGOFFCOMMANDRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingOffCommandResponse) + }, +) _sym_db.RegisterMessage(TrackingOffCommandResponse) -RespondTrackingPointCommandRequest = _reflection.GeneratedProtocolMessageType('RespondTrackingPointCommandRequest', (_message.Message,), { - 'DESCRIPTOR' : _RESPONDTRACKINGPOINTCOMMANDREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingPointCommandRequest) - }) +RespondTrackingPointCommandRequest = _reflection.GeneratedProtocolMessageType( + "RespondTrackingPointCommandRequest", + (_message.Message,), + { + "DESCRIPTOR": _RESPONDTRACKINGPOINTCOMMANDREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingPointCommandRequest) + }, +) _sym_db.RegisterMessage(RespondTrackingPointCommandRequest) -RespondTrackingPointCommandResponse = _reflection.GeneratedProtocolMessageType('RespondTrackingPointCommandResponse', (_message.Message,), { - 'DESCRIPTOR' : _RESPONDTRACKINGPOINTCOMMANDRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingPointCommandResponse) - }) +RespondTrackingPointCommandResponse = _reflection.GeneratedProtocolMessageType( + "RespondTrackingPointCommandResponse", + (_message.Message,), + { + "DESCRIPTOR": _RESPONDTRACKINGPOINTCOMMANDRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingPointCommandResponse) + }, +) _sym_db.RegisterMessage(RespondTrackingPointCommandResponse) -RespondTrackingRectangleCommandRequest = _reflection.GeneratedProtocolMessageType('RespondTrackingRectangleCommandRequest', (_message.Message,), { - 'DESCRIPTOR' : _RESPONDTRACKINGRECTANGLECOMMANDREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandRequest) - }) +RespondTrackingRectangleCommandRequest = _reflection.GeneratedProtocolMessageType( + "RespondTrackingRectangleCommandRequest", + (_message.Message,), + { + "DESCRIPTOR": _RESPONDTRACKINGRECTANGLECOMMANDREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandRequest) + }, +) _sym_db.RegisterMessage(RespondTrackingRectangleCommandRequest) -RespondTrackingRectangleCommandResponse = _reflection.GeneratedProtocolMessageType('RespondTrackingRectangleCommandResponse', (_message.Message,), { - 'DESCRIPTOR' : _RESPONDTRACKINGRECTANGLECOMMANDRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandResponse) - }) +RespondTrackingRectangleCommandResponse = _reflection.GeneratedProtocolMessageType( + "RespondTrackingRectangleCommandResponse", + (_message.Message,), + { + "DESCRIPTOR": _RESPONDTRACKINGRECTANGLECOMMANDRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingRectangleCommandResponse) + }, +) _sym_db.RegisterMessage(RespondTrackingRectangleCommandResponse) -RespondTrackingOffCommandRequest = _reflection.GeneratedProtocolMessageType('RespondTrackingOffCommandRequest', (_message.Message,), { - 'DESCRIPTOR' : _RESPONDTRACKINGOFFCOMMANDREQUEST, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingOffCommandRequest) - }) +RespondTrackingOffCommandRequest = _reflection.GeneratedProtocolMessageType( + "RespondTrackingOffCommandRequest", + (_message.Message,), + { + "DESCRIPTOR": _RESPONDTRACKINGOFFCOMMANDREQUEST, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingOffCommandRequest) + }, +) _sym_db.RegisterMessage(RespondTrackingOffCommandRequest) -RespondTrackingOffCommandResponse = _reflection.GeneratedProtocolMessageType('RespondTrackingOffCommandResponse', (_message.Message,), { - 'DESCRIPTOR' : _RESPONDTRACKINGOFFCOMMANDRESPONSE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingOffCommandResponse) - }) +RespondTrackingOffCommandResponse = _reflection.GeneratedProtocolMessageType( + "RespondTrackingOffCommandResponse", + (_message.Message,), + { + "DESCRIPTOR": _RESPONDTRACKINGOFFCOMMANDRESPONSE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.RespondTrackingOffCommandResponse) + }, +) _sym_db.RegisterMessage(RespondTrackingOffCommandResponse) -TrackPoint = _reflection.GeneratedProtocolMessageType('TrackPoint', (_message.Message,), { - 'DESCRIPTOR' : _TRACKPOINT, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackPoint) - }) +TrackPoint = _reflection.GeneratedProtocolMessageType( + "TrackPoint", + (_message.Message,), + { + "DESCRIPTOR": _TRACKPOINT, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackPoint) + }, +) _sym_db.RegisterMessage(TrackPoint) -TrackRectangle = _reflection.GeneratedProtocolMessageType('TrackRectangle', (_message.Message,), { - 'DESCRIPTOR' : _TRACKRECTANGLE, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackRectangle) - }) +TrackRectangle = _reflection.GeneratedProtocolMessageType( + "TrackRectangle", + (_message.Message,), + { + "DESCRIPTOR": _TRACKRECTANGLE, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackRectangle) + }, +) _sym_db.RegisterMessage(TrackRectangle) -TrackingServerResult = _reflection.GeneratedProtocolMessageType('TrackingServerResult', (_message.Message,), { - 'DESCRIPTOR' : _TRACKINGSERVERRESULT, - '__module__' : 'tracking_server.tracking_server_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingServerResult) - }) +TrackingServerResult = _reflection.GeneratedProtocolMessageType( + "TrackingServerResult", + (_message.Message,), + { + "DESCRIPTOR": _TRACKINGSERVERRESULT, + "__module__": "tracking_server.tracking_server_pb2", + # @@protoc_insertion_point(class_scope:mavsdk.rpc.tracking_server.TrackingServerResult) + }, +) _sym_db.RegisterMessage(TrackingServerResult) -_TRACKINGSERVERSERVICE = DESCRIPTOR.services_by_name['TrackingServerService'] +_TRACKINGSERVERSERVICE = DESCRIPTOR.services_by_name["TrackingServerService"] if _descriptor._USE_C_DESCRIPTORS == False: - - DESCRIPTOR._options = None - DESCRIPTOR._serialized_options = b'\n\031io.mavsdk.tracking_serverB\023TrackingServerProto' - _TRACKINGSERVERSERVICE.methods_by_name['SetTrackingPointStatus']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['SetTrackingPointStatus']._serialized_options = b'\200\265\030\001' - _TRACKINGSERVERSERVICE.methods_by_name['SetTrackingRectangleStatus']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['SetTrackingRectangleStatus']._serialized_options = b'\200\265\030\001' - _TRACKINGSERVERSERVICE.methods_by_name['SetTrackingOffStatus']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['SetTrackingOffStatus']._serialized_options = b'\200\265\030\001' - _TRACKINGSERVERSERVICE.methods_by_name['SubscribeTrackingPointCommand']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['SubscribeTrackingPointCommand']._serialized_options = b'\200\265\030\000' - _TRACKINGSERVERSERVICE.methods_by_name['SubscribeTrackingRectangleCommand']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['SubscribeTrackingRectangleCommand']._serialized_options = b'\200\265\030\000' - _TRACKINGSERVERSERVICE.methods_by_name['SubscribeTrackingOffCommand']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['SubscribeTrackingOffCommand']._serialized_options = b'\200\265\030\000' - _TRACKINGSERVERSERVICE.methods_by_name['RespondTrackingPointCommand']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['RespondTrackingPointCommand']._serialized_options = b'\200\265\030\001' - _TRACKINGSERVERSERVICE.methods_by_name['RespondTrackingRectangleCommand']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['RespondTrackingRectangleCommand']._serialized_options = b'\200\265\030\001' - _TRACKINGSERVERSERVICE.methods_by_name['RespondTrackingOffCommand']._options = None - _TRACKINGSERVERSERVICE.methods_by_name['RespondTrackingOffCommand']._serialized_options = b'\200\265\030\001' - _COMMANDANSWER._serialized_start=1896 - _COMMANDANSWER._serialized_end=2067 - _SETTRACKINGPOINTSTATUSREQUEST._serialized_start=91 - _SETTRACKINGPOINTSTATUSREQUEST._serialized_end=185 - _SETTRACKINGPOINTSTATUSRESPONSE._serialized_start=187 - _SETTRACKINGPOINTSTATUSRESPONSE._serialized_end=219 - _SETTRACKINGRECTANGLESTATUSREQUEST._serialized_start=221 - _SETTRACKINGRECTANGLESTATUSREQUEST._serialized_end=327 - _SETTRACKINGRECTANGLESTATUSRESPONSE._serialized_start=329 - _SETTRACKINGRECTANGLESTATUSRESPONSE._serialized_end=365 - _SETTRACKINGOFFSTATUSREQUEST._serialized_start=367 - _SETTRACKINGOFFSTATUSREQUEST._serialized_end=396 - _SETTRACKINGOFFSTATUSRESPONSE._serialized_start=398 - _SETTRACKINGOFFSTATUSRESPONSE._serialized_end=428 - _SUBSCRIBETRACKINGPOINTCOMMANDREQUEST._serialized_start=430 - _SUBSCRIBETRACKINGPOINTCOMMANDREQUEST._serialized_end=468 - _TRACKINGPOINTCOMMANDRESPONSE._serialized_start=470 - _TRACKINGPOINTCOMMANDRESPONSE._serialized_end=561 - _SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST._serialized_start=563 - _SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST._serialized_end=605 - _TRACKINGRECTANGLECOMMANDRESPONSE._serialized_start=607 - _TRACKINGRECTANGLECOMMANDRESPONSE._serialized_end=710 - _SUBSCRIBETRACKINGOFFCOMMANDREQUEST._serialized_start=712 - _SUBSCRIBETRACKINGOFFCOMMANDREQUEST._serialized_end=748 - _TRACKINGOFFCOMMANDRESPONSE._serialized_start=750 - _TRACKINGOFFCOMMANDRESPONSE._serialized_end=793 - _RESPONDTRACKINGPOINTCOMMANDREQUEST._serialized_start=795 - _RESPONDTRACKINGPOINTCOMMANDREQUEST._serialized_end=898 - _RESPONDTRACKINGPOINTCOMMANDRESPONSE._serialized_start=900 - _RESPONDTRACKINGPOINTCOMMANDRESPONSE._serialized_end=1019 - _RESPONDTRACKINGRECTANGLECOMMANDREQUEST._serialized_start=1021 - _RESPONDTRACKINGRECTANGLECOMMANDREQUEST._serialized_end=1128 - _RESPONDTRACKINGRECTANGLECOMMANDRESPONSE._serialized_start=1130 - _RESPONDTRACKINGRECTANGLECOMMANDRESPONSE._serialized_end=1253 - _RESPONDTRACKINGOFFCOMMANDREQUEST._serialized_start=1255 - _RESPONDTRACKINGOFFCOMMANDREQUEST._serialized_end=1356 - _RESPONDTRACKINGOFFCOMMANDRESPONSE._serialized_start=1358 - _RESPONDTRACKINGOFFCOMMANDRESPONSE._serialized_end=1475 - _TRACKPOINT._serialized_start=1477 - _TRACKPOINT._serialized_end=1539 - _TRACKRECTANGLE._serialized_start=1542 - _TRACKRECTANGLE._serialized_end=1674 - _TRACKINGSERVERRESULT._serialized_start=1677 - _TRACKINGSERVERRESULT._serialized_end=1893 - _TRACKINGSERVERRESULT_RESULT._serialized_start=1794 - _TRACKINGSERVERRESULT_RESULT._serialized_end=1893 - _TRACKINGSERVERSERVICE._serialized_start=2070 - _TRACKINGSERVERSERVICE._serialized_end=3566 + DESCRIPTOR._options = None + DESCRIPTOR._serialized_options = ( + b"\n\031io.mavsdk.tracking_serverB\023TrackingServerProto" + ) + _TRACKINGSERVERSERVICE.methods_by_name["SetTrackingPointStatus"]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "SetTrackingPointStatus" + ]._serialized_options = b"\200\265\030\001" + _TRACKINGSERVERSERVICE.methods_by_name["SetTrackingRectangleStatus"]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "SetTrackingRectangleStatus" + ]._serialized_options = b"\200\265\030\001" + _TRACKINGSERVERSERVICE.methods_by_name["SetTrackingOffStatus"]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "SetTrackingOffStatus" + ]._serialized_options = b"\200\265\030\001" + _TRACKINGSERVERSERVICE.methods_by_name[ + "SubscribeTrackingPointCommand" + ]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "SubscribeTrackingPointCommand" + ]._serialized_options = b"\200\265\030\000" + _TRACKINGSERVERSERVICE.methods_by_name[ + "SubscribeTrackingRectangleCommand" + ]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "SubscribeTrackingRectangleCommand" + ]._serialized_options = b"\200\265\030\000" + _TRACKINGSERVERSERVICE.methods_by_name[ + "SubscribeTrackingOffCommand" + ]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "SubscribeTrackingOffCommand" + ]._serialized_options = b"\200\265\030\000" + _TRACKINGSERVERSERVICE.methods_by_name[ + "RespondTrackingPointCommand" + ]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "RespondTrackingPointCommand" + ]._serialized_options = b"\200\265\030\001" + _TRACKINGSERVERSERVICE.methods_by_name[ + "RespondTrackingRectangleCommand" + ]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "RespondTrackingRectangleCommand" + ]._serialized_options = b"\200\265\030\001" + _TRACKINGSERVERSERVICE.methods_by_name["RespondTrackingOffCommand"]._options = None + _TRACKINGSERVERSERVICE.methods_by_name[ + "RespondTrackingOffCommand" + ]._serialized_options = b"\200\265\030\001" + _COMMANDANSWER._serialized_start = 1896 + _COMMANDANSWER._serialized_end = 2067 + _SETTRACKINGPOINTSTATUSREQUEST._serialized_start = 91 + _SETTRACKINGPOINTSTATUSREQUEST._serialized_end = 185 + _SETTRACKINGPOINTSTATUSRESPONSE._serialized_start = 187 + _SETTRACKINGPOINTSTATUSRESPONSE._serialized_end = 219 + _SETTRACKINGRECTANGLESTATUSREQUEST._serialized_start = 221 + _SETTRACKINGRECTANGLESTATUSREQUEST._serialized_end = 327 + _SETTRACKINGRECTANGLESTATUSRESPONSE._serialized_start = 329 + _SETTRACKINGRECTANGLESTATUSRESPONSE._serialized_end = 365 + _SETTRACKINGOFFSTATUSREQUEST._serialized_start = 367 + _SETTRACKINGOFFSTATUSREQUEST._serialized_end = 396 + _SETTRACKINGOFFSTATUSRESPONSE._serialized_start = 398 + _SETTRACKINGOFFSTATUSRESPONSE._serialized_end = 428 + _SUBSCRIBETRACKINGPOINTCOMMANDREQUEST._serialized_start = 430 + _SUBSCRIBETRACKINGPOINTCOMMANDREQUEST._serialized_end = 468 + _TRACKINGPOINTCOMMANDRESPONSE._serialized_start = 470 + _TRACKINGPOINTCOMMANDRESPONSE._serialized_end = 561 + _SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST._serialized_start = 563 + _SUBSCRIBETRACKINGRECTANGLECOMMANDREQUEST._serialized_end = 605 + _TRACKINGRECTANGLECOMMANDRESPONSE._serialized_start = 607 + _TRACKINGRECTANGLECOMMANDRESPONSE._serialized_end = 710 + _SUBSCRIBETRACKINGOFFCOMMANDREQUEST._serialized_start = 712 + _SUBSCRIBETRACKINGOFFCOMMANDREQUEST._serialized_end = 748 + _TRACKINGOFFCOMMANDRESPONSE._serialized_start = 750 + _TRACKINGOFFCOMMANDRESPONSE._serialized_end = 793 + _RESPONDTRACKINGPOINTCOMMANDREQUEST._serialized_start = 795 + _RESPONDTRACKINGPOINTCOMMANDREQUEST._serialized_end = 898 + _RESPONDTRACKINGPOINTCOMMANDRESPONSE._serialized_start = 900 + _RESPONDTRACKINGPOINTCOMMANDRESPONSE._serialized_end = 1019 + _RESPONDTRACKINGRECTANGLECOMMANDREQUEST._serialized_start = 1021 + _RESPONDTRACKINGRECTANGLECOMMANDREQUEST._serialized_end = 1128 + _RESPONDTRACKINGRECTANGLECOMMANDRESPONSE._serialized_start = 1130 + _RESPONDTRACKINGRECTANGLECOMMANDRESPONSE._serialized_end = 1253 + _RESPONDTRACKINGOFFCOMMANDREQUEST._serialized_start = 1255 + _RESPONDTRACKINGOFFCOMMANDREQUEST._serialized_end = 1356 + _RESPONDTRACKINGOFFCOMMANDRESPONSE._serialized_start = 1358 + _RESPONDTRACKINGOFFCOMMANDRESPONSE._serialized_end = 1475 + _TRACKPOINT._serialized_start = 1477 + _TRACKPOINT._serialized_end = 1539 + _TRACKRECTANGLE._serialized_start = 1542 + _TRACKRECTANGLE._serialized_end = 1674 + _TRACKINGSERVERRESULT._serialized_start = 1677 + _TRACKINGSERVERRESULT._serialized_end = 1893 + _TRACKINGSERVERRESULT_RESULT._serialized_start = 1794 + _TRACKINGSERVERRESULT_RESULT._serialized_end = 1893 + _TRACKINGSERVERSERVICE._serialized_start = 2070 + _TRACKINGSERVERSERVICE._serialized_end = 3566 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/tracking_server_pb2_grpc.py b/mavsdk/tracking_server_pb2_grpc.py index c48add9e..e1764303 100644 --- a/mavsdk/tracking_server_pb2_grpc.py +++ b/mavsdk/tracking_server_pb2_grpc.py @@ -1,13 +1,13 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc from . import tracking_server_pb2 as tracking__server_dot_tracking__server__pb2 class TrackingServerServiceStub(object): - """API for an onboard image tracking software. - """ + """API for an onboard image tracking software.""" def __init__(self, channel): """Constructor. @@ -16,327 +16,425 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SetTrackingPointStatus = channel.unary_unary( - '/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingPointStatus', - request_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingPointStatus", + request_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusResponse.FromString, + ) self.SetTrackingRectangleStatus = channel.unary_unary( - '/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingRectangleStatus', - request_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingRectangleStatus", + request_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusResponse.FromString, + ) self.SetTrackingOffStatus = channel.unary_unary( - '/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingOffStatus', - request_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingOffStatus", + request_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusResponse.FromString, + ) self.SubscribeTrackingPointCommand = channel.unary_stream( - '/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingPointCommand', - request_serializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingPointCommandRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.TrackingPointCommandResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingPointCommand", + request_serializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingPointCommandRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.TrackingPointCommandResponse.FromString, + ) self.SubscribeTrackingRectangleCommand = channel.unary_stream( - '/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingRectangleCommand', - request_serializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingRectangleCommandRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.TrackingRectangleCommandResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingRectangleCommand", + request_serializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingRectangleCommandRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.TrackingRectangleCommandResponse.FromString, + ) self.SubscribeTrackingOffCommand = channel.unary_stream( - '/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingOffCommand', - request_serializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingOffCommandRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.TrackingOffCommandResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingOffCommand", + request_serializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingOffCommandRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.TrackingOffCommandResponse.FromString, + ) self.RespondTrackingPointCommand = channel.unary_unary( - '/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingPointCommand', - request_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingPointCommand", + request_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandResponse.FromString, + ) self.RespondTrackingRectangleCommand = channel.unary_unary( - '/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingRectangleCommand', - request_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingRectangleCommand", + request_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandResponse.FromString, + ) self.RespondTrackingOffCommand = channel.unary_unary( - '/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingOffCommand', - request_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandRequest.SerializeToString, - response_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandResponse.FromString, - ) + "/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingOffCommand", + request_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandRequest.SerializeToString, + response_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandResponse.FromString, + ) class TrackingServerServiceServicer(object): - """API for an onboard image tracking software. - """ + """API for an onboard image tracking software.""" def SetTrackingPointStatus(self, request, context): - """Set/update the current point tracking status. - """ + """Set/update the current point tracking status.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTrackingRectangleStatus(self, request, context): - """Set/update the current rectangle tracking status. - """ + """Set/update the current rectangle tracking status.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetTrackingOffStatus(self, request, context): - """Set the current tracking status to off. - """ + """Set the current tracking status to off.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTrackingPointCommand(self, request, context): - """Subscribe to incoming tracking point command. - """ + """Subscribe to incoming tracking point command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTrackingRectangleCommand(self, request, context): - """Subscribe to incoming tracking rectangle command. - """ + """Subscribe to incoming tracking rectangle command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SubscribeTrackingOffCommand(self, request, context): - """Subscribe to incoming tracking off command. - """ + """Subscribe to incoming tracking off command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTrackingPointCommand(self, request, context): - """Respond to an incoming tracking point command. - """ + """Respond to an incoming tracking point command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTrackingRectangleCommand(self, request, context): - """Respond to an incoming tracking rectangle command. - """ + """Respond to an incoming tracking rectangle command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RespondTrackingOffCommand(self, request, context): - """Respond to an incoming tracking off command. - """ + """Respond to an incoming tracking off command.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_TrackingServerServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SetTrackingPointStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetTrackingPointStatus, - request_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusResponse.SerializeToString, - ), - 'SetTrackingRectangleStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetTrackingRectangleStatus, - request_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusResponse.SerializeToString, - ), - 'SetTrackingOffStatus': grpc.unary_unary_rpc_method_handler( - servicer.SetTrackingOffStatus, - request_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusResponse.SerializeToString, - ), - 'SubscribeTrackingPointCommand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTrackingPointCommand, - request_deserializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingPointCommandRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.TrackingPointCommandResponse.SerializeToString, - ), - 'SubscribeTrackingRectangleCommand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTrackingRectangleCommand, - request_deserializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingRectangleCommandRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.TrackingRectangleCommandResponse.SerializeToString, - ), - 'SubscribeTrackingOffCommand': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTrackingOffCommand, - request_deserializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingOffCommandRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.TrackingOffCommandResponse.SerializeToString, - ), - 'RespondTrackingPointCommand': grpc.unary_unary_rpc_method_handler( - servicer.RespondTrackingPointCommand, - request_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandResponse.SerializeToString, - ), - 'RespondTrackingRectangleCommand': grpc.unary_unary_rpc_method_handler( - servicer.RespondTrackingRectangleCommand, - request_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandResponse.SerializeToString, - ), - 'RespondTrackingOffCommand': grpc.unary_unary_rpc_method_handler( - servicer.RespondTrackingOffCommand, - request_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandRequest.FromString, - response_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandResponse.SerializeToString, - ), + "SetTrackingPointStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetTrackingPointStatus, + request_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusResponse.SerializeToString, + ), + "SetTrackingRectangleStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetTrackingRectangleStatus, + request_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusResponse.SerializeToString, + ), + "SetTrackingOffStatus": grpc.unary_unary_rpc_method_handler( + servicer.SetTrackingOffStatus, + request_deserializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusResponse.SerializeToString, + ), + "SubscribeTrackingPointCommand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTrackingPointCommand, + request_deserializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingPointCommandRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.TrackingPointCommandResponse.SerializeToString, + ), + "SubscribeTrackingRectangleCommand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTrackingRectangleCommand, + request_deserializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingRectangleCommandRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.TrackingRectangleCommandResponse.SerializeToString, + ), + "SubscribeTrackingOffCommand": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTrackingOffCommand, + request_deserializer=tracking__server_dot_tracking__server__pb2.SubscribeTrackingOffCommandRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.TrackingOffCommandResponse.SerializeToString, + ), + "RespondTrackingPointCommand": grpc.unary_unary_rpc_method_handler( + servicer.RespondTrackingPointCommand, + request_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandResponse.SerializeToString, + ), + "RespondTrackingRectangleCommand": grpc.unary_unary_rpc_method_handler( + servicer.RespondTrackingRectangleCommand, + request_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandResponse.SerializeToString, + ), + "RespondTrackingOffCommand": grpc.unary_unary_rpc_method_handler( + servicer.RespondTrackingOffCommand, + request_deserializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandRequest.FromString, + response_serializer=tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.tracking_server.TrackingServerService', rpc_method_handlers) + "mavsdk.rpc.tracking_server.TrackingServerService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class TrackingServerService(object): - """API for an onboard image tracking software. - """ + """API for an onboard image tracking software.""" @staticmethod - def SetTrackingPointStatus(request, + def SetTrackingPointStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingPointStatus', + "/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingPointStatus", tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.SetTrackingPointStatusResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SetTrackingRectangleStatus(request, + def SetTrackingRectangleStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingRectangleStatus', + "/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingRectangleStatus", tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.SetTrackingRectangleStatusResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SetTrackingOffStatus(request, + def SetTrackingOffStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingOffStatus', + "/mavsdk.rpc.tracking_server.TrackingServerService/SetTrackingOffStatus", tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.SetTrackingOffStatusResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SubscribeTrackingPointCommand(request, + def SubscribeTrackingPointCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_stream( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingPointCommand', + "/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingPointCommand", tracking__server_dot_tracking__server__pb2.SubscribeTrackingPointCommandRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.TrackingPointCommandResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SubscribeTrackingRectangleCommand(request, + def SubscribeTrackingRectangleCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_stream( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingRectangleCommand', + "/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingRectangleCommand", tracking__server_dot_tracking__server__pb2.SubscribeTrackingRectangleCommandRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.TrackingRectangleCommandResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def SubscribeTrackingOffCommand(request, + def SubscribeTrackingOffCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_stream( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingOffCommand', + "/mavsdk.rpc.tracking_server.TrackingServerService/SubscribeTrackingOffCommand", tracking__server_dot_tracking__server__pb2.SubscribeTrackingOffCommandRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.TrackingOffCommandResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def RespondTrackingPointCommand(request, + def RespondTrackingPointCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingPointCommand', + "/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingPointCommand", tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.RespondTrackingPointCommandResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def RespondTrackingRectangleCommand(request, + def RespondTrackingRectangleCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingRectangleCommand', + "/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingRectangleCommand", tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.RespondTrackingRectangleCommandResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) @staticmethod - def RespondTrackingOffCommand(request, + def RespondTrackingOffCommand( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): + return grpc.experimental.unary_unary( + request, target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingOffCommand', + "/mavsdk.rpc.tracking_server.TrackingServerService/RespondTrackingOffCommand", tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandRequest.SerializeToString, tracking__server_dot_tracking__server__pb2.RespondTrackingOffCommandResponse.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + options, + channel_credentials, + insecure, + call_credentials, + compression, + wait_for_ready, + timeout, + metadata, + ) diff --git a/mavsdk/transponder.py b/mavsdk/transponder.py index eb4dc01e..219ab398 100644 --- a/mavsdk/transponder.py +++ b/mavsdk/transponder.py @@ -8,73 +8,72 @@ class AdsbEmitterType(Enum): """ - ADSB classification for the type of vehicle emitting the transponder signal. + ADSB classification for the type of vehicle emitting the transponder signal. - Values - ------ - NO_INFO - No emitter info. + Values + ------ + NO_INFO + No emitter info. - LIGHT - Light emitter. + LIGHT + Light emitter. - SMALL - Small emitter. + SMALL + Small emitter. - LARGE - Large emitter. + LARGE + Large emitter. - HIGH_VORTEX_LARGE - High vortex emitter. + HIGH_VORTEX_LARGE + High vortex emitter. - HEAVY - Heavy emitter. + HEAVY + Heavy emitter. - HIGHLY_MANUV - Highly maneuverable emitter. + HIGHLY_MANUV + Highly maneuverable emitter. - ROTOCRAFT - Rotorcraft emitter. + ROTOCRAFT + Rotorcraft emitter. - UNASSIGNED - Unassigned emitter. + UNASSIGNED + Unassigned emitter. - GLIDER - Glider emitter. + GLIDER + Glider emitter. - LIGHTER_AIR - Lighter air emitter. + LIGHTER_AIR + Lighter air emitter. - PARACHUTE - Parachute emitter. + PARACHUTE + Parachute emitter. - ULTRA_LIGHT - Ultra light emitter. + ULTRA_LIGHT + Ultra light emitter. - UNASSIGNED2 - Unassigned2 emitter. + UNASSIGNED2 + Unassigned2 emitter. - UAV - UAV emitter. + UAV + UAV emitter. - SPACE - Space emitter. + SPACE + Space emitter. - UNASSGINED3 - Unassigned3 emitter. + UNASSGINED3 + Unassigned3 emitter. - EMERGENCY_SURFACE - Emergency emitter. + EMERGENCY_SURFACE + Emergency emitter. - SERVICE_SURFACE - Service surface emitter. + SERVICE_SURFACE + Service surface emitter. - POINT_OBSTACLE - Point obstacle emitter. + POINT_OBSTACLE + Point obstacle emitter. - """ + """ - NO_INFO = 0 LIGHT = 1 SMALL = 2 @@ -140,7 +139,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == transponder_pb2.ADSB_EMITTER_TYPE_NO_INFO: return AdsbEmitterType.NO_INFO if rpc_enum_value == transponder_pb2.ADSB_EMITTER_TYPE_LIGHT: @@ -188,19 +187,18 @@ def __str__(self): class AdsbAltitudeType(Enum): """ - Altitude type used in AdsbVehicle message + Altitude type used in AdsbVehicle message - Values - ------ - PRESSURE_QNH - Altitude reported from a Baro source using QNH reference + Values + ------ + PRESSURE_QNH + Altitude reported from a Baro source using QNH reference - GEOMETRIC - Altitude reported from a GNSS source + GEOMETRIC + Altitude reported from a GNSS source - """ + """ - PRESSURE_QNH = 0 GEOMETRIC = 1 @@ -212,7 +210,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == transponder_pb2.ADSB_ALTITUDE_TYPE_PRESSURE_QNH: return AdsbAltitudeType.PRESSURE_QNH if rpc_enum_value == transponder_pb2.ADSB_ALTITUDE_TYPE_GEOMETRIC: @@ -224,65 +222,64 @@ def __str__(self): class AdsbVehicle: """ - ADSB Vehicle type. - - Parameters - ---------- - icao_address : uint32_t - ICAO (International Civil Aviation Organization) unique worldwide identifier + ADSB Vehicle type. - latitude_deg : double - Latitude in degrees (range: -90 to +90) + Parameters + ---------- + icao_address : uint32_t + ICAO (International Civil Aviation Organization) unique worldwide identifier - longitude_deg : double - Longitude in degrees (range: -180 to +180). + latitude_deg : double + Latitude in degrees (range: -90 to +90) - altitude_type : AdsbAltitudeType - ADSB altitude type. + longitude_deg : double + Longitude in degrees (range: -180 to +180). - absolute_altitude_m : float - Altitude in metres according to altitude_type + altitude_type : AdsbAltitudeType + ADSB altitude type. - heading_deg : float - Course over ground, in degrees + absolute_altitude_m : float + Altitude in metres according to altitude_type - horizontal_velocity_m_s : float - The horizontal velocity in metres/second + heading_deg : float + Course over ground, in degrees - vertical_velocity_m_s : float - The vertical velocity in metres/second. Positive is up. + horizontal_velocity_m_s : float + The horizontal velocity in metres/second - callsign : std::string - The callsign + vertical_velocity_m_s : float + The vertical velocity in metres/second. Positive is up. - emitter_type : AdsbEmitterType - ADSB emitter type. + callsign : std::string + The callsign - squawk : uint32_t - Squawk code. + emitter_type : AdsbEmitterType + ADSB emitter type. - tslc_s : uint32_t - Time Since Last Communication in seconds. + squawk : uint32_t + Squawk code. - """ + tslc_s : uint32_t + Time Since Last Communication in seconds. - + """ def __init__( - self, - icao_address, - latitude_deg, - longitude_deg, - altitude_type, - absolute_altitude_m, - heading_deg, - horizontal_velocity_m_s, - vertical_velocity_m_s, - callsign, - emitter_type, - squawk, - tslc_s): - """ Initializes the AdsbVehicle object """ + self, + icao_address, + latitude_deg, + longitude_deg, + altitude_type, + absolute_altitude_m, + heading_deg, + horizontal_velocity_m_s, + vertical_velocity_m_s, + callsign, + emitter_type, + squawk, + tslc_s, + ): + """Initializes the AdsbVehicle object""" self.icao_address = icao_address self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg @@ -297,30 +294,32 @@ def __init__( self.tslc_s = tslc_s def __eq__(self, to_compare): - """ Checks if two AdsbVehicle are the same """ + """Checks if two AdsbVehicle are the same""" try: # Try to compare - this likely fails when it is compared to a non # AdsbVehicle object - return \ - (self.icao_address == to_compare.icao_address) and \ - (self.latitude_deg == to_compare.latitude_deg) and \ - (self.longitude_deg == to_compare.longitude_deg) and \ - (self.altitude_type == to_compare.altitude_type) and \ - (self.absolute_altitude_m == to_compare.absolute_altitude_m) and \ - (self.heading_deg == to_compare.heading_deg) and \ - (self.horizontal_velocity_m_s == to_compare.horizontal_velocity_m_s) and \ - (self.vertical_velocity_m_s == to_compare.vertical_velocity_m_s) and \ - (self.callsign == to_compare.callsign) and \ - (self.emitter_type == to_compare.emitter_type) and \ - (self.squawk == to_compare.squawk) and \ - (self.tslc_s == to_compare.tslc_s) + return ( + (self.icao_address == to_compare.icao_address) + and (self.latitude_deg == to_compare.latitude_deg) + and (self.longitude_deg == to_compare.longitude_deg) + and (self.altitude_type == to_compare.altitude_type) + and (self.absolute_altitude_m == to_compare.absolute_altitude_m) + and (self.heading_deg == to_compare.heading_deg) + and (self.horizontal_velocity_m_s == to_compare.horizontal_velocity_m_s) + and (self.vertical_velocity_m_s == to_compare.vertical_velocity_m_s) + and (self.callsign == to_compare.callsign) + and (self.emitter_type == to_compare.emitter_type) + and (self.squawk == to_compare.squawk) + and (self.tslc_s == to_compare.tslc_s) + ) except AttributeError: return False def __str__(self): - """ AdsbVehicle in string representation """ - struct_repr = ", ".join([ + """AdsbVehicle in string representation""" + struct_repr = ", ".join( + [ "icao_address: " + str(self.icao_address), "latitude_deg: " + str(self.latitude_deg), "longitude_deg: " + str(self.longitude_deg), @@ -332,176 +331,101 @@ def __str__(self): "callsign: " + str(self.callsign), "emitter_type: " + str(self.emitter_type), "squawk: " + str(self.squawk), - "tslc_s: " + str(self.tslc_s) - ]) + "tslc_s: " + str(self.tslc_s), + ] + ) return f"AdsbVehicle: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcAdsbVehicle): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return AdsbVehicle( - - rpcAdsbVehicle.icao_address, - - - rpcAdsbVehicle.latitude_deg, - - - rpcAdsbVehicle.longitude_deg, - - - AdsbAltitudeType.translate_from_rpc(rpcAdsbVehicle.altitude_type), - - - rpcAdsbVehicle.absolute_altitude_m, - - - rpcAdsbVehicle.heading_deg, - - - rpcAdsbVehicle.horizontal_velocity_m_s, - - - rpcAdsbVehicle.vertical_velocity_m_s, - - - rpcAdsbVehicle.callsign, - - - AdsbEmitterType.translate_from_rpc(rpcAdsbVehicle.emitter_type), - - - rpcAdsbVehicle.squawk, - - - rpcAdsbVehicle.tslc_s - ) + rpcAdsbVehicle.icao_address, + rpcAdsbVehicle.latitude_deg, + rpcAdsbVehicle.longitude_deg, + AdsbAltitudeType.translate_from_rpc(rpcAdsbVehicle.altitude_type), + rpcAdsbVehicle.absolute_altitude_m, + rpcAdsbVehicle.heading_deg, + rpcAdsbVehicle.horizontal_velocity_m_s, + rpcAdsbVehicle.vertical_velocity_m_s, + rpcAdsbVehicle.callsign, + AdsbEmitterType.translate_from_rpc(rpcAdsbVehicle.emitter_type), + rpcAdsbVehicle.squawk, + rpcAdsbVehicle.tslc_s, + ) def translate_to_rpc(self, rpcAdsbVehicle): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcAdsbVehicle.icao_address = self.icao_address - - - - - + rpcAdsbVehicle.latitude_deg = self.latitude_deg - - - - - + rpcAdsbVehicle.longitude_deg = self.longitude_deg - - - - - + rpcAdsbVehicle.altitude_type = self.altitude_type.translate_to_rpc() - - - - - + rpcAdsbVehicle.absolute_altitude_m = self.absolute_altitude_m - - - - - + rpcAdsbVehicle.heading_deg = self.heading_deg - - - - - + rpcAdsbVehicle.horizontal_velocity_m_s = self.horizontal_velocity_m_s - - - - - + rpcAdsbVehicle.vertical_velocity_m_s = self.vertical_velocity_m_s - - - - - + rpcAdsbVehicle.callsign = self.callsign - - - - - + rpcAdsbVehicle.emitter_type = self.emitter_type.translate_to_rpc() - - - - - + rpcAdsbVehicle.squawk = self.squawk - - - - - + rpcAdsbVehicle.tslc_s = self.tslc_s - - - class TransponderResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for transponder requests. + Possible results returned for transponder requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Success: the transponder command was accepted by the vehicle + SUCCESS + Success: the transponder command was accepted by the vehicle - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - CONNECTION_ERROR - Connection error + CONNECTION_ERROR + Connection error - BUSY - Vehicle is busy + BUSY + Vehicle is busy - COMMAND_DENIED - Command refused by vehicle + COMMAND_DENIED + Command refused by vehicle - TIMEOUT - Request timed out + TIMEOUT + Request timed out - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -528,87 +452,74 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_UNKNOWN: return TransponderResult.Result.UNKNOWN if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_SUCCESS: return TransponderResult.Result.SUCCESS if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_NO_SYSTEM: return TransponderResult.Result.NO_SYSTEM - if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_CONNECTION_ERROR: + if ( + rpc_enum_value + == transponder_pb2.TransponderResult.RESULT_CONNECTION_ERROR + ): return TransponderResult.Result.CONNECTION_ERROR if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_BUSY: return TransponderResult.Result.BUSY - if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_COMMAND_DENIED: + if ( + rpc_enum_value + == transponder_pb2.TransponderResult.RESULT_COMMAND_DENIED + ): return TransponderResult.Result.COMMAND_DENIED if rpc_enum_value == transponder_pb2.TransponderResult.RESULT_TIMEOUT: return TransponderResult.Result.TIMEOUT def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the TransponderResult object """ + def __init__(self, result, result_str): + """Initializes the TransponderResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two TransponderResult are the same """ + """Checks if two TransponderResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # TransponderResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ TransponderResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """TransponderResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"TransponderResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTransponderResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TransponderResult( - - TransponderResult.Result.translate_from_rpc(rpcTransponderResult.result), - - - rpcTransponderResult.result_str - ) + TransponderResult.Result.translate_from_rpc(rpcTransponderResult.result), + rpcTransponderResult.result_str, + ) def translate_to_rpc(self, rpcTransponderResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTransponderResult.result = self.result.translate_to_rpc() - - - - - - rpcTransponderResult.result_str = self.result_str - - - + rpcTransponderResult.result_str = self.result_str class TransponderError(Exception): - """ Raised when a TransponderResult is a fail code """ + """Raised when a TransponderResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -621,35 +532,33 @@ def __str__(self): class Transponder(AsyncBase): """ - Allow users to get ADS-B information - and set ADS-B update rates. + Allow users to get ADS-B information + and set ADS-B update rates. - Generated by dcsdkgen - MAVSDK Transponder API + Generated by dcsdkgen - MAVSDK Transponder API """ # Plugin name name = "Transponder" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = transponder_pb2_grpc.TransponderServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return TransponderResult.translate_from_rpc(response.transponder_result) - async def transponder(self): """ - Subscribe to 'transponder' updates. + Subscribe to 'transponder' updates. + + Yields + ------- + transponder : AdsbVehicle + The next detection - Yields - ------- - transponder : AdsbVehicle - The next detection - """ request = transponder_pb2.SubscribeTransponderRequest() @@ -657,35 +566,30 @@ async def transponder(self): try: async for response in transponder_stream: - - - yield AdsbVehicle.translate_from_rpc(response.transponder) finally: transponder_stream.cancel() async def set_rate_transponder(self, rate_hz): """ - Set rate to 'transponder' updates. + Set rate to 'transponder' updates. - Parameters - ---------- - rate_hz : double - The requested rate (in Hertz) + Parameters + ---------- + rate_hz : double + The requested rate (in Hertz) - Raises - ------ - TransponderError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TransponderError + If the request fails. The error contains the reason for the failure. """ request = transponder_pb2.SetRateTransponderRequest() request.rate_hz = rate_hz response = await self._stub.SetRateTransponder(request) - result = self._extract_result(response) if result.result != TransponderResult.Result.SUCCESS: raise TransponderError(result, "set_rate_transponder()", rate_hz) - \ No newline at end of file diff --git a/mavsdk/transponder_pb2.py b/mavsdk/transponder_pb2.py index bf33d829..f26ec47d 100644 --- a/mavsdk/transponder_pb2.py +++ b/mavsdk/transponder_pb2.py @@ -4,52 +4,53 @@ # source: transponder/transponder.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'transponder/transponder.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "transponder/transponder.proto" ) # @@protoc_insertion_point(imports) _sym_db = _symbol_database.Default() - - -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x1dtransponder/transponder.proto\x12\x16mavsdk.rpc.transponder\"\x1d\n\x1bSubscribeTransponderRequest\"O\n\x13TransponderResponse\x12\x38\n\x0btransponder\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.transponder.AdsbVehicle\",\n\x19SetRateTransponderRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"c\n\x1aSetRateTransponderResponse\x12\x45\n\x12transponder_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.transponder.TransponderResult\"\xf4\x02\n\x0b\x41\x64sbVehicle\x12\x14\n\x0cicao_address\x18\x01 \x01(\r\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12?\n\raltitude_type\x18\x04 \x01(\x0e\x32(.mavsdk.rpc.transponder.AdsbAltitudeType\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x05 \x01(\x02\x12\x13\n\x0bheading_deg\x18\x06 \x01(\x02\x12\x1f\n\x17horizontal_velocity_m_s\x18\x07 \x01(\x02\x12\x1d\n\x15vertical_velocity_m_s\x18\x08 \x01(\x02\x12\x10\n\x08\x63\x61llsign\x18\t \x01(\t\x12=\n\x0c\x65mitter_type\x18\n \x01(\x0e\x32\'.mavsdk.rpc.transponder.AdsbEmitterType\x12\x0e\n\x06squawk\x18\r \x01(\r\x12\x0e\n\x06tslc_s\x18\x0e \x01(\r\"\x8f\x02\n\x11TransponderResult\x12@\n\x06result\x18\x01 \x01(\x0e\x32\x30.mavsdk.rpc.transponder.TransponderResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xa3\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*\xad\x05\n\x0f\x41\x64sbEmitterType\x12\x1d\n\x19\x41\x44SB_EMITTER_TYPE_NO_INFO\x10\x00\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_LIGHT\x10\x01\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_SMALL\x10\x02\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_LARGE\x10\x03\x12\'\n#ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE\x10\x04\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_HEAVY\x10\x05\x12\"\n\x1e\x41\x44SB_EMITTER_TYPE_HIGHLY_MANUV\x10\x06\x12\x1f\n\x1b\x41\x44SB_EMITTER_TYPE_ROTOCRAFT\x10\x07\x12 \n\x1c\x41\x44SB_EMITTER_TYPE_UNASSIGNED\x10\x08\x12\x1c\n\x18\x41\x44SB_EMITTER_TYPE_GLIDER\x10\t\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_LIGHTER_AIR\x10\n\x12\x1f\n\x1b\x41\x44SB_EMITTER_TYPE_PARACHUTE\x10\x0b\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_ULTRA_LIGHT\x10\x0c\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_UNASSIGNED2\x10\r\x12\x19\n\x15\x41\x44SB_EMITTER_TYPE_UAV\x10\x0e\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_SPACE\x10\x0f\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_UNASSGINED3\x10\x10\x12\'\n#ADSB_EMITTER_TYPE_EMERGENCY_SURFACE\x10\x11\x12%\n!ADSB_EMITTER_TYPE_SERVICE_SURFACE\x10\x12\x12$\n ADSB_EMITTER_TYPE_POINT_OBSTACLE\x10\x13*Y\n\x10\x41\x64sbAltitudeType\x12#\n\x1f\x41\x44SB_ALTITUDE_TYPE_PRESSURE_QNH\x10\x00\x12 \n\x1c\x41\x44SB_ALTITUDE_TYPE_GEOMETRIC\x10\x01\x32\x91\x02\n\x12TransponderService\x12|\n\x14SubscribeTransponder\x12\x33.mavsdk.rpc.transponder.SubscribeTransponderRequest\x1a+.mavsdk.rpc.transponder.TransponderResponse\"\x00\x30\x01\x12}\n\x12SetRateTransponder\x12\x31.mavsdk.rpc.transponder.SetRateTransponderRequest\x1a\x32.mavsdk.rpc.transponder.SetRateTransponderResponse\"\x00\x42)\n\x15io.mavsdk.transponderB\x10TransponderProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x1dtransponder/transponder.proto\x12\x16mavsdk.rpc.transponder"\x1d\n\x1bSubscribeTransponderRequest"O\n\x13TransponderResponse\x12\x38\n\x0btransponder\x18\x01 \x01(\x0b\x32#.mavsdk.rpc.transponder.AdsbVehicle",\n\x19SetRateTransponderRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01"c\n\x1aSetRateTransponderResponse\x12\x45\n\x12transponder_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.transponder.TransponderResult"\xf4\x02\n\x0b\x41\x64sbVehicle\x12\x14\n\x0cicao_address\x18\x01 \x01(\r\x12\x14\n\x0clatitude_deg\x18\x02 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x03 \x01(\x01\x12?\n\raltitude_type\x18\x04 \x01(\x0e\x32(.mavsdk.rpc.transponder.AdsbAltitudeType\x12\x1b\n\x13\x61\x62solute_altitude_m\x18\x05 \x01(\x02\x12\x13\n\x0bheading_deg\x18\x06 \x01(\x02\x12\x1f\n\x17horizontal_velocity_m_s\x18\x07 \x01(\x02\x12\x1d\n\x15vertical_velocity_m_s\x18\x08 \x01(\x02\x12\x10\n\x08\x63\x61llsign\x18\t \x01(\t\x12=\n\x0c\x65mitter_type\x18\n \x01(\x0e\x32\'.mavsdk.rpc.transponder.AdsbEmitterType\x12\x0e\n\x06squawk\x18\r \x01(\r\x12\x0e\n\x06tslc_s\x18\x0e \x01(\r"\x8f\x02\n\x11TransponderResult\x12@\n\x06result\x18\x01 \x01(\x0e\x32\x30.mavsdk.rpc.transponder.TransponderResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t"\xa3\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*\xad\x05\n\x0f\x41\x64sbEmitterType\x12\x1d\n\x19\x41\x44SB_EMITTER_TYPE_NO_INFO\x10\x00\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_LIGHT\x10\x01\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_SMALL\x10\x02\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_LARGE\x10\x03\x12\'\n#ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE\x10\x04\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_HEAVY\x10\x05\x12"\n\x1e\x41\x44SB_EMITTER_TYPE_HIGHLY_MANUV\x10\x06\x12\x1f\n\x1b\x41\x44SB_EMITTER_TYPE_ROTOCRAFT\x10\x07\x12 \n\x1c\x41\x44SB_EMITTER_TYPE_UNASSIGNED\x10\x08\x12\x1c\n\x18\x41\x44SB_EMITTER_TYPE_GLIDER\x10\t\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_LIGHTER_AIR\x10\n\x12\x1f\n\x1b\x41\x44SB_EMITTER_TYPE_PARACHUTE\x10\x0b\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_ULTRA_LIGHT\x10\x0c\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_UNASSIGNED2\x10\r\x12\x19\n\x15\x41\x44SB_EMITTER_TYPE_UAV\x10\x0e\x12\x1b\n\x17\x41\x44SB_EMITTER_TYPE_SPACE\x10\x0f\x12!\n\x1d\x41\x44SB_EMITTER_TYPE_UNASSGINED3\x10\x10\x12\'\n#ADSB_EMITTER_TYPE_EMERGENCY_SURFACE\x10\x11\x12%\n!ADSB_EMITTER_TYPE_SERVICE_SURFACE\x10\x12\x12$\n ADSB_EMITTER_TYPE_POINT_OBSTACLE\x10\x13*Y\n\x10\x41\x64sbAltitudeType\x12#\n\x1f\x41\x44SB_ALTITUDE_TYPE_PRESSURE_QNH\x10\x00\x12 \n\x1c\x41\x44SB_ALTITUDE_TYPE_GEOMETRIC\x10\x01\x32\x91\x02\n\x12TransponderService\x12|\n\x14SubscribeTransponder\x12\x33.mavsdk.rpc.transponder.SubscribeTransponderRequest\x1a+.mavsdk.rpc.transponder.TransponderResponse"\x00\x30\x01\x12}\n\x12SetRateTransponder\x12\x31.mavsdk.rpc.transponder.SetRateTransponderRequest\x1a\x32.mavsdk.rpc.transponder.SetRateTransponderResponse"\x00\x42)\n\x15io.mavsdk.transponderB\x10TransponderProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'transponder.transponder_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages( + DESCRIPTOR, "transponder.transponder_pb2", _globals +) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\025io.mavsdk.transponderB\020TransponderProto' - _globals['_ADSBEMITTERTYPE']._serialized_start=966 - _globals['_ADSBEMITTERTYPE']._serialized_end=1651 - _globals['_ADSBALTITUDETYPE']._serialized_start=1653 - _globals['_ADSBALTITUDETYPE']._serialized_end=1742 - _globals['_SUBSCRIBETRANSPONDERREQUEST']._serialized_start=57 - _globals['_SUBSCRIBETRANSPONDERREQUEST']._serialized_end=86 - _globals['_TRANSPONDERRESPONSE']._serialized_start=88 - _globals['_TRANSPONDERRESPONSE']._serialized_end=167 - _globals['_SETRATETRANSPONDERREQUEST']._serialized_start=169 - _globals['_SETRATETRANSPONDERREQUEST']._serialized_end=213 - _globals['_SETRATETRANSPONDERRESPONSE']._serialized_start=215 - _globals['_SETRATETRANSPONDERRESPONSE']._serialized_end=314 - _globals['_ADSBVEHICLE']._serialized_start=317 - _globals['_ADSBVEHICLE']._serialized_end=689 - _globals['_TRANSPONDERRESULT']._serialized_start=692 - _globals['_TRANSPONDERRESULT']._serialized_end=963 - _globals['_TRANSPONDERRESULT_RESULT']._serialized_start=800 - _globals['_TRANSPONDERRESULT_RESULT']._serialized_end=963 - _globals['_TRANSPONDERSERVICE']._serialized_start=1745 - _globals['_TRANSPONDERSERVICE']._serialized_end=2018 + _globals["DESCRIPTOR"]._loaded_options = None + _globals[ + "DESCRIPTOR" + ]._serialized_options = b"\n\025io.mavsdk.transponderB\020TransponderProto" + _globals["_ADSBEMITTERTYPE"]._serialized_start = 966 + _globals["_ADSBEMITTERTYPE"]._serialized_end = 1651 + _globals["_ADSBALTITUDETYPE"]._serialized_start = 1653 + _globals["_ADSBALTITUDETYPE"]._serialized_end = 1742 + _globals["_SUBSCRIBETRANSPONDERREQUEST"]._serialized_start = 57 + _globals["_SUBSCRIBETRANSPONDERREQUEST"]._serialized_end = 86 + _globals["_TRANSPONDERRESPONSE"]._serialized_start = 88 + _globals["_TRANSPONDERRESPONSE"]._serialized_end = 167 + _globals["_SETRATETRANSPONDERREQUEST"]._serialized_start = 169 + _globals["_SETRATETRANSPONDERREQUEST"]._serialized_end = 213 + _globals["_SETRATETRANSPONDERRESPONSE"]._serialized_start = 215 + _globals["_SETRATETRANSPONDERRESPONSE"]._serialized_end = 314 + _globals["_ADSBVEHICLE"]._serialized_start = 317 + _globals["_ADSBVEHICLE"]._serialized_end = 689 + _globals["_TRANSPONDERRESULT"]._serialized_start = 692 + _globals["_TRANSPONDERRESULT"]._serialized_end = 963 + _globals["_TRANSPONDERRESULT_RESULT"]._serialized_start = 800 + _globals["_TRANSPONDERRESULT_RESULT"]._serialized_end = 963 + _globals["_TRANSPONDERSERVICE"]._serialized_start = 1745 + _globals["_TRANSPONDERSERVICE"]._serialized_end = 2018 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/transponder_pb2_grpc.py b/mavsdk/transponder_pb2_grpc.py index e39ccbd2..b2a1f4f6 100644 --- a/mavsdk/transponder_pb2_grpc.py +++ b/mavsdk/transponder_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import transponder_pb2 as transponder_dot_transponder__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in transponder/transponder_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in transponder/transponder_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -38,15 +42,17 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeTransponder = channel.unary_stream( - '/mavsdk.rpc.transponder.TransponderService/SubscribeTransponder', - request_serializer=transponder_dot_transponder__pb2.SubscribeTransponderRequest.SerializeToString, - response_deserializer=transponder_dot_transponder__pb2.TransponderResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.transponder.TransponderService/SubscribeTransponder", + request_serializer=transponder_dot_transponder__pb2.SubscribeTransponderRequest.SerializeToString, + response_deserializer=transponder_dot_transponder__pb2.TransponderResponse.FromString, + _registered_method=True, + ) self.SetRateTransponder = channel.unary_unary( - '/mavsdk.rpc.transponder.TransponderService/SetRateTransponder', - request_serializer=transponder_dot_transponder__pb2.SetRateTransponderRequest.SerializeToString, - response_deserializer=transponder_dot_transponder__pb2.SetRateTransponderResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.transponder.TransponderService/SetRateTransponder", + request_serializer=transponder_dot_transponder__pb2.SetRateTransponderRequest.SerializeToString, + response_deserializer=transponder_dot_transponder__pb2.SetRateTransponderResponse.FromString, + _registered_method=True, + ) class TransponderServiceServicer(object): @@ -56,40 +62,41 @@ class TransponderServiceServicer(object): """ def SubscribeTransponder(self, request, context): - """Subscribe to 'transponder' updates. - """ + """Subscribe to 'transponder' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def SetRateTransponder(self, request, context): - """Set rate to 'transponder' updates. - """ + """Set rate to 'transponder' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_TransponderServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeTransponder': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeTransponder, - request_deserializer=transponder_dot_transponder__pb2.SubscribeTransponderRequest.FromString, - response_serializer=transponder_dot_transponder__pb2.TransponderResponse.SerializeToString, - ), - 'SetRateTransponder': grpc.unary_unary_rpc_method_handler( - servicer.SetRateTransponder, - request_deserializer=transponder_dot_transponder__pb2.SetRateTransponderRequest.FromString, - response_serializer=transponder_dot_transponder__pb2.SetRateTransponderResponse.SerializeToString, - ), + "SubscribeTransponder": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeTransponder, + request_deserializer=transponder_dot_transponder__pb2.SubscribeTransponderRequest.FromString, + response_serializer=transponder_dot_transponder__pb2.TransponderResponse.SerializeToString, + ), + "SetRateTransponder": grpc.unary_unary_rpc_method_handler( + servicer.SetRateTransponder, + request_deserializer=transponder_dot_transponder__pb2.SetRateTransponderRequest.FromString, + response_serializer=transponder_dot_transponder__pb2.SetRateTransponderResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.transponder.TransponderService', rpc_method_handlers) + "mavsdk.rpc.transponder.TransponderService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.transponder.TransponderService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.transponder.TransponderService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class TransponderService(object): """ Allow users to get ADS-B information @@ -97,20 +104,22 @@ class TransponderService(object): """ @staticmethod - def SubscribeTransponder(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeTransponder( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.transponder.TransponderService/SubscribeTransponder', + "/mavsdk.rpc.transponder.TransponderService/SubscribeTransponder", transponder_dot_transponder__pb2.SubscribeTransponderRequest.SerializeToString, transponder_dot_transponder__pb2.TransponderResponse.FromString, options, @@ -121,23 +130,26 @@ def SubscribeTransponder(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def SetRateTransponder(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SetRateTransponder( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.transponder.TransponderService/SetRateTransponder', + "/mavsdk.rpc.transponder.TransponderService/SetRateTransponder", transponder_dot_transponder__pb2.SetRateTransponderRequest.SerializeToString, transponder_dot_transponder__pb2.SetRateTransponderResponse.FromString, options, @@ -148,4 +160,5 @@ def SetRateTransponder(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/tune.py b/mavsdk/tune.py index b7a041bf..b8ea96dd 100644 --- a/mavsdk/tune.py +++ b/mavsdk/tune.py @@ -8,76 +8,75 @@ class SongElement(Enum): """ - An element of the tune + An element of the tune - Values - ------ - STYLE_LEGATO - After this element, start playing legato + Values + ------ + STYLE_LEGATO + After this element, start playing legato - STYLE_NORMAL - After this element, start playing normal + STYLE_NORMAL + After this element, start playing normal - STYLE_STACCATO - After this element, start playing staccato + STYLE_STACCATO + After this element, start playing staccato - DURATION_1 - After this element, set the note duration to 1 + DURATION_1 + After this element, set the note duration to 1 - DURATION_2 - After this element, set the note duration to 2 + DURATION_2 + After this element, set the note duration to 2 - DURATION_4 - After this element, set the note duration to 4 + DURATION_4 + After this element, set the note duration to 4 - DURATION_8 - After this element, set the note duration to 8 + DURATION_8 + After this element, set the note duration to 8 - DURATION_16 - After this element, set the note duration to 16 + DURATION_16 + After this element, set the note duration to 16 - DURATION_32 - After this element, set the note duration to 32 + DURATION_32 + After this element, set the note duration to 32 - NOTE_A - Play note A + NOTE_A + Play note A - NOTE_B - Play note B + NOTE_B + Play note B - NOTE_C - Play note C + NOTE_C + Play note C - NOTE_D - Play note D + NOTE_D + Play note D - NOTE_E - Play note E + NOTE_E + Play note E - NOTE_F - Play note F + NOTE_F + Play note F - NOTE_G - Play note G + NOTE_G + Play note G - NOTE_PAUSE - Play a rest + NOTE_PAUSE + Play a rest - SHARP - After this element, sharp the note (half a step up) + SHARP + After this element, sharp the note (half a step up) - FLAT - After this element, flat the note (half a step down) + FLAT + After this element, flat the note (half a step down) - OCTAVE_UP - After this element, shift the note 1 octave up + OCTAVE_UP + After this element, shift the note 1 octave up - OCTAVE_DOWN - After this element, shift the note 1 octave down + OCTAVE_DOWN + After this element, shift the note 1 octave down - """ + """ - STYLE_LEGATO = 0 STYLE_NORMAL = 1 STYLE_STACCATO = 2 @@ -146,7 +145,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == tune_pb2.SONG_ELEMENT_STYLE_LEGATO: return SongElement.STYLE_LEGATO if rpc_enum_value == tune_pb2.SONG_ELEMENT_STYLE_NORMAL: @@ -196,126 +195,108 @@ def __str__(self): class TuneDescription: """ - Tune description, containing song elements and tempo. - - Parameters - ---------- - song_elements : [SongElement] - The list of song elements (notes, pauses, ...) to be played + Tune description, containing song elements and tempo. - tempo : int32_t - The tempo of the song (range: 32 - 255) + Parameters + ---------- + song_elements : [SongElement] + The list of song elements (notes, pauses, ...) to be played - """ + tempo : int32_t + The tempo of the song (range: 32 - 255) - + """ - def __init__( - self, - song_elements, - tempo): - """ Initializes the TuneDescription object """ + def __init__(self, song_elements, tempo): + """Initializes the TuneDescription object""" self.song_elements = song_elements self.tempo = tempo def __eq__(self, to_compare): - """ Checks if two TuneDescription are the same """ + """Checks if two TuneDescription are the same""" try: # Try to compare - this likely fails when it is compared to a non # TuneDescription object - return \ - (self.song_elements == to_compare.song_elements) and \ - (self.tempo == to_compare.tempo) + return (self.song_elements == to_compare.song_elements) and ( + self.tempo == to_compare.tempo + ) except AttributeError: return False def __str__(self): - """ TuneDescription in string representation """ - struct_repr = ", ".join([ - "song_elements: " + str(self.song_elements), - "tempo: " + str(self.tempo) - ]) + """TuneDescription in string representation""" + struct_repr = ", ".join( + ["song_elements: " + str(self.song_elements), "tempo: " + str(self.tempo)] + ) return f"TuneDescription: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTuneDescription): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TuneDescription( - - list(map(lambda elem: SongElement.translate_from_rpc(elem), rpcTuneDescription.song_elements)), - - - rpcTuneDescription.tempo + list( + map( + lambda elem: SongElement.translate_from_rpc(elem), + rpcTuneDescription.song_elements, ) + ), + rpcTuneDescription.tempo, + ) def translate_to_rpc(self, rpcTuneDescription): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpc_elems_list = [] for elem in self.song_elements: - rpc_elems_list.append(elem.translate_to_rpc()) - + rpcTuneDescription.song_elements.extend(rpc_elems_list) - - - - - + rpcTuneDescription.tempo = self.tempo - - - class TuneResult: """ - - Parameters - ---------- - result : Result - Result enum value - result_str : std::string - Human-readable English string describing the result + Parameters + ---------- + result : Result + Result enum value + + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for tune requests. + Possible results returned for tune requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request succeeded + SUCCESS + Request succeeded - INVALID_TEMPO - Invalid tempo (range: 32 - 255) + INVALID_TEMPO + Invalid tempo (range: 32 - 255) - TUNE_TOO_LONG - Invalid tune: encoded string must be at most 247 chars + TUNE_TOO_LONG + Invalid tune: encoded string must be at most 247 chars - ERROR - Failed to send the request + ERROR + Failed to send the request - NO_SYSTEM - No system connected + NO_SYSTEM + No system connected - """ + """ - UNKNOWN = 0 SUCCESS = 1 INVALID_TEMPO = 2 @@ -339,7 +320,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == tune_pb2.TuneResult.RESULT_UNKNOWN: return TuneResult.Result.UNKNOWN if rpc_enum_value == tune_pb2.TuneResult.RESULT_SUCCESS: @@ -355,69 +336,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the TuneResult object """ + def __init__(self, result, result_str): + """Initializes the TuneResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two TuneResult are the same """ + """Checks if two TuneResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # TuneResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ TuneResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """TuneResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"TuneResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcTuneResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return TuneResult( - - TuneResult.Result.translate_from_rpc(rpcTuneResult.result), - - - rpcTuneResult.result_str - ) + TuneResult.Result.translate_from_rpc(rpcTuneResult.result), + rpcTuneResult.result_str, + ) def translate_to_rpc(self, rpcTuneResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcTuneResult.result = self.result.translate_to_rpc() - - - - - - rpcTuneResult.result_str = self.result_str - - - + rpcTuneResult.result_str = self.result_str class TuneError(Exception): - """ Raised when a TuneResult is a fail code """ + """Raised when a TuneResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -430,49 +392,44 @@ def __str__(self): class Tune(AsyncBase): """ - Enable creating and sending a tune to be played on the system. + Enable creating and sending a tune to be played on the system. - Generated by dcsdkgen - MAVSDK Tune API + Generated by dcsdkgen - MAVSDK Tune API """ # Plugin name name = "Tune" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = tune_pb2_grpc.TuneServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return TuneResult.translate_from_rpc(response.tune_result) - async def play_tune(self, tune_description): """ - Send a tune to be played by the system. + Send a tune to be played by the system. - Parameters - ---------- - tune_description : TuneDescription - The tune to be played + Parameters + ---------- + tune_description : TuneDescription + The tune to be played - Raises - ------ - TuneError - If the request fails. The error contains the reason for the failure. + Raises + ------ + TuneError + If the request fails. The error contains the reason for the failure. """ request = tune_pb2.PlayTuneRequest() - + tune_description.translate_to_rpc(request.tune_description) - - + response = await self._stub.PlayTune(request) - result = self._extract_result(response) if result.result != TuneResult.Result.SUCCESS: raise TuneError(result, "play_tune()", tune_description) - \ No newline at end of file diff --git a/mavsdk/tune_pb2.py b/mavsdk/tune_pb2.py index ecbc6ce0..6cd5aff0 100644 --- a/mavsdk/tune_pb2.py +++ b/mavsdk/tune_pb2.py @@ -4,46 +4,43 @@ # source: tune/tune.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'tune/tune.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "tune/tune.proto" ) # @@protoc_insertion_point(imports) _sym_db = _symbol_database.Default() - - -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') +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' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'tune.tune_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "tune.tune_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\016io.mavsdk.tuneB\tTuneProto' - _globals['_SONGELEMENT']._serialized_start=503 - _globals['_SONGELEMENT']._serialized_end=1096 - _globals['_PLAYTUNEREQUEST']._serialized_start=36 - _globals['_PLAYTUNEREQUEST']._serialized_end=113 - _globals['_PLAYTUNERESPONSE']._serialized_start=115 - _globals['_PLAYTUNERESPONSE']._serialized_end=183 - _globals['_TUNEDESCRIPTION']._serialized_start=185 - _globals['_TUNEDESCRIPTION']._serialized_end=270 - _globals['_TUNERESULT']._serialized_start=273 - _globals['_TUNERESULT']._serialized_end=500 - _globals['_TUNERESULT_RESULT']._serialized_start=360 - _globals['_TUNERESULT_RESULT']._serialized_end=500 - _globals['_TUNESERVICE']._serialized_start=1098 - _globals['_TUNESERVICE']._serialized_end=1194 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\016io.mavsdk.tuneB\tTuneProto" + _globals["_SONGELEMENT"]._serialized_start = 503 + _globals["_SONGELEMENT"]._serialized_end = 1096 + _globals["_PLAYTUNEREQUEST"]._serialized_start = 36 + _globals["_PLAYTUNEREQUEST"]._serialized_end = 113 + _globals["_PLAYTUNERESPONSE"]._serialized_start = 115 + _globals["_PLAYTUNERESPONSE"]._serialized_end = 183 + _globals["_TUNEDESCRIPTION"]._serialized_start = 185 + _globals["_TUNEDESCRIPTION"]._serialized_end = 270 + _globals["_TUNERESULT"]._serialized_start = 273 + _globals["_TUNERESULT"]._serialized_end = 500 + _globals["_TUNERESULT_RESULT"]._serialized_start = 360 + _globals["_TUNERESULT_RESULT"]._serialized_end = 500 + _globals["_TUNESERVICE"]._serialized_start = 1098 + _globals["_TUNESERVICE"]._serialized_end = 1194 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/tune_pb2_grpc.py b/mavsdk/tune_pb2_grpc.py index a3204880..2a7d6b02 100644 --- a/mavsdk/tune_pb2_grpc.py +++ b/mavsdk/tune_pb2_grpc.py @@ -1,33 +1,36 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import tune_pb2 as tune_dot_tune__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in tune/tune_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in tune/tune_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) class TuneServiceStub(object): - """Enable creating and sending a tune to be played on the system. - """ + """Enable creating and sending a tune to be played on the system.""" def __init__(self, channel): """Constructor. @@ -36,58 +39,61 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.PlayTune = channel.unary_unary( - '/mavsdk.rpc.tune.TuneService/PlayTune', - request_serializer=tune_dot_tune__pb2.PlayTuneRequest.SerializeToString, - response_deserializer=tune_dot_tune__pb2.PlayTuneResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.tune.TuneService/PlayTune", + request_serializer=tune_dot_tune__pb2.PlayTuneRequest.SerializeToString, + response_deserializer=tune_dot_tune__pb2.PlayTuneResponse.FromString, + _registered_method=True, + ) class TuneServiceServicer(object): - """Enable creating and sending a tune to be played on the system. - """ + """Enable creating and sending a tune to be played on the system.""" def PlayTune(self, request, context): - """Send a tune to be played by the system. - """ + """Send a tune to be played by the system.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_TuneServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'PlayTune': grpc.unary_unary_rpc_method_handler( - servicer.PlayTune, - request_deserializer=tune_dot_tune__pb2.PlayTuneRequest.FromString, - response_serializer=tune_dot_tune__pb2.PlayTuneResponse.SerializeToString, - ), + "PlayTune": grpc.unary_unary_rpc_method_handler( + servicer.PlayTune, + request_deserializer=tune_dot_tune__pb2.PlayTuneRequest.FromString, + response_serializer=tune_dot_tune__pb2.PlayTuneResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.tune.TuneService', rpc_method_handlers) + "mavsdk.rpc.tune.TuneService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.tune.TuneService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.tune.TuneService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class TuneService(object): - """Enable creating and sending a tune to be played on the system. - """ + """Enable creating and sending a tune to be played on the system.""" @staticmethod - def PlayTune(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def PlayTune( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.tune.TuneService/PlayTune', + "/mavsdk.rpc.tune.TuneService/PlayTune", tune_dot_tune__pb2.PlayTuneRequest.SerializeToString, tune_dot_tune__pb2.PlayTuneResponse.FromString, options, @@ -98,4 +104,5 @@ def PlayTune(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/mavsdk/winch.py b/mavsdk/winch.py index e66ca037..b4414cf5 100644 --- a/mavsdk/winch.py +++ b/mavsdk/winch.py @@ -8,43 +8,42 @@ class WinchAction(Enum): """ - Winch Action type. + Winch Action type. - Values - ------ - RELAXED - Allow motor to freewheel + Values + ------ + RELAXED + Allow motor to freewheel - RELATIVE_LENGTH_CONTROL - Wind or unwind specified length of line, optionally using specified rate + RELATIVE_LENGTH_CONTROL + Wind or unwind specified length of line, optionally using specified rate - RATE_CONTROL - Wind or unwind line at specified rate + RATE_CONTROL + Wind or unwind line at specified rate - LOCK - Perform the locking sequence to relieve motor while in the fully retracted position + LOCK + Perform the locking sequence to relieve motor while in the fully retracted position - DELIVER - Sequence of drop, slow down, touch down, reel up, lock + DELIVER + Sequence of drop, slow down, touch down, reel up, lock - HOLD - Engage motor and hold current position + HOLD + Engage motor and hold current position - RETRACT - Return the reel to the fully retracted position + RETRACT + Return the reel to the fully retracted position - LOAD_LINE - Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold + LOAD_LINE + Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold - ABANDON_LINE - Spool out the entire length of the line + ABANDON_LINE + Spool out the entire length of the line - LOAD_PAYLOAD - Spools out just enough to present the hook to the user to load the payload + LOAD_PAYLOAD + Spools out just enough to present the hook to the user to load the payload - """ + """ - RELAXED = 0 RELATIVE_LENGTH_CONTROL = 1 RATE_CONTROL = 2 @@ -80,7 +79,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == winch_pb2.WINCH_ACTION_RELAXED: return WinchAction.RELAXED if rpc_enum_value == winch_pb2.WINCH_ACTION_RELATIVE_LENGTH_CONTROL: @@ -108,79 +107,78 @@ def __str__(self): class StatusFlags: """ - Winch Status Flags. - - The status flags are defined in mavlink - https://mavlink.io/en/messages/common.html#MAV_WINCH_STATUS_FLAG. + Winch Status Flags. - Multiple status fields can be set simultaneously. Mavlink does - not specify which states are mutually exclusive. + The status flags are defined in mavlink + https://mavlink.io/en/messages/common.html#MAV_WINCH_STATUS_FLAG. - Parameters - ---------- - healthy : bool - Winch is healthy + Multiple status fields can be set simultaneously. Mavlink does + not specify which states are mutually exclusive. - fully_retracted : bool - Winch line is fully retracted + Parameters + ---------- + healthy : bool + Winch is healthy - moving : bool - Winch motor is moving + fully_retracted : bool + Winch line is fully retracted - clutch_engaged : bool - Winch clutch is engaged allowing motor to move freely + moving : bool + Winch motor is moving - locked : bool - Winch is locked by locking mechanism + clutch_engaged : bool + Winch clutch is engaged allowing motor to move freely - dropping : bool - Winch is gravity dropping payload + locked : bool + Winch is locked by locking mechanism - arresting : bool - Winch is arresting payload descent + dropping : bool + Winch is gravity dropping payload - ground_sense : bool - Winch is using torque measurements to sense the ground + arresting : bool + Winch is arresting payload descent - retracting : bool - Winch is returning to the fully retracted position + ground_sense : bool + Winch is using torque measurements to sense the ground - redeliver : bool - Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING. + retracting : bool + Winch is returning to the fully retracted position - abandon_line : bool - Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold. + redeliver : bool + Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING. - locking : bool - Winch is engaging the locking mechanism + abandon_line : bool + Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold. - load_line : bool - Winch is spooling on line + locking : bool + Winch is engaging the locking mechanism - load_payload : bool - Winch is loading a payload + load_line : bool + Winch is spooling on line - """ + load_payload : bool + Winch is loading a payload - + """ def __init__( - self, - healthy, - fully_retracted, - moving, - clutch_engaged, - locked, - dropping, - arresting, - ground_sense, - retracting, - redeliver, - abandon_line, - locking, - load_line, - load_payload): - """ Initializes the StatusFlags object """ + self, + healthy, + fully_retracted, + moving, + clutch_engaged, + locked, + dropping, + arresting, + ground_sense, + retracting, + redeliver, + abandon_line, + locking, + load_line, + load_payload, + ): + """Initializes the StatusFlags object""" self.healthy = healthy self.fully_retracted = fully_retracted self.moving = moving @@ -197,32 +195,34 @@ def __init__( self.load_payload = load_payload def __eq__(self, to_compare): - """ Checks if two StatusFlags are the same """ + """Checks if two StatusFlags are the same""" try: # Try to compare - this likely fails when it is compared to a non # StatusFlags object - return \ - (self.healthy == to_compare.healthy) and \ - (self.fully_retracted == to_compare.fully_retracted) and \ - (self.moving == to_compare.moving) and \ - (self.clutch_engaged == to_compare.clutch_engaged) and \ - (self.locked == to_compare.locked) and \ - (self.dropping == to_compare.dropping) and \ - (self.arresting == to_compare.arresting) and \ - (self.ground_sense == to_compare.ground_sense) and \ - (self.retracting == to_compare.retracting) and \ - (self.redeliver == to_compare.redeliver) and \ - (self.abandon_line == to_compare.abandon_line) and \ - (self.locking == to_compare.locking) and \ - (self.load_line == to_compare.load_line) and \ - (self.load_payload == to_compare.load_payload) + return ( + (self.healthy == to_compare.healthy) + and (self.fully_retracted == to_compare.fully_retracted) + and (self.moving == to_compare.moving) + and (self.clutch_engaged == to_compare.clutch_engaged) + and (self.locked == to_compare.locked) + and (self.dropping == to_compare.dropping) + and (self.arresting == to_compare.arresting) + and (self.ground_sense == to_compare.ground_sense) + and (self.retracting == to_compare.retracting) + and (self.redeliver == to_compare.redeliver) + and (self.abandon_line == to_compare.abandon_line) + and (self.locking == to_compare.locking) + and (self.load_line == to_compare.load_line) + and (self.load_payload == to_compare.load_payload) + ) except AttributeError: return False def __str__(self): - """ StatusFlags in string representation """ - struct_repr = ", ".join([ + """StatusFlags in string representation""" + struct_repr = ", ".join( + [ "healthy: " + str(self.healthy), "fully_retracted: " + str(self.fully_retracted), "moving: " + str(self.moving), @@ -236,193 +236,108 @@ def __str__(self): "abandon_line: " + str(self.abandon_line), "locking: " + str(self.locking), "load_line: " + str(self.load_line), - "load_payload: " + str(self.load_payload) - ]) + "load_payload: " + str(self.load_payload), + ] + ) return f"StatusFlags: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStatusFlags): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return StatusFlags( - - rpcStatusFlags.healthy, - - - rpcStatusFlags.fully_retracted, - - - rpcStatusFlags.moving, - - - rpcStatusFlags.clutch_engaged, - - - rpcStatusFlags.locked, - - - rpcStatusFlags.dropping, - - - rpcStatusFlags.arresting, - - - rpcStatusFlags.ground_sense, - - - rpcStatusFlags.retracting, - - - rpcStatusFlags.redeliver, - - - rpcStatusFlags.abandon_line, - - - rpcStatusFlags.locking, - - - rpcStatusFlags.load_line, - - - rpcStatusFlags.load_payload - ) + rpcStatusFlags.healthy, + rpcStatusFlags.fully_retracted, + rpcStatusFlags.moving, + rpcStatusFlags.clutch_engaged, + rpcStatusFlags.locked, + rpcStatusFlags.dropping, + rpcStatusFlags.arresting, + rpcStatusFlags.ground_sense, + rpcStatusFlags.retracting, + rpcStatusFlags.redeliver, + rpcStatusFlags.abandon_line, + rpcStatusFlags.locking, + rpcStatusFlags.load_line, + rpcStatusFlags.load_payload, + ) def translate_to_rpc(self, rpcStatusFlags): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStatusFlags.healthy = self.healthy - - - - - + rpcStatusFlags.fully_retracted = self.fully_retracted - - - - - + rpcStatusFlags.moving = self.moving - - - - - + rpcStatusFlags.clutch_engaged = self.clutch_engaged - - - - - + rpcStatusFlags.locked = self.locked - - - - - + rpcStatusFlags.dropping = self.dropping - - - - - + rpcStatusFlags.arresting = self.arresting - - - - - + rpcStatusFlags.ground_sense = self.ground_sense - - - - - + rpcStatusFlags.retracting = self.retracting - - - - - + rpcStatusFlags.redeliver = self.redeliver - - - - - + rpcStatusFlags.abandon_line = self.abandon_line - - - - - + rpcStatusFlags.locking = self.locking - - - - - + rpcStatusFlags.load_line = self.load_line - - - - - + rpcStatusFlags.load_payload = self.load_payload - - - class Status: """ - Status type. - - Parameters - ---------- - time_usec : uint64_t - Time in usec + Status type. - line_length_m : float - Length of the line in meters + Parameters + ---------- + time_usec : uint64_t + Time in usec - speed_m_s : float - Speed in meters per second + line_length_m : float + Length of the line in meters - tension_kg : float - Tension in kilograms + speed_m_s : float + Speed in meters per second - voltage_v : float - Voltage in volts + tension_kg : float + Tension in kilograms - current_a : float - Current in amperes + voltage_v : float + Voltage in volts - temperature_c : int32_t - Temperature in Celsius + current_a : float + Current in amperes - status_flags : StatusFlags - Status flags + temperature_c : int32_t + Temperature in Celsius - """ + status_flags : StatusFlags + Status flags - + """ def __init__( - self, - time_usec, - line_length_m, - speed_m_s, - tension_kg, - voltage_v, - current_a, - temperature_c, - status_flags): - """ Initializes the Status object """ + self, + time_usec, + line_length_m, + speed_m_s, + tension_kg, + voltage_v, + current_a, + temperature_c, + status_flags, + ): + """Initializes the Status object""" self.time_usec = time_usec self.line_length_m = line_length_m self.speed_m_s = speed_m_s @@ -433,26 +348,28 @@ def __init__( self.status_flags = status_flags def __eq__(self, to_compare): - """ Checks if two Status are the same """ + """Checks if two Status are the same""" try: # Try to compare - this likely fails when it is compared to a non # Status object - return \ - (self.time_usec == to_compare.time_usec) and \ - (self.line_length_m == to_compare.line_length_m) and \ - (self.speed_m_s == to_compare.speed_m_s) and \ - (self.tension_kg == to_compare.tension_kg) and \ - (self.voltage_v == to_compare.voltage_v) and \ - (self.current_a == to_compare.current_a) and \ - (self.temperature_c == to_compare.temperature_c) and \ - (self.status_flags == to_compare.status_flags) + return ( + (self.time_usec == to_compare.time_usec) + and (self.line_length_m == to_compare.line_length_m) + and (self.speed_m_s == to_compare.speed_m_s) + and (self.tension_kg == to_compare.tension_kg) + and (self.voltage_v == to_compare.voltage_v) + and (self.current_a == to_compare.current_a) + and (self.temperature_c == to_compare.temperature_c) + and (self.status_flags == to_compare.status_flags) + ) except AttributeError: return False def __str__(self): - """ Status in string representation """ - struct_repr = ", ".join([ + """Status in string representation""" + struct_repr = ", ".join( + [ "time_usec: " + str(self.time_usec), "line_length_m: " + str(self.line_length_m), "speed_m_s: " + str(self.speed_m_s), @@ -460,140 +377,89 @@ def __str__(self): "voltage_v: " + str(self.voltage_v), "current_a: " + str(self.current_a), "temperature_c: " + str(self.temperature_c), - "status_flags: " + str(self.status_flags) - ]) + "status_flags: " + str(self.status_flags), + ] + ) return f"Status: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcStatus): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return Status( - - rpcStatus.time_usec, - - - rpcStatus.line_length_m, - - - rpcStatus.speed_m_s, - - - rpcStatus.tension_kg, - - - rpcStatus.voltage_v, - - - rpcStatus.current_a, - - - rpcStatus.temperature_c, - - - StatusFlags.translate_from_rpc(rpcStatus.status_flags) - ) + rpcStatus.time_usec, + rpcStatus.line_length_m, + rpcStatus.speed_m_s, + rpcStatus.tension_kg, + rpcStatus.voltage_v, + rpcStatus.current_a, + rpcStatus.temperature_c, + StatusFlags.translate_from_rpc(rpcStatus.status_flags), + ) def translate_to_rpc(self, rpcStatus): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcStatus.time_usec = self.time_usec - - - - - + rpcStatus.line_length_m = self.line_length_m - - - - - + rpcStatus.speed_m_s = self.speed_m_s - - - - - + rpcStatus.tension_kg = self.tension_kg - - - - - + rpcStatus.voltage_v = self.voltage_v - - - - - + rpcStatus.current_a = self.current_a - - - - - + rpcStatus.temperature_c = self.temperature_c - - - - - + self.status_flags.translate_to_rpc(rpcStatus.status_flags) - - - class WinchResult: """ - Result type. + Result type. - Parameters - ---------- - result : Result - Result enum value + Parameters + ---------- + result : Result + Result enum value - result_str : std::string - Human-readable English string describing the result + result_str : std::string + Human-readable English string describing the result - """ + """ - - class Result(Enum): """ - Possible results returned for winch action requests. + Possible results returned for winch action requests. - Values - ------ - UNKNOWN - Unknown result + Values + ------ + UNKNOWN + Unknown result - SUCCESS - Request was successful + SUCCESS + Request was successful - NO_SYSTEM - No system is connected + NO_SYSTEM + No system is connected - BUSY - Temporarily rejected + BUSY + Temporarily rejected - TIMEOUT - Request timed out + TIMEOUT + Request timed out - UNSUPPORTED - Action not supported + UNSUPPORTED + Action not supported - FAILED - Action failed + FAILED + Action failed - """ + """ - UNKNOWN = 0 SUCCESS = 1 NO_SYSTEM = 2 @@ -620,7 +486,7 @@ def translate_to_rpc(self): @staticmethod def translate_from_rpc(rpc_enum_value): - """ Parses a gRPC response """ + """Parses a gRPC response""" if rpc_enum_value == winch_pb2.WinchResult.RESULT_UNKNOWN: return WinchResult.Result.UNKNOWN if rpc_enum_value == winch_pb2.WinchResult.RESULT_SUCCESS: @@ -638,69 +504,50 @@ def translate_from_rpc(rpc_enum_value): def __str__(self): return self.name - - def __init__( - self, - result, - result_str): - """ Initializes the WinchResult object """ + def __init__(self, result, result_str): + """Initializes the WinchResult object""" self.result = result self.result_str = result_str def __eq__(self, to_compare): - """ Checks if two WinchResult are the same """ + """Checks if two WinchResult are the same""" try: # Try to compare - this likely fails when it is compared to a non # WinchResult object - return \ - (self.result == to_compare.result) and \ - (self.result_str == to_compare.result_str) + return (self.result == to_compare.result) and ( + self.result_str == to_compare.result_str + ) except AttributeError: return False def __str__(self): - """ WinchResult in string representation """ - struct_repr = ", ".join([ - "result: " + str(self.result), - "result_str: " + str(self.result_str) - ]) + """WinchResult in string representation""" + struct_repr = ", ".join( + ["result: " + str(self.result), "result_str: " + str(self.result_str)] + ) return f"WinchResult: [{struct_repr}]" @staticmethod def translate_from_rpc(rpcWinchResult): - """ Translates a gRPC struct to the SDK equivalent """ + """Translates a gRPC struct to the SDK equivalent""" return WinchResult( - - WinchResult.Result.translate_from_rpc(rpcWinchResult.result), - - - rpcWinchResult.result_str - ) + WinchResult.Result.translate_from_rpc(rpcWinchResult.result), + rpcWinchResult.result_str, + ) def translate_to_rpc(self, rpcWinchResult): - """ Translates this SDK object into its gRPC equivalent """ + """Translates this SDK object into its gRPC equivalent""" - - - rpcWinchResult.result = self.result.translate_to_rpc() - - - - - - rpcWinchResult.result_str = self.result_str - - - + rpcWinchResult.result_str = self.result_str class WinchError(Exception): - """ Raised when a WinchResult is a fail code """ + """Raised when a WinchResult is a fail code""" def __init__(self, result, origin, *params): self._result = result @@ -713,34 +560,32 @@ def __str__(self): class Winch(AsyncBase): """ - Allows users to send winch actions, as well as receive status information from winch systems. + Allows users to send winch actions, as well as receive status information from winch systems. - Generated by dcsdkgen - MAVSDK Winch API + Generated by dcsdkgen - MAVSDK Winch API """ # Plugin name name = "Winch" def _setup_stub(self, channel): - """ Setups the api stub """ + """Setups the api stub""" self._stub = winch_pb2_grpc.WinchServiceStub(channel) - def _extract_result(self, response): - """ Returns the response status and description """ + """Returns the response status and description""" return WinchResult.translate_from_rpc(response.winch_result) - async def status(self): """ - Subscribe to 'winch status' updates. + Subscribe to 'winch status' updates. + + Yields + ------- + status : Status + The next 'winch status' state - Yields - ------- - status : Status - The next 'winch status' state - """ request = winch_pb2.SubscribeStatusRequest() @@ -748,57 +593,52 @@ async def status(self): try: async for response in status_stream: - - - yield Status.translate_from_rpc(response.status) finally: status_stream.cancel() async def relax(self, instance): """ - Allow motor to freewheel. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Allow motor to freewheel. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.RelaxRequest() request.instance = instance response = await self._stub.Relax(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "relax()", instance) - async def relative_length_control(self, instance, length_m, rate_m_s): """ - Wind or unwind specified length of line, optionally using specified rate. + Wind or unwind specified length of line, optionally using specified rate. - Parameters - ---------- - instance : uint32_t - Instance ID of the winch addressed by this request + Parameters + ---------- + instance : uint32_t + Instance ID of the winch addressed by this request - length_m : float - Length of line to unwind or wind + length_m : float + Length of line to unwind or wind - rate_m_s : float - Rate at which to wind or unwind the line + rate_m_s : float + Rate at which to wind or unwind the line - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.RelativeLengthControlRequest() @@ -807,28 +647,28 @@ async def relative_length_control(self, instance, length_m, rate_m_s): request.rate_m_s = rate_m_s response = await self._stub.RelativeLengthControl(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: - raise WinchError(result, "relative_length_control()", instance, length_m, rate_m_s) - + raise WinchError( + result, "relative_length_control()", instance, length_m, rate_m_s + ) async def rate_control(self, instance, rate_m_s): """ - Wind or unwind line at specified rate. - - Parameters - ---------- - instance : uint32_t - - rate_m_s : float - Rate at which to wind or unwind the line - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Wind or unwind line at specified rate. + + Parameters + ---------- + instance : uint32_t + + rate_m_s : float + Rate at which to wind or unwind the line + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.RateControlRequest() @@ -836,186 +676,170 @@ async def rate_control(self, instance, rate_m_s): request.rate_m_s = rate_m_s response = await self._stub.RateControl(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "rate_control()", instance, rate_m_s) - async def lock(self, instance): """ - Perform the locking sequence to relieve motor while in the fully retracted position. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Perform the locking sequence to relieve motor while in the fully retracted position. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.LockRequest() request.instance = instance response = await self._stub.Lock(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "lock()", instance) - async def deliver(self, instance): """ - Sequence of drop, slow down, touch down, reel up, lock. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Sequence of drop, slow down, touch down, reel up, lock. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.DeliverRequest() request.instance = instance response = await self._stub.Deliver(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "deliver()", instance) - async def hold(self, instance): """ - Engage motor and hold current position. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Engage motor and hold current position. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.HoldRequest() request.instance = instance response = await self._stub.Hold(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "hold()", instance) - async def retract(self, instance): """ - Return the reel to the fully retracted position. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Return the reel to the fully retracted position. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.RetractRequest() request.instance = instance response = await self._stub.Retract(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "retract()", instance) - async def load_line(self, instance): """ - Load the reel with line. - - The winch will calculate the total loaded length and stop when the tension exceeds a threshold. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Load the reel with line. + + The winch will calculate the total loaded length and stop when the tension exceeds a threshold. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.LoadLineRequest() request.instance = instance response = await self._stub.LoadLine(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "load_line()", instance) - async def abandon_line(self, instance): """ - Spool out the entire length of the line. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Spool out the entire length of the line. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.AbandonLineRequest() request.instance = instance response = await self._stub.AbandonLine(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "abandon_line()", instance) - async def load_payload(self, instance): """ - Spools out just enough to present the hook to the user to load the payload. - - Parameters - ---------- - instance : uint32_t - - Raises - ------ - WinchError - If the request fails. The error contains the reason for the failure. + Spools out just enough to present the hook to the user to load the payload. + + Parameters + ---------- + instance : uint32_t + + Raises + ------ + WinchError + If the request fails. The error contains the reason for the failure. """ request = winch_pb2.LoadPayloadRequest() request.instance = instance response = await self._stub.LoadPayload(request) - result = self._extract_result(response) if result.result != WinchResult.Result.SUCCESS: raise WinchError(result, "load_payload()", instance) - \ No newline at end of file diff --git a/mavsdk/winch_pb2.py b/mavsdk/winch_pb2.py index 045ea9eb..cf55285d 100644 --- a/mavsdk/winch_pb2.py +++ b/mavsdk/winch_pb2.py @@ -4,18 +4,15 @@ # source: winch/winch.proto # Protobuf Python Version: 5.29.0 """Generated protocol buffer code.""" + from google.protobuf import descriptor as _descriptor from google.protobuf import descriptor_pool as _descriptor_pool from google.protobuf import runtime_version as _runtime_version from google.protobuf import symbol_database as _symbol_database from google.protobuf.internal import builder as _builder + _runtime_version.ValidateProtobufRuntimeVersion( - _runtime_version.Domain.PUBLIC, - 5, - 29, - 0, - '', - 'winch/winch.proto' + _runtime_version.Domain.PUBLIC, 5, 29, 0, "", "winch/winch.proto" ) # @@protoc_insertion_point(imports) @@ -25,70 +22,76 @@ from . import mavsdk_options_pb2 as mavsdk__options__pb2 -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x11winch/winch.proto\x12\x10mavsdk.rpc.winch\x1a\x14mavsdk_options.proto\"\x18\n\x16SubscribeStatusRequest\":\n\x0eStatusResponse\x12(\n\x06status\x18\x01 \x01(\x0b\x32\x18.mavsdk.rpc.winch.Status\"\xa1\x02\n\x0bStatusFlags\x12\x0f\n\x07healthy\x18\x01 \x01(\x08\x12\x17\n\x0f\x66ully_retracted\x18\x02 \x01(\x08\x12\x0e\n\x06moving\x18\x03 \x01(\x08\x12\x16\n\x0e\x63lutch_engaged\x18\x04 \x01(\x08\x12\x0e\n\x06locked\x18\x05 \x01(\x08\x12\x10\n\x08\x64ropping\x18\x06 \x01(\x08\x12\x11\n\tarresting\x18\x07 \x01(\x08\x12\x14\n\x0cground_sense\x18\x08 \x01(\x08\x12\x12\n\nretracting\x18\t \x01(\x08\x12\x11\n\tredeliver\x18\n \x01(\x08\x12\x14\n\x0c\x61\x62\x61ndon_line\x18\x0b \x01(\x08\x12\x0f\n\x07locking\x18\x0c \x01(\x08\x12\x11\n\tload_line\x18\r \x01(\x08\x12\x14\n\x0cload_payload\x18\x0e \x01(\x08\"\xcb\x01\n\x06Status\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x15\n\rline_length_m\x18\x02 \x01(\x02\x12\x11\n\tspeed_m_s\x18\x03 \x01(\x02\x12\x12\n\ntension_kg\x18\x04 \x01(\x02\x12\x11\n\tvoltage_v\x18\x05 \x01(\x02\x12\x11\n\tcurrent_a\x18\x06 \x01(\x02\x12\x15\n\rtemperature_c\x18\x07 \x01(\x05\x12\x33\n\x0cstatus_flags\x18\x08 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.StatusFlags\" \n\x0cRelaxRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"D\n\rRelaxResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"]\n\x1cRelativeLengthControlRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\x12\x10\n\x08length_m\x18\x02 \x01(\x02\x12\x19\n\x08rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"T\n\x1dRelativeLengthControlResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"8\n\x12RateControlRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\x12\x10\n\x08rate_m_s\x18\x02 \x01(\x02\"J\n\x13RateControlResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"\x1f\n\x0bLockRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"C\n\x0cLockResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"\"\n\x0e\x44\x65liverRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"F\n\x0f\x44\x65liverResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"\x1f\n\x0bHoldRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"C\n\x0cHoldResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"\"\n\x0eRetractRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"F\n\x0fRetractResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"#\n\x0fLoadLineRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"G\n\x10LoadLineResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"&\n\x12\x41\x62\x61ndonLineRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"J\n\x13\x41\x62\x61ndonLineResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"&\n\x12LoadPayloadRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\"J\n\x13LoadPayloadResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult\"\xf0\x01\n\x0bWinchResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.winch.WinchResult.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*\xac\x02\n\x0bWinchAction\x12\x18\n\x14WINCH_ACTION_RELAXED\x10\x00\x12(\n$WINCH_ACTION_RELATIVE_LENGTH_CONTROL\x10\x01\x12\x1d\n\x19WINCH_ACTION_RATE_CONTROL\x10\x02\x12\x15\n\x11WINCH_ACTION_LOCK\x10\x03\x12\x18\n\x14WINCH_ACTION_DELIVER\x10\x04\x12\x15\n\x11WINCH_ACTION_HOLD\x10\x05\x12\x18\n\x14WINCH_ACTION_RETRACT\x10\x06\x12\x1a\n\x16WINCH_ACTION_LOAD_LINE\x10\x07\x12\x1d\n\x19WINCH_ACTION_ABANDON_LINE\x10\x08\x12\x1d\n\x19WINCH_ACTION_LOAD_PAYLOAD\x10\t2\xde\x07\n\x0cWinchService\x12\x61\n\x0fSubscribeStatus\x12(.mavsdk.rpc.winch.SubscribeStatusRequest\x1a .mavsdk.rpc.winch.StatusResponse\"\x00\x30\x01\x12J\n\x05Relax\x12\x1e.mavsdk.rpc.winch.RelaxRequest\x1a\x1f.mavsdk.rpc.winch.RelaxResponse\"\x00\x12z\n\x15RelativeLengthControl\x12..mavsdk.rpc.winch.RelativeLengthControlRequest\x1a/.mavsdk.rpc.winch.RelativeLengthControlResponse\"\x00\x12\\\n\x0bRateControl\x12$.mavsdk.rpc.winch.RateControlRequest\x1a%.mavsdk.rpc.winch.RateControlResponse\"\x00\x12G\n\x04Lock\x12\x1d.mavsdk.rpc.winch.LockRequest\x1a\x1e.mavsdk.rpc.winch.LockResponse\"\x00\x12P\n\x07\x44\x65liver\x12 .mavsdk.rpc.winch.DeliverRequest\x1a!.mavsdk.rpc.winch.DeliverResponse\"\x00\x12G\n\x04Hold\x12\x1d.mavsdk.rpc.winch.HoldRequest\x1a\x1e.mavsdk.rpc.winch.HoldResponse\"\x00\x12P\n\x07Retract\x12 .mavsdk.rpc.winch.RetractRequest\x1a!.mavsdk.rpc.winch.RetractResponse\"\x00\x12S\n\x08LoadLine\x12!.mavsdk.rpc.winch.LoadLineRequest\x1a\".mavsdk.rpc.winch.LoadLineResponse\"\x00\x12\\\n\x0b\x41\x62\x61ndonLine\x12$.mavsdk.rpc.winch.AbandonLineRequest\x1a%.mavsdk.rpc.winch.AbandonLineResponse\"\x00\x12\\\n\x0bLoadPayload\x12$.mavsdk.rpc.winch.LoadPayloadRequest\x1a%.mavsdk.rpc.winch.LoadPayloadResponse\"\x00\x42\x1d\n\x0fio.mavsdk.winchB\nWinchProtob\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile( + b'\n\x11winch/winch.proto\x12\x10mavsdk.rpc.winch\x1a\x14mavsdk_options.proto"\x18\n\x16SubscribeStatusRequest":\n\x0eStatusResponse\x12(\n\x06status\x18\x01 \x01(\x0b\x32\x18.mavsdk.rpc.winch.Status"\xa1\x02\n\x0bStatusFlags\x12\x0f\n\x07healthy\x18\x01 \x01(\x08\x12\x17\n\x0f\x66ully_retracted\x18\x02 \x01(\x08\x12\x0e\n\x06moving\x18\x03 \x01(\x08\x12\x16\n\x0e\x63lutch_engaged\x18\x04 \x01(\x08\x12\x0e\n\x06locked\x18\x05 \x01(\x08\x12\x10\n\x08\x64ropping\x18\x06 \x01(\x08\x12\x11\n\tarresting\x18\x07 \x01(\x08\x12\x14\n\x0cground_sense\x18\x08 \x01(\x08\x12\x12\n\nretracting\x18\t \x01(\x08\x12\x11\n\tredeliver\x18\n \x01(\x08\x12\x14\n\x0c\x61\x62\x61ndon_line\x18\x0b \x01(\x08\x12\x0f\n\x07locking\x18\x0c \x01(\x08\x12\x11\n\tload_line\x18\r \x01(\x08\x12\x14\n\x0cload_payload\x18\x0e \x01(\x08"\xcb\x01\n\x06Status\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x15\n\rline_length_m\x18\x02 \x01(\x02\x12\x11\n\tspeed_m_s\x18\x03 \x01(\x02\x12\x12\n\ntension_kg\x18\x04 \x01(\x02\x12\x11\n\tvoltage_v\x18\x05 \x01(\x02\x12\x11\n\tcurrent_a\x18\x06 \x01(\x02\x12\x15\n\rtemperature_c\x18\x07 \x01(\x05\x12\x33\n\x0cstatus_flags\x18\x08 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.StatusFlags" \n\x0cRelaxRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"D\n\rRelaxResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"]\n\x1cRelativeLengthControlRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\x12\x10\n\x08length_m\x18\x02 \x01(\x02\x12\x19\n\x08rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN"T\n\x1dRelativeLengthControlResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"8\n\x12RateControlRequest\x12\x10\n\x08instance\x18\x01 \x01(\r\x12\x10\n\x08rate_m_s\x18\x02 \x01(\x02"J\n\x13RateControlResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"\x1f\n\x0bLockRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"C\n\x0cLockResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult""\n\x0e\x44\x65liverRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"F\n\x0f\x44\x65liverResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"\x1f\n\x0bHoldRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"C\n\x0cHoldResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult""\n\x0eRetractRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"F\n\x0fRetractResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"#\n\x0fLoadLineRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"G\n\x10LoadLineResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"&\n\x12\x41\x62\x61ndonLineRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"J\n\x13\x41\x62\x61ndonLineResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"&\n\x12LoadPayloadRequest\x12\x10\n\x08instance\x18\x01 \x01(\r"J\n\x13LoadPayloadResponse\x12\x33\n\x0cwinch_result\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.winch.WinchResult"\xf0\x01\n\x0bWinchResult\x12\x34\n\x06result\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.winch.WinchResult.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*\xac\x02\n\x0bWinchAction\x12\x18\n\x14WINCH_ACTION_RELAXED\x10\x00\x12(\n$WINCH_ACTION_RELATIVE_LENGTH_CONTROL\x10\x01\x12\x1d\n\x19WINCH_ACTION_RATE_CONTROL\x10\x02\x12\x15\n\x11WINCH_ACTION_LOCK\x10\x03\x12\x18\n\x14WINCH_ACTION_DELIVER\x10\x04\x12\x15\n\x11WINCH_ACTION_HOLD\x10\x05\x12\x18\n\x14WINCH_ACTION_RETRACT\x10\x06\x12\x1a\n\x16WINCH_ACTION_LOAD_LINE\x10\x07\x12\x1d\n\x19WINCH_ACTION_ABANDON_LINE\x10\x08\x12\x1d\n\x19WINCH_ACTION_LOAD_PAYLOAD\x10\t2\xde\x07\n\x0cWinchService\x12\x61\n\x0fSubscribeStatus\x12(.mavsdk.rpc.winch.SubscribeStatusRequest\x1a .mavsdk.rpc.winch.StatusResponse"\x00\x30\x01\x12J\n\x05Relax\x12\x1e.mavsdk.rpc.winch.RelaxRequest\x1a\x1f.mavsdk.rpc.winch.RelaxResponse"\x00\x12z\n\x15RelativeLengthControl\x12..mavsdk.rpc.winch.RelativeLengthControlRequest\x1a/.mavsdk.rpc.winch.RelativeLengthControlResponse"\x00\x12\\\n\x0bRateControl\x12$.mavsdk.rpc.winch.RateControlRequest\x1a%.mavsdk.rpc.winch.RateControlResponse"\x00\x12G\n\x04Lock\x12\x1d.mavsdk.rpc.winch.LockRequest\x1a\x1e.mavsdk.rpc.winch.LockResponse"\x00\x12P\n\x07\x44\x65liver\x12 .mavsdk.rpc.winch.DeliverRequest\x1a!.mavsdk.rpc.winch.DeliverResponse"\x00\x12G\n\x04Hold\x12\x1d.mavsdk.rpc.winch.HoldRequest\x1a\x1e.mavsdk.rpc.winch.HoldResponse"\x00\x12P\n\x07Retract\x12 .mavsdk.rpc.winch.RetractRequest\x1a!.mavsdk.rpc.winch.RetractResponse"\x00\x12S\n\x08LoadLine\x12!.mavsdk.rpc.winch.LoadLineRequest\x1a".mavsdk.rpc.winch.LoadLineResponse"\x00\x12\\\n\x0b\x41\x62\x61ndonLine\x12$.mavsdk.rpc.winch.AbandonLineRequest\x1a%.mavsdk.rpc.winch.AbandonLineResponse"\x00\x12\\\n\x0bLoadPayload\x12$.mavsdk.rpc.winch.LoadPayloadRequest\x1a%.mavsdk.rpc.winch.LoadPayloadResponse"\x00\x42\x1d\n\x0fio.mavsdk.winchB\nWinchProtob\x06proto3' +) _globals = globals() _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals) -_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'winch.winch_pb2', _globals) +_builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, "winch.winch_pb2", _globals) if not _descriptor._USE_C_DESCRIPTORS: - _globals['DESCRIPTOR']._loaded_options = None - _globals['DESCRIPTOR']._serialized_options = b'\n\017io.mavsdk.winchB\nWinchProto' - _globals['_RELATIVELENGTHCONTROLREQUEST'].fields_by_name['rate_m_s']._loaded_options = None - _globals['_RELATIVELENGTHCONTROLREQUEST'].fields_by_name['rate_m_s']._serialized_options = b'\202\265\030\003NaN' - _globals['_WINCHACTION']._serialized_start=2070 - _globals['_WINCHACTION']._serialized_end=2370 - _globals['_SUBSCRIBESTATUSREQUEST']._serialized_start=61 - _globals['_SUBSCRIBESTATUSREQUEST']._serialized_end=85 - _globals['_STATUSRESPONSE']._serialized_start=87 - _globals['_STATUSRESPONSE']._serialized_end=145 - _globals['_STATUSFLAGS']._serialized_start=148 - _globals['_STATUSFLAGS']._serialized_end=437 - _globals['_STATUS']._serialized_start=440 - _globals['_STATUS']._serialized_end=643 - _globals['_RELAXREQUEST']._serialized_start=645 - _globals['_RELAXREQUEST']._serialized_end=677 - _globals['_RELAXRESPONSE']._serialized_start=679 - _globals['_RELAXRESPONSE']._serialized_end=747 - _globals['_RELATIVELENGTHCONTROLREQUEST']._serialized_start=749 - _globals['_RELATIVELENGTHCONTROLREQUEST']._serialized_end=842 - _globals['_RELATIVELENGTHCONTROLRESPONSE']._serialized_start=844 - _globals['_RELATIVELENGTHCONTROLRESPONSE']._serialized_end=928 - _globals['_RATECONTROLREQUEST']._serialized_start=930 - _globals['_RATECONTROLREQUEST']._serialized_end=986 - _globals['_RATECONTROLRESPONSE']._serialized_start=988 - _globals['_RATECONTROLRESPONSE']._serialized_end=1062 - _globals['_LOCKREQUEST']._serialized_start=1064 - _globals['_LOCKREQUEST']._serialized_end=1095 - _globals['_LOCKRESPONSE']._serialized_start=1097 - _globals['_LOCKRESPONSE']._serialized_end=1164 - _globals['_DELIVERREQUEST']._serialized_start=1166 - _globals['_DELIVERREQUEST']._serialized_end=1200 - _globals['_DELIVERRESPONSE']._serialized_start=1202 - _globals['_DELIVERRESPONSE']._serialized_end=1272 - _globals['_HOLDREQUEST']._serialized_start=1274 - _globals['_HOLDREQUEST']._serialized_end=1305 - _globals['_HOLDRESPONSE']._serialized_start=1307 - _globals['_HOLDRESPONSE']._serialized_end=1374 - _globals['_RETRACTREQUEST']._serialized_start=1376 - _globals['_RETRACTREQUEST']._serialized_end=1410 - _globals['_RETRACTRESPONSE']._serialized_start=1412 - _globals['_RETRACTRESPONSE']._serialized_end=1482 - _globals['_LOADLINEREQUEST']._serialized_start=1484 - _globals['_LOADLINEREQUEST']._serialized_end=1519 - _globals['_LOADLINERESPONSE']._serialized_start=1521 - _globals['_LOADLINERESPONSE']._serialized_end=1592 - _globals['_ABANDONLINEREQUEST']._serialized_start=1594 - _globals['_ABANDONLINEREQUEST']._serialized_end=1632 - _globals['_ABANDONLINERESPONSE']._serialized_start=1634 - _globals['_ABANDONLINERESPONSE']._serialized_end=1708 - _globals['_LOADPAYLOADREQUEST']._serialized_start=1710 - _globals['_LOADPAYLOADREQUEST']._serialized_end=1748 - _globals['_LOADPAYLOADRESPONSE']._serialized_start=1750 - _globals['_LOADPAYLOADRESPONSE']._serialized_end=1824 - _globals['_WINCHRESULT']._serialized_start=1827 - _globals['_WINCHRESULT']._serialized_end=2067 - _globals['_WINCHRESULT_RESULT']._serialized_start=1917 - _globals['_WINCHRESULT_RESULT']._serialized_end=2067 - _globals['_WINCHSERVICE']._serialized_start=2373 - _globals['_WINCHSERVICE']._serialized_end=3363 + _globals["DESCRIPTOR"]._loaded_options = None + _globals["DESCRIPTOR"]._serialized_options = b"\n\017io.mavsdk.winchB\nWinchProto" + _globals["_RELATIVELENGTHCONTROLREQUEST"].fields_by_name[ + "rate_m_s" + ]._loaded_options = None + _globals["_RELATIVELENGTHCONTROLREQUEST"].fields_by_name[ + "rate_m_s" + ]._serialized_options = b"\202\265\030\003NaN" + _globals["_WINCHACTION"]._serialized_start = 2070 + _globals["_WINCHACTION"]._serialized_end = 2370 + _globals["_SUBSCRIBESTATUSREQUEST"]._serialized_start = 61 + _globals["_SUBSCRIBESTATUSREQUEST"]._serialized_end = 85 + _globals["_STATUSRESPONSE"]._serialized_start = 87 + _globals["_STATUSRESPONSE"]._serialized_end = 145 + _globals["_STATUSFLAGS"]._serialized_start = 148 + _globals["_STATUSFLAGS"]._serialized_end = 437 + _globals["_STATUS"]._serialized_start = 440 + _globals["_STATUS"]._serialized_end = 643 + _globals["_RELAXREQUEST"]._serialized_start = 645 + _globals["_RELAXREQUEST"]._serialized_end = 677 + _globals["_RELAXRESPONSE"]._serialized_start = 679 + _globals["_RELAXRESPONSE"]._serialized_end = 747 + _globals["_RELATIVELENGTHCONTROLREQUEST"]._serialized_start = 749 + _globals["_RELATIVELENGTHCONTROLREQUEST"]._serialized_end = 842 + _globals["_RELATIVELENGTHCONTROLRESPONSE"]._serialized_start = 844 + _globals["_RELATIVELENGTHCONTROLRESPONSE"]._serialized_end = 928 + _globals["_RATECONTROLREQUEST"]._serialized_start = 930 + _globals["_RATECONTROLREQUEST"]._serialized_end = 986 + _globals["_RATECONTROLRESPONSE"]._serialized_start = 988 + _globals["_RATECONTROLRESPONSE"]._serialized_end = 1062 + _globals["_LOCKREQUEST"]._serialized_start = 1064 + _globals["_LOCKREQUEST"]._serialized_end = 1095 + _globals["_LOCKRESPONSE"]._serialized_start = 1097 + _globals["_LOCKRESPONSE"]._serialized_end = 1164 + _globals["_DELIVERREQUEST"]._serialized_start = 1166 + _globals["_DELIVERREQUEST"]._serialized_end = 1200 + _globals["_DELIVERRESPONSE"]._serialized_start = 1202 + _globals["_DELIVERRESPONSE"]._serialized_end = 1272 + _globals["_HOLDREQUEST"]._serialized_start = 1274 + _globals["_HOLDREQUEST"]._serialized_end = 1305 + _globals["_HOLDRESPONSE"]._serialized_start = 1307 + _globals["_HOLDRESPONSE"]._serialized_end = 1374 + _globals["_RETRACTREQUEST"]._serialized_start = 1376 + _globals["_RETRACTREQUEST"]._serialized_end = 1410 + _globals["_RETRACTRESPONSE"]._serialized_start = 1412 + _globals["_RETRACTRESPONSE"]._serialized_end = 1482 + _globals["_LOADLINEREQUEST"]._serialized_start = 1484 + _globals["_LOADLINEREQUEST"]._serialized_end = 1519 + _globals["_LOADLINERESPONSE"]._serialized_start = 1521 + _globals["_LOADLINERESPONSE"]._serialized_end = 1592 + _globals["_ABANDONLINEREQUEST"]._serialized_start = 1594 + _globals["_ABANDONLINEREQUEST"]._serialized_end = 1632 + _globals["_ABANDONLINERESPONSE"]._serialized_start = 1634 + _globals["_ABANDONLINERESPONSE"]._serialized_end = 1708 + _globals["_LOADPAYLOADREQUEST"]._serialized_start = 1710 + _globals["_LOADPAYLOADREQUEST"]._serialized_end = 1748 + _globals["_LOADPAYLOADRESPONSE"]._serialized_start = 1750 + _globals["_LOADPAYLOADRESPONSE"]._serialized_end = 1824 + _globals["_WINCHRESULT"]._serialized_start = 1827 + _globals["_WINCHRESULT"]._serialized_end = 2067 + _globals["_WINCHRESULT_RESULT"]._serialized_start = 1917 + _globals["_WINCHRESULT_RESULT"]._serialized_end = 2067 + _globals["_WINCHSERVICE"]._serialized_start = 2373 + _globals["_WINCHSERVICE"]._serialized_end = 3363 # @@protoc_insertion_point(module_scope) diff --git a/mavsdk/winch_pb2_grpc.py b/mavsdk/winch_pb2_grpc.py index 03bc894b..36e4ba73 100644 --- a/mavsdk/winch_pb2_grpc.py +++ b/mavsdk/winch_pb2_grpc.py @@ -1,27 +1,31 @@ # Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! """Client and server classes corresponding to protobuf-defined services.""" + import grpc import warnings from . import winch_pb2 as winch_dot_winch__pb2 -GRPC_GENERATED_VERSION = '1.71.0' +GRPC_GENERATED_VERSION = "1.71.0" GRPC_VERSION = grpc.__version__ _version_not_supported = False try: from grpc._utilities import first_version_is_lower - _version_not_supported = first_version_is_lower(GRPC_VERSION, GRPC_GENERATED_VERSION) + + _version_not_supported = first_version_is_lower( + GRPC_VERSION, GRPC_GENERATED_VERSION + ) except ImportError: _version_not_supported = True if _version_not_supported: raise RuntimeError( - f'The grpc package installed is at version {GRPC_VERSION},' - + f' but the generated code in winch/winch_pb2_grpc.py depends on' - + f' grpcio>={GRPC_GENERATED_VERSION}.' - + f' Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}' - + f' or downgrade your generated code using grpcio-tools<={GRPC_VERSION}.' + f"The grpc package installed is at version {GRPC_VERSION}," + + f" but the generated code in winch/winch_pb2_grpc.py depends on" + + f" grpcio>={GRPC_GENERATED_VERSION}." + + f" Please upgrade your grpc module to grpcio>={GRPC_GENERATED_VERSION}" + + f" or downgrade your generated code using grpcio-tools<={GRPC_VERSION}." ) @@ -38,60 +42,71 @@ def __init__(self, channel): channel: A grpc.Channel. """ self.SubscribeStatus = channel.unary_stream( - '/mavsdk.rpc.winch.WinchService/SubscribeStatus', - request_serializer=winch_dot_winch__pb2.SubscribeStatusRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.StatusResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/SubscribeStatus", + request_serializer=winch_dot_winch__pb2.SubscribeStatusRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.StatusResponse.FromString, + _registered_method=True, + ) self.Relax = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/Relax', - request_serializer=winch_dot_winch__pb2.RelaxRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.RelaxResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/Relax", + request_serializer=winch_dot_winch__pb2.RelaxRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.RelaxResponse.FromString, + _registered_method=True, + ) self.RelativeLengthControl = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/RelativeLengthControl', - request_serializer=winch_dot_winch__pb2.RelativeLengthControlRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.RelativeLengthControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/RelativeLengthControl", + request_serializer=winch_dot_winch__pb2.RelativeLengthControlRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.RelativeLengthControlResponse.FromString, + _registered_method=True, + ) self.RateControl = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/RateControl', - request_serializer=winch_dot_winch__pb2.RateControlRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.RateControlResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/RateControl", + request_serializer=winch_dot_winch__pb2.RateControlRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.RateControlResponse.FromString, + _registered_method=True, + ) self.Lock = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/Lock', - request_serializer=winch_dot_winch__pb2.LockRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.LockResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/Lock", + request_serializer=winch_dot_winch__pb2.LockRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.LockResponse.FromString, + _registered_method=True, + ) self.Deliver = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/Deliver', - request_serializer=winch_dot_winch__pb2.DeliverRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.DeliverResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/Deliver", + request_serializer=winch_dot_winch__pb2.DeliverRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.DeliverResponse.FromString, + _registered_method=True, + ) self.Hold = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/Hold', - request_serializer=winch_dot_winch__pb2.HoldRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.HoldResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/Hold", + request_serializer=winch_dot_winch__pb2.HoldRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.HoldResponse.FromString, + _registered_method=True, + ) self.Retract = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/Retract', - request_serializer=winch_dot_winch__pb2.RetractRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.RetractResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/Retract", + request_serializer=winch_dot_winch__pb2.RetractRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.RetractResponse.FromString, + _registered_method=True, + ) self.LoadLine = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/LoadLine', - request_serializer=winch_dot_winch__pb2.LoadLineRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.LoadLineResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/LoadLine", + request_serializer=winch_dot_winch__pb2.LoadLineRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.LoadLineResponse.FromString, + _registered_method=True, + ) self.AbandonLine = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/AbandonLine', - request_serializer=winch_dot_winch__pb2.AbandonLineRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.AbandonLineResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/AbandonLine", + request_serializer=winch_dot_winch__pb2.AbandonLineRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.AbandonLineResponse.FromString, + _registered_method=True, + ) self.LoadPayload = channel.unary_unary( - '/mavsdk.rpc.winch.WinchService/LoadPayload', - request_serializer=winch_dot_winch__pb2.LoadPayloadRequest.SerializeToString, - response_deserializer=winch_dot_winch__pb2.LoadPayloadResponse.FromString, - _registered_method=True) + "/mavsdk.rpc.winch.WinchService/LoadPayload", + request_serializer=winch_dot_winch__pb2.LoadPayloadRequest.SerializeToString, + response_deserializer=winch_dot_winch__pb2.LoadPayloadResponse.FromString, + _registered_method=True, + ) class WinchServiceServicer(object): @@ -101,67 +116,66 @@ class WinchServiceServicer(object): """ def SubscribeStatus(self, request, context): - """Subscribe to 'winch status' updates. - """ + """Subscribe to 'winch status' updates.""" context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Relax(self, request, context): """ Allow motor to freewheel. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RelativeLengthControl(self, request, context): """ Wind or unwind specified length of line, optionally using specified rate. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def RateControl(self, request, context): """ Wind or unwind line at specified rate. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Lock(self, request, context): """ Perform the locking sequence to relieve motor while in the fully retracted position. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Deliver(self, request, context): """ Sequence of drop, slow down, touch down, reel up, lock. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Hold(self, request, context): """ Engage motor and hold current position. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def Retract(self, request, context): """ Return the reel to the fully retracted position. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def LoadLine(self, request, context): """ @@ -170,91 +184,94 @@ def LoadLine(self, request, context): The winch will calculate the total loaded length and stop when the tension exceeds a threshold. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def AbandonLine(self, request, context): """ Spool out the entire length of the line. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def LoadPayload(self, request, context): """ Spools out just enough to present the hook to the user to load the payload. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') + context.set_details("Method not implemented!") + raise NotImplementedError("Method not implemented!") def add_WinchServiceServicer_to_server(servicer, server): rpc_method_handlers = { - 'SubscribeStatus': grpc.unary_stream_rpc_method_handler( - servicer.SubscribeStatus, - request_deserializer=winch_dot_winch__pb2.SubscribeStatusRequest.FromString, - response_serializer=winch_dot_winch__pb2.StatusResponse.SerializeToString, - ), - 'Relax': grpc.unary_unary_rpc_method_handler( - servicer.Relax, - request_deserializer=winch_dot_winch__pb2.RelaxRequest.FromString, - response_serializer=winch_dot_winch__pb2.RelaxResponse.SerializeToString, - ), - 'RelativeLengthControl': grpc.unary_unary_rpc_method_handler( - servicer.RelativeLengthControl, - request_deserializer=winch_dot_winch__pb2.RelativeLengthControlRequest.FromString, - response_serializer=winch_dot_winch__pb2.RelativeLengthControlResponse.SerializeToString, - ), - 'RateControl': grpc.unary_unary_rpc_method_handler( - servicer.RateControl, - request_deserializer=winch_dot_winch__pb2.RateControlRequest.FromString, - response_serializer=winch_dot_winch__pb2.RateControlResponse.SerializeToString, - ), - 'Lock': grpc.unary_unary_rpc_method_handler( - servicer.Lock, - request_deserializer=winch_dot_winch__pb2.LockRequest.FromString, - response_serializer=winch_dot_winch__pb2.LockResponse.SerializeToString, - ), - 'Deliver': grpc.unary_unary_rpc_method_handler( - servicer.Deliver, - request_deserializer=winch_dot_winch__pb2.DeliverRequest.FromString, - response_serializer=winch_dot_winch__pb2.DeliverResponse.SerializeToString, - ), - 'Hold': grpc.unary_unary_rpc_method_handler( - servicer.Hold, - request_deserializer=winch_dot_winch__pb2.HoldRequest.FromString, - response_serializer=winch_dot_winch__pb2.HoldResponse.SerializeToString, - ), - 'Retract': grpc.unary_unary_rpc_method_handler( - servicer.Retract, - request_deserializer=winch_dot_winch__pb2.RetractRequest.FromString, - response_serializer=winch_dot_winch__pb2.RetractResponse.SerializeToString, - ), - 'LoadLine': grpc.unary_unary_rpc_method_handler( - servicer.LoadLine, - request_deserializer=winch_dot_winch__pb2.LoadLineRequest.FromString, - response_serializer=winch_dot_winch__pb2.LoadLineResponse.SerializeToString, - ), - 'AbandonLine': grpc.unary_unary_rpc_method_handler( - servicer.AbandonLine, - request_deserializer=winch_dot_winch__pb2.AbandonLineRequest.FromString, - response_serializer=winch_dot_winch__pb2.AbandonLineResponse.SerializeToString, - ), - 'LoadPayload': grpc.unary_unary_rpc_method_handler( - servicer.LoadPayload, - request_deserializer=winch_dot_winch__pb2.LoadPayloadRequest.FromString, - response_serializer=winch_dot_winch__pb2.LoadPayloadResponse.SerializeToString, - ), + "SubscribeStatus": grpc.unary_stream_rpc_method_handler( + servicer.SubscribeStatus, + request_deserializer=winch_dot_winch__pb2.SubscribeStatusRequest.FromString, + response_serializer=winch_dot_winch__pb2.StatusResponse.SerializeToString, + ), + "Relax": grpc.unary_unary_rpc_method_handler( + servicer.Relax, + request_deserializer=winch_dot_winch__pb2.RelaxRequest.FromString, + response_serializer=winch_dot_winch__pb2.RelaxResponse.SerializeToString, + ), + "RelativeLengthControl": grpc.unary_unary_rpc_method_handler( + servicer.RelativeLengthControl, + request_deserializer=winch_dot_winch__pb2.RelativeLengthControlRequest.FromString, + response_serializer=winch_dot_winch__pb2.RelativeLengthControlResponse.SerializeToString, + ), + "RateControl": grpc.unary_unary_rpc_method_handler( + servicer.RateControl, + request_deserializer=winch_dot_winch__pb2.RateControlRequest.FromString, + response_serializer=winch_dot_winch__pb2.RateControlResponse.SerializeToString, + ), + "Lock": grpc.unary_unary_rpc_method_handler( + servicer.Lock, + request_deserializer=winch_dot_winch__pb2.LockRequest.FromString, + response_serializer=winch_dot_winch__pb2.LockResponse.SerializeToString, + ), + "Deliver": grpc.unary_unary_rpc_method_handler( + servicer.Deliver, + request_deserializer=winch_dot_winch__pb2.DeliverRequest.FromString, + response_serializer=winch_dot_winch__pb2.DeliverResponse.SerializeToString, + ), + "Hold": grpc.unary_unary_rpc_method_handler( + servicer.Hold, + request_deserializer=winch_dot_winch__pb2.HoldRequest.FromString, + response_serializer=winch_dot_winch__pb2.HoldResponse.SerializeToString, + ), + "Retract": grpc.unary_unary_rpc_method_handler( + servicer.Retract, + request_deserializer=winch_dot_winch__pb2.RetractRequest.FromString, + response_serializer=winch_dot_winch__pb2.RetractResponse.SerializeToString, + ), + "LoadLine": grpc.unary_unary_rpc_method_handler( + servicer.LoadLine, + request_deserializer=winch_dot_winch__pb2.LoadLineRequest.FromString, + response_serializer=winch_dot_winch__pb2.LoadLineResponse.SerializeToString, + ), + "AbandonLine": grpc.unary_unary_rpc_method_handler( + servicer.AbandonLine, + request_deserializer=winch_dot_winch__pb2.AbandonLineRequest.FromString, + response_serializer=winch_dot_winch__pb2.AbandonLineResponse.SerializeToString, + ), + "LoadPayload": grpc.unary_unary_rpc_method_handler( + servicer.LoadPayload, + request_deserializer=winch_dot_winch__pb2.LoadPayloadRequest.FromString, + response_serializer=winch_dot_winch__pb2.LoadPayloadResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( - 'mavsdk.rpc.winch.WinchService', rpc_method_handlers) + "mavsdk.rpc.winch.WinchService", rpc_method_handlers + ) server.add_generic_rpc_handlers((generic_handler,)) - server.add_registered_method_handlers('mavsdk.rpc.winch.WinchService', rpc_method_handlers) + server.add_registered_method_handlers( + "mavsdk.rpc.winch.WinchService", rpc_method_handlers + ) - # This class is part of an EXPERIMENTAL API. +# This class is part of an EXPERIMENTAL API. class WinchService(object): """ Allows users to send winch actions, as well as receive status information from winch systems. @@ -262,20 +279,22 @@ class WinchService(object): """ @staticmethod - def SubscribeStatus(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def SubscribeStatus( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_stream( request, target, - '/mavsdk.rpc.winch.WinchService/SubscribeStatus', + "/mavsdk.rpc.winch.WinchService/SubscribeStatus", winch_dot_winch__pb2.SubscribeStatusRequest.SerializeToString, winch_dot_winch__pb2.StatusResponse.FromString, options, @@ -286,23 +305,26 @@ def SubscribeStatus(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Relax(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Relax( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/Relax', + "/mavsdk.rpc.winch.WinchService/Relax", winch_dot_winch__pb2.RelaxRequest.SerializeToString, winch_dot_winch__pb2.RelaxResponse.FromString, options, @@ -313,23 +335,26 @@ def Relax(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RelativeLengthControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RelativeLengthControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/RelativeLengthControl', + "/mavsdk.rpc.winch.WinchService/RelativeLengthControl", winch_dot_winch__pb2.RelativeLengthControlRequest.SerializeToString, winch_dot_winch__pb2.RelativeLengthControlResponse.FromString, options, @@ -340,23 +365,26 @@ def RelativeLengthControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def RateControl(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def RateControl( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/RateControl', + "/mavsdk.rpc.winch.WinchService/RateControl", winch_dot_winch__pb2.RateControlRequest.SerializeToString, winch_dot_winch__pb2.RateControlResponse.FromString, options, @@ -367,23 +395,26 @@ def RateControl(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Lock(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Lock( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/Lock', + "/mavsdk.rpc.winch.WinchService/Lock", winch_dot_winch__pb2.LockRequest.SerializeToString, winch_dot_winch__pb2.LockResponse.FromString, options, @@ -394,23 +425,26 @@ def Lock(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Deliver(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Deliver( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/Deliver', + "/mavsdk.rpc.winch.WinchService/Deliver", winch_dot_winch__pb2.DeliverRequest.SerializeToString, winch_dot_winch__pb2.DeliverResponse.FromString, options, @@ -421,23 +455,26 @@ def Deliver(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Hold(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Hold( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/Hold', + "/mavsdk.rpc.winch.WinchService/Hold", winch_dot_winch__pb2.HoldRequest.SerializeToString, winch_dot_winch__pb2.HoldResponse.FromString, options, @@ -448,23 +485,26 @@ def Hold(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def Retract(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def Retract( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/Retract', + "/mavsdk.rpc.winch.WinchService/Retract", winch_dot_winch__pb2.RetractRequest.SerializeToString, winch_dot_winch__pb2.RetractResponse.FromString, options, @@ -475,23 +515,26 @@ def Retract(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def LoadLine(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def LoadLine( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/LoadLine', + "/mavsdk.rpc.winch.WinchService/LoadLine", winch_dot_winch__pb2.LoadLineRequest.SerializeToString, winch_dot_winch__pb2.LoadLineResponse.FromString, options, @@ -502,23 +545,26 @@ def LoadLine(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def AbandonLine(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def AbandonLine( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/AbandonLine', + "/mavsdk.rpc.winch.WinchService/AbandonLine", winch_dot_winch__pb2.AbandonLineRequest.SerializeToString, winch_dot_winch__pb2.AbandonLineResponse.FromString, options, @@ -529,23 +575,26 @@ def AbandonLine(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) @staticmethod - def LoadPayload(request, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): + def LoadPayload( + request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None, + ): return grpc.experimental.unary_unary( request, target, - '/mavsdk.rpc.winch.WinchService/LoadPayload', + "/mavsdk.rpc.winch.WinchService/LoadPayload", winch_dot_winch__pb2.LoadPayloadRequest.SerializeToString, winch_dot_winch__pb2.LoadPayloadResponse.FromString, options, @@ -556,4 +605,5 @@ def LoadPayload(request, wait_for_ready, timeout, metadata, - _registered_method=True) + _registered_method=True, + ) diff --git a/other/tools/run_protoc.sh b/other/tools/run_protoc.sh index edc24584..b5f1347e 100755 --- a/other/tools/run_protoc.sh +++ b/other/tools/run_protoc.sh @@ -96,4 +96,9 @@ function generate { echo "[+] Generating plugins from " generate -echo "[+] Done" +echo "[+] Generating plugins done" + +echo "[+] Formatting using ruff" +python3 -m ruff format "${GENERATED_DIR}" +echo "[+] Formatting done" + diff --git a/requirements-dev.txt b/requirements-dev.txt index 9505f24a..4e2dcde0 100644 --- a/requirements-dev.txt +++ b/requirements-dev.txt @@ -1,2 +1,3 @@ grpcio-tools>=1.40.0 protoc-gen-mavsdk>=1.2.0 +ruff>=0.12.12 diff --git a/setup.py b/setup.py index d6b1a832..cb3dfe0d 100644 --- a/setup.py +++ b/setup.py @@ -53,52 +53,57 @@ def platform_suffix(self): Trying to detect the platform to know which `mavsdk_server` executable to download """ - if platform.system() == 'Linux' and 'MAVSDK_SERVER_ARCH' in os.environ: - if os.environ['MAVSDK_SERVER_ARCH'] == "armv6l": - return 'linux-armv6-musl' - elif os.environ['MAVSDK_SERVER_ARCH'] == "armv7l": - return 'linux-armv7l-musl' - elif os.environ['MAVSDK_SERVER_ARCH'] == "aarch64": - return 'linux-arm64-musl' + if platform.system() == "Linux" and "MAVSDK_SERVER_ARCH" in os.environ: + if os.environ["MAVSDK_SERVER_ARCH"] == "armv6l": + return "linux-armv6-musl" + elif os.environ["MAVSDK_SERVER_ARCH"] == "armv7l": + return "linux-armv7l-musl" + elif os.environ["MAVSDK_SERVER_ARCH"] == "aarch64": + return "linux-arm64-musl" else: raise NotImplementedError( "Error: unknown MAVSDK_SERVER_ARCH: " - f"{os.environ['MAVSDK_SERVER_ARCH']}") + f"{os.environ['MAVSDK_SERVER_ARCH']}" + ) - elif platform.system() == 'Linux': - return 'musl_x86_64' + elif platform.system() == "Linux": + return "musl_x86_64" - elif platform.system() == 'Darwin': - if platform.processor() == 'i386': - return 'macos_x64' - elif platform.processor() == 'arm': - return 'macos_arm64' + elif platform.system() == "Darwin": + if platform.processor() == "i386": + return "macos_x64" + elif platform.processor() == "arm": + return "macos_arm64" raise NotImplementedError( - f"Error: unknown macOS processor: {platform.processor()}") - - elif platform.system() == 'Windows' and 'MAVSDK_SERVER_ARCH' in os.environ: - if os.environ['MAVSDK_SERVER_ARCH'] == "x86": - return 'win_x86' - elif os.environ['MAVSDK_SERVER_ARCH'] == "x64": - return 'win_x64' - elif os.environ['MAVSDK_SERVER_ARCH'] == "arm64": - return 'win_arm64' + f"Error: unknown macOS processor: {platform.processor()}" + ) + + elif platform.system() == "Windows" and "MAVSDK_SERVER_ARCH" in os.environ: + if os.environ["MAVSDK_SERVER_ARCH"] == "x86": + return "win_x86" + elif os.environ["MAVSDK_SERVER_ARCH"] == "x64": + return "win_x64" + elif os.environ["MAVSDK_SERVER_ARCH"] == "arm64": + return "win_arm64" else: raise NotImplementedError( "Error: unknown MAVSDK_SERVER_ARCH: " - f"{os.environ['MAVSDK_SERVER_ARCH']}") + f"{os.environ['MAVSDK_SERVER_ARCH']}" + ) - elif platform.system() == 'Windows' \ - and (platform.processor().startswith('AMD64') or - platform.processor().startswith('Intel64')): + elif platform.system() == "Windows" and ( + platform.processor().startswith("AMD64") + or platform.processor().startswith("Intel64") + ): # Fallback - return 'win_x64.exe' + return "win_x64.exe" else: raise NotImplementedError( "Error: mavsdk_server is not distributed for platform " f"{platform.system()} ({platform.processor()}) (yet)!\n\n" "You should set the 'MAVSDK_BUILD_PURE=ON' environment " - "variable and get mavsdk_server manually.") + "variable and get mavsdk_server manually." + ) @property def mavsdk_server_filepath(self): @@ -106,10 +111,10 @@ def mavsdk_server_filepath(self): The location of the downloaded `mavsdk_server` binary For Windows this needs to be a .exe file """ - if platform.system() == 'Windows': - return 'mavsdk/bin/mavsdk_server.exe' + if platform.system() == "Windows": + return "mavsdk/bin/mavsdk_server.exe" else: - return 'mavsdk/bin/mavsdk_server' + return "mavsdk/bin/mavsdk_server" @property def mavsdk_server_tag(self): @@ -125,22 +130,24 @@ def mavsdk_server_url(self): """ Build the url of the `mavsdk_server` binary """ - return "https://github.com/mavlink/MAVSDK/releases/download/" \ + return ( + "https://github.com/mavlink/MAVSDK/releases/download/" f"{self.mavsdk_server_tag}/mavsdk_server_{self.platform_suffix}" + ) def run(self): - if 'MAVSDK_BUILD_PURE' not in os.environ: + if "MAVSDK_BUILD_PURE" not in os.environ: self.download_mavsdk_server() build.run(self) def download_mavsdk_server(self): print( - f"downloading {self.mavsdk_server_url} into " - f"{self.mavsdk_server_filepath}") + f"downloading {self.mavsdk_server_url} into {self.mavsdk_server_filepath}" + ) urllib.request.urlretrieve( - self.mavsdk_server_url, - filename=self.mavsdk_server_filepath) + self.mavsdk_server_url, filename=self.mavsdk_server_filepath + ) print(f"adding execution permission to {self.mavsdk_server_filepath}") st = os.stat(self.mavsdk_server_filepath) @@ -148,8 +155,7 @@ def download_mavsdk_server(self): def version(): - process = subprocess.Popen(["git", "describe", "--tags"], - stdout=subprocess.PIPE) + process = subprocess.Popen(["git", "describe", "--tags"], stdout=subprocess.PIPE) output, _ = process.communicate() exit_code = process.wait() if exit_code != 0: @@ -169,21 +175,17 @@ def version(): url="https://github.com/mavlink/MAVSDK-Python", maintainer="Jonas Vautherin, Julian Oes", maintainer_email="jonas@auterion.com, julian.oes@auterion.com", - python_requires='>=3.7', + python_requires=">=3.7", include_package_data=True, - cmdclass={'build': custom_build}, - + cmdclass={"build": custom_build}, classifiers=[ "Development Status :: 5 - Production/Stable", "Intended Audience :: Developers", "License :: OSI Approved :: BSD License", "Programming Language :: Python :: 3.7", ], - - packages=find_packages(exclude=["other", "docs", "tests", "examples", - "proto"]), + packages=find_packages(exclude=["other", "docs", "tests", "examples", "proto"]), install_requires=parse_requirements("requirements.txt"), - project_urls={ "Bug Reports": "https://github.com/mavlink/MAVSDK-Python/issues", "Source": "https://github.com/mavlink/MAVSDK-Python/",