From 2f627b3fe6aae68de883f7f916f590ad53a5d946 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 31 Oct 2021 15:17:11 -0700 Subject: [PATCH] Update mavsdk_server version and proto submodule This adds a couple of fixes and uses mavsdk_server v0.46.1 which contains all the newly added server plugins. --- MAVSDK_SERVER_VERSION | 2 +- mavsdk/action.py | 44 +++++++-------- mavsdk/action_server.py | 28 ++++----- mavsdk/calibration.py | 16 +++--- mavsdk/camera.py | 50 ++++++++--------- mavsdk/core.py | 2 +- mavsdk/failure.py | 4 +- mavsdk/follow_me.py | 14 ++--- mavsdk/ftp.py | 26 ++++----- mavsdk/geofence.py | 10 ++-- mavsdk/gimbal.py | 16 +++--- mavsdk/info.py | 20 +++---- mavsdk/log_files.py | 10 ++-- mavsdk/manual_control.py | 8 +-- mavsdk/mission.py | 46 ++++++++++----- mavsdk/mission_pb2.py | 36 +++++++----- mavsdk/mission_raw.py | 26 ++++----- mavsdk/mission_raw_server.py | 10 ++-- mavsdk/mocap.py | 26 ++++----- mavsdk/offboard.py | 38 ++++++------- mavsdk/param.py | 16 +++--- mavsdk/param_server.py | 24 +++++--- mavsdk/param_server_pb2.py | 17 ++++-- mavsdk/server_utility.py | 4 +- mavsdk/shell.py | 4 +- mavsdk/telemetry.py | 106 +++++++++++++++++------------------ mavsdk/telemetry_server.py | 84 +++++++++++++-------------- mavsdk/tracking_server.py | 12 ++-- mavsdk/transponder.py | 6 +- mavsdk/tune.py | 6 +- proto | 2 +- 31 files changed, 376 insertions(+), 337 deletions(-) diff --git a/MAVSDK_SERVER_VERSION b/MAVSDK_SERVER_VERSION index 9052dab9..fe2725ea 100644 --- a/MAVSDK_SERVER_VERSION +++ b/MAVSDK_SERVER_VERSION @@ -1 +1 @@ -v0.44.0 +v0.46.1 diff --git a/mavsdk/action.py b/mavsdk/action.py index c96b95cb..26c80b03 100644 --- a/mavsdk/action.py +++ b/mavsdk/action.py @@ -206,7 +206,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActionResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -308,7 +308,7 @@ async def arm(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "arm()") @@ -331,7 +331,7 @@ async def disarm(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "disarm()") @@ -356,7 +356,7 @@ async def takeoff(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "takeoff()") @@ -378,7 +378,7 @@ async def land(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "land()") @@ -400,7 +400,7 @@ async def reboot(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "reboot()") @@ -424,7 +424,7 @@ async def shutdown(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "shutdown()") @@ -446,7 +446,7 @@ async def terminate(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "terminate()") @@ -469,7 +469,7 @@ async def kill(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "kill()") @@ -493,7 +493,7 @@ async def return_to_launch(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "return_to_launch()") @@ -536,7 +536,7 @@ async def goto_location(self, latitude_deg, longitude_deg, absolute_altitude_m, result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "goto_location()", latitude_deg, longitude_deg, absolute_altitude_m, yaw_deg) @@ -587,7 +587,7 @@ async def do_orbit(self, radius_m, velocity_ms, yaw_behavior, latitude_deg, long result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "do_orbit()", radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m) @@ -613,7 +613,7 @@ async def hold(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "hold()") @@ -643,7 +643,7 @@ async def set_actuator(self, index, value): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_actuator()", index, value) @@ -667,7 +667,7 @@ async def transition_to_fixedwing(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "transition_to_fixedwing()") @@ -691,7 +691,7 @@ async def transition_to_multicopter(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "transition_to_multicopter()") @@ -716,7 +716,7 @@ async def get_takeoff_altitude(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "get_takeoff_altitude()") @@ -745,7 +745,7 @@ async def set_takeoff_altitude(self, altitude): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_takeoff_altitude()", altitude) @@ -770,7 +770,7 @@ async def get_maximum_speed(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "get_maximum_speed()") @@ -799,7 +799,7 @@ async def set_maximum_speed(self, speed): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_maximum_speed()", speed) @@ -824,7 +824,7 @@ async def get_return_to_launch_altitude(self): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "get_return_to_launch_altitude()") @@ -853,6 +853,6 @@ async def set_return_to_launch_altitude(self, relative_altitude_m): result = self._extract_result(response) - if result.result is not ActionResult.Result.SUCCESS: + if result.result != ActionResult.Result.SUCCESS: raise ActionError(result, "set_return_to_launch_altitude()", relative_altitude_m) \ No newline at end of file diff --git a/mavsdk/action_server.py b/mavsdk/action_server.py index d4871c1c..8b269661 100644 --- a/mavsdk/action_server.py +++ b/mavsdk/action_server.py @@ -171,7 +171,7 @@ def __init__( self.can_guided_mode = can_guided_mode self.can_stabilize_mode = can_stabilize_mode - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AllowableFlightModes are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -256,7 +256,7 @@ def __init__( self.arm = arm self.force = force - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ArmDisarm are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -454,7 +454,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActionServerResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -566,7 +566,7 @@ async def arm_disarm(self): if result.result not in success_codes: raise ActionServerError(result, "arm_disarm()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: arm_disarm_stream.cancel(); return @@ -605,7 +605,7 @@ async def flight_mode_change(self): if result.result not in success_codes: raise ActionServerError(result, "flight_mode_change()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: flight_mode_change_stream.cancel(); return @@ -644,7 +644,7 @@ async def takeoff(self): if result.result not in success_codes: raise ActionServerError(result, "takeoff()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: takeoff_stream.cancel(); return @@ -683,7 +683,7 @@ async def land(self): if result.result not in success_codes: raise ActionServerError(result, "land()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: land_stream.cancel(); return @@ -722,7 +722,7 @@ async def reboot(self): if result.result not in success_codes: raise ActionServerError(result, "reboot()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: reboot_stream.cancel(); return @@ -761,7 +761,7 @@ async def shutdown(self): if result.result not in success_codes: raise ActionServerError(result, "shutdown()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: shutdown_stream.cancel(); return @@ -800,7 +800,7 @@ async def terminate(self): if result.result not in success_codes: raise ActionServerError(result, "terminate()") - if result.result is ActionServerResult.Result.SUCCESS: + if result.result == ActionServerResult.Result.SUCCESS: terminate_stream.cancel(); return @@ -832,7 +832,7 @@ async def set_allow_takeoff(self, allow_takeoff): result = self._extract_result(response) - if result.result is not ActionServerResult.Result.SUCCESS: + if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_allow_takeoff()", allow_takeoff) @@ -862,7 +862,7 @@ async def set_armable(self, armable, force_armable): result = self._extract_result(response) - if result.result is not ActionServerResult.Result.SUCCESS: + if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_armable()", armable, force_armable) @@ -892,7 +892,7 @@ async def set_disarmable(self, disarmable, force_disarmable): result = self._extract_result(response) - if result.result is not ActionServerResult.Result.SUCCESS: + if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_disarmable()", disarmable, force_disarmable) @@ -920,7 +920,7 @@ async def set_allowable_flight_modes(self, flight_modes): result = self._extract_result(response) - if result.result is not ActionServerResult.Result.SUCCESS: + if result.result != ActionServerResult.Result.SUCCESS: raise ActionServerError(result, "set_allowable_flight_modes()", flight_modes) diff --git a/mavsdk/calibration.py b/mavsdk/calibration.py index 76607009..bc4abf3b 100644 --- a/mavsdk/calibration.py +++ b/mavsdk/calibration.py @@ -138,7 +138,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two CalibrationResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -224,7 +224,7 @@ def __init__( self.has_status_text = has_status_text self.status_text = status_text - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ProgressData are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -359,7 +359,7 @@ async def calibrate_gyro(self): if result.result not in success_codes: raise CalibrationError(result, "calibrate_gyro()") - if result.result is CalibrationResult.Result.SUCCESS: + if result.result == CalibrationResult.Result.SUCCESS: calibrate_gyro_stream.cancel(); return @@ -399,7 +399,7 @@ async def calibrate_accelerometer(self): if result.result not in success_codes: raise CalibrationError(result, "calibrate_accelerometer()") - if result.result is CalibrationResult.Result.SUCCESS: + if result.result == CalibrationResult.Result.SUCCESS: calibrate_accelerometer_stream.cancel(); return @@ -439,7 +439,7 @@ async def calibrate_magnetometer(self): if result.result not in success_codes: raise CalibrationError(result, "calibrate_magnetometer()") - if result.result is CalibrationResult.Result.SUCCESS: + if result.result == CalibrationResult.Result.SUCCESS: calibrate_magnetometer_stream.cancel(); return @@ -479,7 +479,7 @@ async def calibrate_level_horizon(self): if result.result not in success_codes: raise CalibrationError(result, "calibrate_level_horizon()") - if result.result is CalibrationResult.Result.SUCCESS: + if result.result == CalibrationResult.Result.SUCCESS: calibrate_level_horizon_stream.cancel(); return @@ -519,7 +519,7 @@ async def calibrate_gimbal_accelerometer(self): if result.result not in success_codes: raise CalibrationError(result, "calibrate_gimbal_accelerometer()") - if result.result is CalibrationResult.Result.SUCCESS: + if result.result == CalibrationResult.Result.SUCCESS: calibrate_gimbal_accelerometer_stream.cancel(); return @@ -545,6 +545,6 @@ async def cancel(self): result = self._extract_result(response) - if result.result is not CalibrationResult.Result.SUCCESS: + if result.result != CalibrationResult.Result.SUCCESS: raise CalibrationError(result, "cancel()") \ No newline at end of file diff --git a/mavsdk/camera.py b/mavsdk/camera.py index 907ce890..05cdfaee 100644 --- a/mavsdk/camera.py +++ b/mavsdk/camera.py @@ -202,7 +202,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two CameraResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -286,7 +286,7 @@ def __init__( self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Position are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -399,7 +399,7 @@ def __init__( self.y = y self.z = z - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Quaternion are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -505,7 +505,7 @@ def __init__( self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two EulerAngle are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -615,7 +615,7 @@ def __init__( self.index = index self.file_url = file_url - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two CaptureInfo are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -769,7 +769,7 @@ def __init__( self.uri = uri self.horizontal_fov_deg = horizontal_fov_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VideoStreamSettings are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -983,7 +983,7 @@ def __init__( self.status = status self.spectrum = spectrum - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VideoStreamInfo are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1150,7 +1150,7 @@ def __init__( self.media_folder_name = media_folder_name self.storage_status = storage_status - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Status are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1290,7 +1290,7 @@ def __init__( self.option_id = option_id self.option_description = option_description - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Option are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1374,7 +1374,7 @@ def __init__( self.option = option self.is_range = is_range - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Setting are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1480,7 +1480,7 @@ def __init__( self.options = options self.is_range = is_range - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two SettingOptions are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1608,7 +1608,7 @@ def __init__( self.horizontal_resolution_px = horizontal_resolution_px self.vertical_resolution_px = vertical_resolution_px - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Information are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1768,7 +1768,7 @@ async def prepare(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "prepare()") @@ -1788,7 +1788,7 @@ async def take_photo(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "take_photo()") @@ -1814,7 +1814,7 @@ async def start_photo_interval(self, interval_s): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "start_photo_interval()", interval_s) @@ -1834,7 +1834,7 @@ async def stop_photo_interval(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "stop_photo_interval()") @@ -1854,7 +1854,7 @@ async def start_video(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "start_video()") @@ -1874,7 +1874,7 @@ async def stop_video(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "stop_video()") @@ -1894,7 +1894,7 @@ async def start_video_streaming(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "start_video_streaming()") @@ -1914,7 +1914,7 @@ async def stop_video_streaming(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "stop_video_streaming()") @@ -1943,7 +1943,7 @@ async def set_mode(self, mode): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "set_mode()", mode) @@ -1979,7 +1979,7 @@ async def list_photos(self, photos_range): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "list_photos()", photos_range) @@ -2185,7 +2185,7 @@ async def set_setting(self, setting): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "set_setting()", setting) @@ -2223,7 +2223,7 @@ async def get_setting(self, setting): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "get_setting()", setting) @@ -2248,6 +2248,6 @@ async def format_storage(self): result = self._extract_result(response) - if result.result is not CameraResult.Result.SUCCESS: + if result.result != CameraResult.Result.SUCCESS: raise CameraError(result, "format_storage()") \ No newline at end of file diff --git a/mavsdk/core.py b/mavsdk/core.py index 841ed3cb..7a2e2cec 100644 --- a/mavsdk/core.py +++ b/mavsdk/core.py @@ -25,7 +25,7 @@ def __init__( """ Initializes the ConnectionState object """ self.is_connected = is_connected - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ConnectionState are the same """ try: # Try to compare - this likely fails when it is compared to a non diff --git a/mavsdk/failure.py b/mavsdk/failure.py index 9a6d83da..6b7da425 100644 --- a/mavsdk/failure.py +++ b/mavsdk/failure.py @@ -338,7 +338,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FailureResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -457,6 +457,6 @@ async def inject(self, failure_unit, failure_type, instance): result = self._extract_result(response) - if result.result is not FailureResult.Result.SUCCESS: + 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/follow_me.py b/mavsdk/follow_me.py index c01d993c..58d5337f 100644 --- a/mavsdk/follow_me.py +++ b/mavsdk/follow_me.py @@ -100,7 +100,7 @@ def __init__( self.follow_direction = follow_direction self.responsiveness = responsiveness - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Config are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -216,7 +216,7 @@ def __init__( self.velocity_y_m_s = velocity_y_m_s self.velocity_z_m_s = velocity_z_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TargetLocation are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -426,7 +426,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FollowMeResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -555,7 +555,7 @@ async def set_config(self, config): result = self._extract_result(response) - if result.result is not FollowMeResult.Result.SUCCESS: + if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "set_config()", config) @@ -604,7 +604,7 @@ async def set_target_location(self, location): result = self._extract_result(response) - if result.result is not FollowMeResult.Result.SUCCESS: + if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "set_target_location()", location) @@ -644,7 +644,7 @@ async def start(self): result = self._extract_result(response) - if result.result is not FollowMeResult.Result.SUCCESS: + if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "start()") @@ -664,6 +664,6 @@ async def stop(self): result = self._extract_result(response) - if result.result is not FollowMeResult.Result.SUCCESS: + if result.result != FollowMeResult.Result.SUCCESS: raise FollowMeError(result, "stop()") \ No newline at end of file diff --git a/mavsdk/ftp.py b/mavsdk/ftp.py index 251afce4..16d8eb8c 100644 --- a/mavsdk/ftp.py +++ b/mavsdk/ftp.py @@ -30,7 +30,7 @@ def __init__( self.bytes_transferred = bytes_transferred self.total_bytes = total_bytes - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ProgressData are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -228,7 +228,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FtpResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -327,7 +327,7 @@ async def reset(self): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "reset()") @@ -371,7 +371,7 @@ async def download(self, remote_file_path, local_dir): if result.result not in success_codes: raise FtpError(result, "download()", remote_file_path, local_dir) - if result.result is FtpResult.Result.SUCCESS: + if result.result == FtpResult.Result.SUCCESS: download_stream.cancel(); return @@ -421,7 +421,7 @@ async def upload(self, local_file_path, remote_dir): if result.result not in success_codes: raise FtpError(result, "upload()", local_file_path, remote_dir) - if result.result is FtpResult.Result.SUCCESS: + if result.result == FtpResult.Result.SUCCESS: upload_stream.cancel(); return @@ -461,7 +461,7 @@ async def list_directory(self, remote_dir): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "list_directory()", remote_dir) @@ -490,7 +490,7 @@ async def create_directory(self, remote_dir): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "create_directory()", remote_dir) @@ -516,7 +516,7 @@ async def remove_directory(self, remote_dir): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "remove_directory()", remote_dir) @@ -542,7 +542,7 @@ async def remove_file(self, remote_file_path): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "remove_file()", remote_file_path) @@ -572,7 +572,7 @@ async def rename(self, remote_from_path, remote_to_path): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "rename()", remote_from_path, remote_to_path) @@ -613,7 +613,7 @@ async def are_files_identical(self, local_file_path, remote_file_path): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "are_files_identical()", local_file_path, remote_file_path) @@ -642,7 +642,7 @@ async def set_root_directory(self, root_dir): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "set_root_directory()", root_dir) @@ -668,7 +668,7 @@ async def set_target_compid(self, compid): result = self._extract_result(response) - if result.result is not FtpResult.Result.SUCCESS: + if result.result != FtpResult.Result.SUCCESS: raise FtpError(result, "set_target_compid()", compid) diff --git a/mavsdk/geofence.py b/mavsdk/geofence.py index 38e02e35..67a874a7 100644 --- a/mavsdk/geofence.py +++ b/mavsdk/geofence.py @@ -30,7 +30,7 @@ def __init__( self.latitude_deg = latitude_deg self.longitude_deg = longitude_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Point are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -140,7 +140,7 @@ def __init__( self.points = points self.fence_type = fence_type - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Polygon are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -305,7 +305,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GeofenceResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -423,7 +423,7 @@ async def upload_geofence(self, polygons): result = self._extract_result(response) - if result.result is not GeofenceResult.Result.SUCCESS: + if result.result != GeofenceResult.Result.SUCCESS: raise GeofenceError(result, "upload_geofence()", polygons) @@ -443,6 +443,6 @@ async def clear_geofence(self): result = self._extract_result(response) - if result.result is not GeofenceResult.Result.SUCCESS: + if result.result != GeofenceResult.Result.SUCCESS: raise GeofenceError(result, "clear_geofence()") \ No newline at end of file diff --git a/mavsdk/gimbal.py b/mavsdk/gimbal.py index a380d313..5a99c889 100644 --- a/mavsdk/gimbal.py +++ b/mavsdk/gimbal.py @@ -125,7 +125,7 @@ def __init__( self.sysid_secondary_control = sysid_secondary_control self.compid_secondary_control = compid_secondary_control - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ControlStatus are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -300,7 +300,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GimbalResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -413,7 +413,7 @@ async def set_pitch_and_yaw(self, pitch_deg, yaw_deg): result = self._extract_result(response) - if result.result is not GimbalResult.Result.SUCCESS: + if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "set_pitch_and_yaw()", pitch_deg, yaw_deg) @@ -447,7 +447,7 @@ async def set_pitch_rate_and_yaw_rate(self, pitch_rate_deg_s, yaw_rate_deg_s): result = self._extract_result(response) - if result.result is not GimbalResult.Result.SUCCESS: + if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "set_pitch_rate_and_yaw_rate()", pitch_rate_deg_s, yaw_rate_deg_s) @@ -480,7 +480,7 @@ async def set_mode(self, gimbal_mode): result = self._extract_result(response) - if result.result is not GimbalResult.Result.SUCCESS: + if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "set_mode()", gimbal_mode) @@ -520,7 +520,7 @@ async def set_roi_location(self, latitude_deg, longitude_deg, altitude_m): result = self._extract_result(response) - if result.result is not GimbalResult.Result.SUCCESS: + if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "set_roi_location()", latitude_deg, longitude_deg, altitude_m) @@ -557,7 +557,7 @@ async def take_control(self, control_mode): result = self._extract_result(response) - if result.result is not GimbalResult.Result.SUCCESS: + if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "take_control()", control_mode) @@ -579,7 +579,7 @@ async def release_control(self): result = self._extract_result(response) - if result.result is not GimbalResult.Result.SUCCESS: + if result.result != GimbalResult.Result.SUCCESS: raise GimbalError(result, "release_control()") diff --git a/mavsdk/info.py b/mavsdk/info.py index f2cd6e8d..eea05466 100644 --- a/mavsdk/info.py +++ b/mavsdk/info.py @@ -30,7 +30,7 @@ def __init__( self.time_boot_ms = time_boot_ms self.flight_uid = flight_uid - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FlightInfo are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -104,7 +104,7 @@ def __init__( self.hardware_uid = hardware_uid self.legacy_uid = legacy_uid - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Identification are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -188,7 +188,7 @@ def __init__( self.product_id = product_id self.product_name = product_name - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Product are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -329,7 +329,7 @@ def __init__( self.flight_sw_git_hash = flight_sw_git_hash self.os_sw_git_hash = os_sw_git_hash - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Version are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -554,7 +554,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two InfoResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -658,7 +658,7 @@ async def get_flight_information(self): result = self._extract_result(response) - if result.result is not InfoResult.Result.SUCCESS: + if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_flight_information()") @@ -686,7 +686,7 @@ async def get_identification(self): result = self._extract_result(response) - if result.result is not InfoResult.Result.SUCCESS: + if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_identification()") @@ -714,7 +714,7 @@ async def get_product(self): result = self._extract_result(response) - if result.result is not InfoResult.Result.SUCCESS: + if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_product()") @@ -742,7 +742,7 @@ async def get_version(self): result = self._extract_result(response) - if result.result is not InfoResult.Result.SUCCESS: + if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_version()") @@ -770,7 +770,7 @@ async def get_speed_factor(self): result = self._extract_result(response) - if result.result is not InfoResult.Result.SUCCESS: + if result.result != InfoResult.Result.SUCCESS: raise InfoError(result, "get_speed_factor()") diff --git a/mavsdk/log_files.py b/mavsdk/log_files.py index 0920b6d4..8ef3117a 100644 --- a/mavsdk/log_files.py +++ b/mavsdk/log_files.py @@ -25,7 +25,7 @@ def __init__( """ Initializes the ProgressData object """ self.progress = progress - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ProgressData are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -93,7 +93,7 @@ def __init__( self.date = date self.size_bytes = size_bytes - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Entry are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -262,7 +262,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two LogFilesResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -367,7 +367,7 @@ async def get_entries(self): result = self._extract_result(response) - if result.result is not LogFilesResult.Result.SUCCESS: + if result.result != LogFilesResult.Result.SUCCESS: raise LogFilesError(result, "get_entries()") @@ -421,7 +421,7 @@ async def download_log_file(self, entry, path): if result.result not in success_codes: raise LogFilesError(result, "download_log_file()", entry, path) - if result.result is LogFilesResult.Result.SUCCESS: + if result.result == LogFilesResult.Result.SUCCESS: download_log_file_stream.cancel(); return diff --git a/mavsdk/manual_control.py b/mavsdk/manual_control.py index eb8c3883..577bfbcb 100644 --- a/mavsdk/manual_control.py +++ b/mavsdk/manual_control.py @@ -122,7 +122,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ManualControlResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -224,7 +224,7 @@ async def start_position_control(self): result = self._extract_result(response) - if result.result is not ManualControlResult.Result.SUCCESS: + if result.result != ManualControlResult.Result.SUCCESS: raise ManualControlError(result, "start_position_control()") @@ -247,7 +247,7 @@ async def start_altitude_control(self): result = self._extract_result(response) - if result.result is not ManualControlResult.Result.SUCCESS: + if result.result != ManualControlResult.Result.SUCCESS: raise ManualControlError(result, "start_altitude_control()") @@ -288,6 +288,6 @@ async def set_manual_control_input(self, x, y, z, r): result = self._extract_result(response) - if result.result is not ManualControlResult.Result.SUCCESS: + 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/mission.py b/mavsdk/mission.py index f2feda1b..136db7e1 100644 --- a/mavsdk/mission.py +++ b/mavsdk/mission.py @@ -81,6 +81,12 @@ class CameraAction(Enum): STOP_VIDEO Stop capturing video + START_PHOTO_DISTANCE + Start capturing photos at regular distance + + STOP_PHOTO_DISTANCE + Stop capturing photos at regular distance + """ @@ -90,6 +96,8 @@ class CameraAction(Enum): STOP_PHOTO_INTERVAL = 3 START_VIDEO = 4 STOP_VIDEO = 5 + START_PHOTO_DISTANCE = 6 + STOP_PHOTO_DISTANCE = 7 def translate_to_rpc(self): if self == MissionItem.CameraAction.NONE: @@ -104,6 +112,10 @@ def translate_to_rpc(self): return mission_pb2.MissionItem.CAMERA_ACTION_START_VIDEO if self == MissionItem.CameraAction.STOP_VIDEO: return mission_pb2.MissionItem.CAMERA_ACTION_STOP_VIDEO + if self == MissionItem.CameraAction.START_PHOTO_DISTANCE: + return mission_pb2.MissionItem.CAMERA_ACTION_START_PHOTO_DISTANCE + if self == MissionItem.CameraAction.STOP_PHOTO_DISTANCE: + return mission_pb2.MissionItem.CAMERA_ACTION_STOP_PHOTO_DISTANCE @staticmethod def translate_from_rpc(rpc_enum_value): @@ -120,6 +132,10 @@ def translate_from_rpc(rpc_enum_value): 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: + return MissionItem.CameraAction.START_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 @@ -153,7 +169,7 @@ def __init__( self.acceptance_radius_m = acceptance_radius_m self.yaw_deg = yaw_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionItem are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -332,7 +348,7 @@ def __init__( """ Initializes the MissionPlan object """ self.mission_items = mission_items - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionPlan are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -402,7 +418,7 @@ def __init__( self.current = current self.total = total - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionProgress are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -592,7 +608,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -703,7 +719,7 @@ async def upload_mission(self, mission_plan): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "upload_mission()", mission_plan) @@ -723,7 +739,7 @@ async def cancel_mission_upload(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "cancel_mission_upload()") @@ -751,7 +767,7 @@ async def download_mission(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "download_mission()") @@ -774,7 +790,7 @@ async def cancel_mission_download(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "cancel_mission_download()") @@ -796,7 +812,7 @@ async def start_mission(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "start_mission()") @@ -821,7 +837,7 @@ async def pause_mission(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "pause_mission()") @@ -841,7 +857,7 @@ async def clear_mission(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "clear_mission()") @@ -873,7 +889,7 @@ async def set_current_mission_item(self, index): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "set_current_mission_item()", index) @@ -898,7 +914,7 @@ async def is_mission_finished(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "is_mission_finished()") @@ -953,7 +969,7 @@ async def get_return_to_launch_after_mission(self): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + if result.result != MissionResult.Result.SUCCESS: raise MissionError(result, "get_return_to_launch_after_mission()") @@ -985,6 +1001,6 @@ async def set_return_to_launch_after_mission(self, enable): result = self._extract_result(response) - if result.result is not MissionResult.Result.SUCCESS: + 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 0e8550ca..74161e03 100644 --- a/mavsdk/mission_pb2.py +++ b/mavsdk/mission_pb2.py @@ -20,7 +20,7 @@ syntax='proto3', serialized_options=b'\n\021io.mavsdk.missionB\014MissionProto', create_key=_descriptor._internal_create_key, - serialized_pb=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\"\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\"\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\"\xc3\x05\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\"\xd0\x01\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\"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\"\x99\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\"\xb9\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\r2\xcd\x0b\n\x0eMissionService\x12\x66\n\rUploadMission\x12(.mavsdk.rpc.mission.UploadMissionRequest\x1a).mavsdk.rpc.mission.UploadMissionResponse\"\x00\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\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' + serialized_pb=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\"\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\"\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\"\x92\x06\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\"\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\"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\"\x99\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\"\xb9\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\r2\xcd\x0b\n\x0eMissionService\x12\x66\n\rUploadMission\x12(.mavsdk.rpc.mission.UploadMissionRequest\x1a).mavsdk.rpc.mission.UploadMissionResponse\"\x00\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\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' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -63,11 +63,21 @@ serialized_options=None, type=None, create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CAMERA_ACTION_START_PHOTO_DISTANCE', index=6, number=6, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CAMERA_ACTION_STOP_PHOTO_DISTANCE', index=7, number=7, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), ], containing_type=None, serialized_options=None, serialized_start=2173, - serialized_end=2381, + serialized_end=2460, ) _sym_db.RegisterEnumDescriptor(_MISSIONITEM_CAMERAACTION) @@ -141,8 +151,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=2602, - serialized_end=2915, + serialized_start=2681, + serialized_end=2994, ) _sym_db.RegisterEnumDescriptor(_MISSIONRESULT_RESULT) @@ -979,7 +989,7 @@ oneofs=[ ], serialized_start=1674, - serialized_end=2381, + serialized_end=2460, ) @@ -1010,8 +1020,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=2383, - serialized_end=2452, + serialized_start=2462, + serialized_end=2531, ) @@ -1049,8 +1059,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=2454, - serialized_end=2503, + serialized_start=2533, + serialized_end=2582, ) @@ -1089,8 +1099,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=2506, - serialized_end=2915, + serialized_start=2585, + serialized_end=2994, ) _UPLOADMISSIONREQUEST.fields_by_name['mission_plan'].message_type = _MISSIONPLAN @@ -1359,8 +1369,8 @@ index=0, serialized_options=None, create_key=_descriptor._internal_create_key, - serialized_start=2918, - serialized_end=4403, + serialized_start=2997, + serialized_end=4482, methods=[ _descriptor.MethodDescriptor( name='UploadMission', diff --git a/mavsdk/mission_raw.py b/mavsdk/mission_raw.py index 35a4fc80..f5e60c46 100644 --- a/mavsdk/mission_raw.py +++ b/mavsdk/mission_raw.py @@ -30,7 +30,7 @@ def __init__( self.current = current self.total = total - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionProgress are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -159,7 +159,7 @@ def __init__( self.z = z self.mission_type = mission_type - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionItem are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -359,7 +359,7 @@ def __init__( self.geofence_items = geofence_items self.rally_items = rally_items - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionImportData are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -589,7 +589,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionRawResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -707,7 +707,7 @@ async def upload_mission(self, mission_items): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "upload_mission()", mission_items) @@ -727,7 +727,7 @@ async def cancel_mission_upload(self): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "cancel_mission_upload()") @@ -752,7 +752,7 @@ async def download_mission(self): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "download_mission()") @@ -779,7 +779,7 @@ async def cancel_mission_download(self): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "cancel_mission_download()") @@ -801,7 +801,7 @@ async def start_mission(self): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "start_mission()") @@ -826,7 +826,7 @@ async def pause_mission(self): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "pause_mission()") @@ -846,7 +846,7 @@ async def clear_mission(self): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "clear_mission()") @@ -875,7 +875,7 @@ async def set_current_mission_item(self, index): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "set_current_mission_item()", index) @@ -969,7 +969,7 @@ async def import_qgroundcontrol_mission(self, qgc_plan_path): result = self._extract_result(response) - if result.result is not MissionRawResult.Result.SUCCESS: + if result.result != MissionRawResult.Result.SUCCESS: raise MissionRawError(result, "import_qgroundcontrol_mission()", qgc_plan_path) diff --git a/mavsdk/mission_raw_server.py b/mavsdk/mission_raw_server.py index 9360fc84..0de20d11 100644 --- a/mavsdk/mission_raw_server.py +++ b/mavsdk/mission_raw_server.py @@ -85,7 +85,7 @@ def __init__( self.z = z self.mission_type = mission_type - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionItem are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -275,7 +275,7 @@ def __init__( """ Initializes the MissionPlan object """ self.mission_items = mission_items - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionPlan are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -345,7 +345,7 @@ def __init__( self.current = current self.total = total - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionProgress are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -543,7 +543,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MissionRawServerResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -657,7 +657,7 @@ async def incoming_mission(self): if result.result not in success_codes: raise MissionRawServerError(result, "incoming_mission()") - if result.result is MissionRawServerResult.Result.SUCCESS: + if result.result == MissionRawServerResult.Result.SUCCESS: incoming_mission_stream.cancel(); return diff --git a/mavsdk/mocap.py b/mavsdk/mocap.py index e3df2736..a1242495 100644 --- a/mavsdk/mocap.py +++ b/mavsdk/mocap.py @@ -35,7 +35,7 @@ def __init__( self.y_m = y_m self.z_m = z_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -125,7 +125,7 @@ def __init__( self.pitch_rad = pitch_rad self.yaw_rad = yaw_rad - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AngleBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -215,7 +215,7 @@ def __init__( self.y_m_s = y_m_s self.z_m_s = z_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two SpeedBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -305,7 +305,7 @@ def __init__( self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AngularVelocityBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -388,7 +388,7 @@ def __init__( """ Initializes the Covariance object """ self.covariance_matrix = covariance_matrix - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Covariance are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -469,7 +469,7 @@ def __init__( self.y = y self.z = z - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Quaternion are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -575,7 +575,7 @@ def __init__( self.angle_body = angle_body self.pose_covariance = pose_covariance - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VisionPositionEstimate are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -681,7 +681,7 @@ def __init__( self.position_body = position_body self.pose_covariance = pose_covariance - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AttitudePositionMocap are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -843,7 +843,7 @@ def __init__( self.pose_covariance = pose_covariance self.velocity_covariance = velocity_covariance - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Odometry are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1043,7 +1043,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MocapResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1154,7 +1154,7 @@ async def set_vision_position_estimate(self, vision_position_estimate): result = self._extract_result(response) - if result.result is not MocapResult.Result.SUCCESS: + if result.result != MocapResult.Result.SUCCESS: raise MocapError(result, "set_vision_position_estimate()", vision_position_estimate) @@ -1183,7 +1183,7 @@ async def set_attitude_position_mocap(self, attitude_position_mocap): result = self._extract_result(response) - if result.result is not MocapResult.Result.SUCCESS: + if result.result != MocapResult.Result.SUCCESS: raise MocapError(result, "set_attitude_position_mocap()", attitude_position_mocap) @@ -1212,6 +1212,6 @@ async def set_odometry(self, odometry): result = self._extract_result(response) - if result.result is not MocapResult.Result.SUCCESS: + if result.result != MocapResult.Result.SUCCESS: raise MocapError(result, "set_odometry()", odometry) \ No newline at end of file diff --git a/mavsdk/offboard.py b/mavsdk/offboard.py index 68ecc880..f2cf4220 100644 --- a/mavsdk/offboard.py +++ b/mavsdk/offboard.py @@ -40,7 +40,7 @@ def __init__( self.yaw_deg = yaw_deg self.thrust_value = thrust_value - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Attitude are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -132,7 +132,7 @@ def __init__( """ Initializes the ActuatorControlGroup object """ self.controls = controls - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActuatorControlGroup are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -205,7 +205,7 @@ def __init__( """ Initializes the ActuatorControl object """ self.groups = groups - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActuatorControl are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -285,7 +285,7 @@ def __init__( self.yaw_deg_s = yaw_deg_s self.thrust_value = thrust_value - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AttitudeRate are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -391,7 +391,7 @@ def __init__( self.down_m = down_m self.yaw_deg = yaw_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionNedYaw are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -497,7 +497,7 @@ def __init__( self.down_m_s = down_m_s self.yawspeed_deg_s = yawspeed_deg_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VelocityBodyYawspeed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -603,7 +603,7 @@ def __init__( self.down_m_s = down_m_s self.yaw_deg = yaw_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VelocityNedYaw are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -704,7 +704,7 @@ def __init__( self.east_m_s2 = east_m_s2 self.down_m_s2 = down_m_s2 - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AccelerationNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -873,7 +873,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two OffboardResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -980,7 +980,7 @@ async def start(self): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "start()") @@ -1002,7 +1002,7 @@ async def stop(self): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "stop()") @@ -1054,7 +1054,7 @@ async def set_attitude(self, attitude): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_attitude()", attitude) @@ -1086,7 +1086,7 @@ async def set_actuator_control(self, actuator_control): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_actuator_control()", actuator_control) @@ -1115,7 +1115,7 @@ async def set_attitude_rate(self, attitude_rate): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_attitude_rate()", attitude_rate) @@ -1144,7 +1144,7 @@ async def set_position_ned(self, position_ned_yaw): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_position_ned()", position_ned_yaw) @@ -1173,7 +1173,7 @@ async def set_velocity_body(self, velocity_body_yawspeed): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_velocity_body()", velocity_body_yawspeed) @@ -1202,7 +1202,7 @@ async def set_velocity_ned(self, velocity_ned_yaw): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_velocity_ned()", velocity_ned_yaw) @@ -1238,7 +1238,7 @@ async def set_position_velocity_ned(self, position_ned_yaw, velocity_ned_yaw): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_position_velocity_ned()", position_ned_yaw, velocity_ned_yaw) @@ -1267,6 +1267,6 @@ async def set_acceleration_ned(self, acceleration_ned): result = self._extract_result(response) - if result.result is not OffboardResult.Result.SUCCESS: + if result.result != OffboardResult.Result.SUCCESS: raise OffboardError(result, "set_acceleration_ned()", acceleration_ned) \ No newline at end of file diff --git a/mavsdk/param.py b/mavsdk/param.py index 7f2ef787..8730b0d8 100644 --- a/mavsdk/param.py +++ b/mavsdk/param.py @@ -30,7 +30,7 @@ def __init__( self.name = name self.value = value - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two IntParam are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -104,7 +104,7 @@ def __init__( self.name = name self.value = value - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FloatParam are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -178,7 +178,7 @@ def __init__( self.int_params = int_params self.float_params = float_params - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AllParams are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -342,7 +342,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ParamResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -457,7 +457,7 @@ async def get_param_int(self, name): result = self._extract_result(response) - if result.result is not ParamResult.Result.SUCCESS: + if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "get_param_int()", name) @@ -492,7 +492,7 @@ async def set_param_int(self, name, value): result = self._extract_result(response) - if result.result is not ParamResult.Result.SUCCESS: + if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "set_param_int()", name, value) @@ -528,7 +528,7 @@ async def get_param_float(self, name): result = self._extract_result(response) - if result.result is not ParamResult.Result.SUCCESS: + if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "get_param_float()", name) @@ -563,7 +563,7 @@ async def set_param_float(self, name, value): result = self._extract_result(response) - if result.result is not ParamResult.Result.SUCCESS: + if result.result != ParamResult.Result.SUCCESS: raise ParamError(result, "set_param_float()", name, value) diff --git a/mavsdk/param_server.py b/mavsdk/param_server.py index 8f59b4af..1b712899 100644 --- a/mavsdk/param_server.py +++ b/mavsdk/param_server.py @@ -30,7 +30,7 @@ def __init__( self.name = name self.value = value - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two IntParam are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -104,7 +104,7 @@ def __init__( self.name = name self.value = value - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FloatParam are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -178,7 +178,7 @@ def __init__( self.int_params = int_params self.float_params = float_params - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AllParams are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -279,6 +279,9 @@ class Result(Enum): PARAM_NAME_TOO_LONG Parameter name too long (> 16) + NO_SYSTEM + No system available + """ @@ -287,6 +290,7 @@ class Result(Enum): NOT_FOUND = 2 WRONG_TYPE = 3 PARAM_NAME_TOO_LONG = 4 + NO_SYSTEM = 5 def translate_to_rpc(self): if self == ParamServerResult.Result.UNKNOWN: @@ -299,6 +303,8 @@ def translate_to_rpc(self): return param_server_pb2.ParamServerResult.RESULT_WRONG_TYPE if self == ParamServerResult.Result.PARAM_NAME_TOO_LONG: return param_server_pb2.ParamServerResult.RESULT_PARAM_NAME_TOO_LONG + if self == ParamServerResult.Result.NO_SYSTEM: + return param_server_pb2.ParamServerResult.RESULT_NO_SYSTEM @staticmethod def translate_from_rpc(rpc_enum_value): @@ -313,6 +319,8 @@ def translate_from_rpc(rpc_enum_value): return ParamServerResult.Result.WRONG_TYPE 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 def __str__(self): return self.name @@ -326,7 +334,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ParamServerResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -441,7 +449,7 @@ async def retrieve_param_int(self, name): result = self._extract_result(response) - if result.result is not ParamServerResult.Result.SUCCESS: + if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "retrieve_param_int()", name) @@ -476,7 +484,7 @@ async def provide_param_int(self, name, value): result = self._extract_result(response) - if result.result is not ParamServerResult.Result.SUCCESS: + if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "provide_param_int()", name, value) @@ -512,7 +520,7 @@ async def retrieve_param_float(self, name): result = self._extract_result(response) - if result.result is not ParamServerResult.Result.SUCCESS: + if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "retrieve_param_float()", name) @@ -547,7 +555,7 @@ async def provide_param_float(self, name, value): result = self._extract_result(response) - if result.result is not ParamServerResult.Result.SUCCESS: + if result.result != ParamServerResult.Result.SUCCESS: raise ParamServerError(result, "provide_param_float()", name, value) diff --git a/mavsdk/param_server_pb2.py b/mavsdk/param_server_pb2.py index 4a4d1c63..e0bb2ea1 100644 --- a/mavsdk/param_server_pb2.py +++ b/mavsdk/param_server_pb2.py @@ -20,7 +20,7 @@ syntax='proto3', serialized_options=b'\n\026io.mavsdk.param_serverB\020ParamServerProto', create_key=_descriptor._internal_create_key, - serialized_pb=b'\n\x1fparam_server/param_server.proto\x12\x17mavsdk.rpc.param_server\x1a\x14mavsdk_options.proto\"\'\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\"\x1a\n\x18RetrieveAllParamsRequest\"O\n\x19RetrieveAllParamsResponse\x12\x32\n\x06params\x18\x01 \x01(\x0b\x32\".mavsdk.rpc.param_server.AllParams\"\'\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\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\"\xe9\x01\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\"}\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\x32\x9b\x05\n\x12ParamServerService\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\x80\x01\n\x11RetrieveAllParams\x12\x31.mavsdk.rpc.param_server.RetrieveAllParamsRequest\x1a\x32.mavsdk.rpc.param_server.RetrieveAllParamsResponse\"\x04\x80\xb5\x18\x01\x42*\n\x16io.mavsdk.param_serverB\x10ParamServerProtob\x06proto3' + serialized_pb=b'\n\x1fparam_server/param_server.proto\x12\x17mavsdk.rpc.param_server\x1a\x14mavsdk_options.proto\"\'\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\"\x1a\n\x18RetrieveAllParamsRequest\"O\n\x19RetrieveAllParamsResponse\x12\x32\n\x06params\x18\x01 \x01(\x0b\x32\".mavsdk.rpc.param_server.AllParams\"\'\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\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\"\x80\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\"\x93\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\x32\x9b\x05\n\x12ParamServerService\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\x80\x01\n\x11RetrieveAllParams\x12\x31.mavsdk.rpc.param_server.RetrieveAllParamsRequest\x1a\x32.mavsdk.rpc.param_server.RetrieveAllParamsResponse\"\x04\x80\xb5\x18\x01\x42*\n\x16io.mavsdk.param_serverB\x10ParamServerProtob\x06proto3' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -58,11 +58,16 @@ serialized_options=None, type=None, create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='RESULT_NO_SYSTEM', index=5, number=5, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), ], containing_type=None, serialized_options=None, - serialized_start=1143, - serialized_end=1268, + serialized_start=1144, + serialized_end=1291, ) _sym_db.RegisterEnumDescriptor(_PARAMSERVERRESULT_RESULT) @@ -561,7 +566,7 @@ oneofs=[ ], serialized_start=1035, - serialized_end=1268, + serialized_end=1291, ) _RETRIEVEPARAMINTRESPONSE.fields_by_name['param_server_result'].message_type = _PARAMSERVERRESULT @@ -697,8 +702,8 @@ index=0, serialized_options=None, create_key=_descriptor._internal_create_key, - serialized_start=1271, - serialized_end=1938, + serialized_start=1294, + serialized_end=1961, methods=[ _descriptor.MethodDescriptor( name='RetrieveParamInt', diff --git a/mavsdk/server_utility.py b/mavsdk/server_utility.py index eefe8028..619ded82 100644 --- a/mavsdk/server_utility.py +++ b/mavsdk/server_utility.py @@ -174,7 +174,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ServerUtilityResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -286,6 +286,6 @@ async def send_status_text(self, type, text): result = self._extract_result(response) - if result.result is not ServerUtilityResult.Result.SUCCESS: + if result.result != ServerUtilityResult.Result.SUCCESS: raise ServerUtilityError(result, "send_status_text()", type, text) \ No newline at end of file diff --git a/mavsdk/shell.py b/mavsdk/shell.py index 5d2dc7d0..c7f8886e 100644 --- a/mavsdk/shell.py +++ b/mavsdk/shell.py @@ -98,7 +98,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ShellResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -204,7 +204,7 @@ async def send(self, command): result = self._extract_result(response) - if result.result is not ShellResult.Result.SUCCESS: + if result.result != ShellResult.Result.SUCCESS: raise ShellError(result, "send()", command) diff --git a/mavsdk/telemetry.py b/mavsdk/telemetry.py index afb17b1c..b33339f1 100644 --- a/mavsdk/telemetry.py +++ b/mavsdk/telemetry.py @@ -463,7 +463,7 @@ def __init__( self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Position are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -554,7 +554,7 @@ def __init__( """ Initializes the Heading object """ self.heading_deg = heading_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Heading are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -639,7 +639,7 @@ def __init__( self.z = z self.timestamp_us = timestamp_us - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Quaternion are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -761,7 +761,7 @@ def __init__( self.yaw_deg = yaw_deg self.timestamp_us = timestamp_us - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two EulerAngle are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -862,7 +862,7 @@ def __init__( self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AngularVelocityBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -947,7 +947,7 @@ def __init__( self.num_satellites = num_satellites self.fix_type = fix_type - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GpsInfo are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1084,7 +1084,7 @@ def __init__( self.heading_uncertainty_deg = heading_uncertainty_deg self.yaw_deg = yaw_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two RawGps are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1295,7 +1295,7 @@ def __init__( self.voltage_v = voltage_v self.remaining_percent = remaining_percent - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Battery are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1405,7 +1405,7 @@ def __init__( self.is_home_position_ok = is_home_position_ok self.is_armable = is_armable - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Health are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1539,7 +1539,7 @@ def __init__( self.is_available = is_available self.signal_strength_percent = signal_strength_percent - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two RcStatus are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1624,7 +1624,7 @@ def __init__( self.type = type self.text = text - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two StatusText are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1698,7 +1698,7 @@ def __init__( self.group = group self.controls = controls - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActuatorControlTarget are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1773,7 +1773,7 @@ def __init__( self.active = active self.actuator = actuator - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActuatorOutputStatus are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1847,7 +1847,7 @@ def __init__( """ Initializes the Covariance object """ self.covariance_matrix = covariance_matrix - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Covariance are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1916,7 +1916,7 @@ def __init__( self.y_m_s = y_m_s self.z_m_s = z_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VelocityBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2006,7 +2006,7 @@ def __init__( self.y_m = y_m self.z_m = z_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2178,7 +2178,7 @@ def __init__( self.pose_covariance = pose_covariance self.velocity_covariance = velocity_covariance - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Odometry are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2334,7 +2334,7 @@ def __init__( self.maximum_distance_m = maximum_distance_m self.current_distance_m = current_distance_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two DistanceSensor are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2434,7 +2434,7 @@ def __init__( self.temperature_deg = temperature_deg self.differential_pressure_temperature_deg = differential_pressure_temperature_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ScaledPressure are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2546,7 +2546,7 @@ def __init__( self.east_m = east_m self.down_m = down_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2636,7 +2636,7 @@ def __init__( self.east_m_s = east_m_s self.down_m_s = down_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VelocityNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2721,7 +2721,7 @@ def __init__( self.position = position self.velocity = velocity - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionVelocityNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2800,7 +2800,7 @@ def __init__( self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GroundTruth are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2890,7 +2890,7 @@ def __init__( self.throttle_percentage = throttle_percentage self.climb_rate_m_s = climb_rate_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FixedwingMetrics are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2980,7 +2980,7 @@ def __init__( self.right_m_s2 = right_m_s2 self.down_m_s2 = down_m_s2 - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AccelerationFrd are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3070,7 +3070,7 @@ def __init__( self.right_rad_s = right_rad_s self.down_rad_s = down_rad_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AngularVelocityFrd are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3160,7 +3160,7 @@ def __init__( self.right_gauss = right_gauss self.down_gauss = down_gauss - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MagneticFieldFrd are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3260,7 +3260,7 @@ def __init__( self.temperature_degc = temperature_degc self.timestamp_us = timestamp_us - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Imu are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3372,7 +3372,7 @@ def __init__( self.longitude_deg = longitude_deg self.altitude_m = altitude_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GpsGlobalOrigin are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3541,7 +3541,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TelemetryResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -4439,7 +4439,7 @@ async def set_rate_position(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_position()", rate_hz) @@ -4465,7 +4465,7 @@ async def set_rate_home(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_home()", rate_hz) @@ -4491,7 +4491,7 @@ async def set_rate_in_air(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_in_air()", rate_hz) @@ -4517,7 +4517,7 @@ async def set_rate_landed_state(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_landed_state()", rate_hz) @@ -4543,7 +4543,7 @@ async def set_rate_vtol_state(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_vtol_state()", rate_hz) @@ -4569,7 +4569,7 @@ async def set_rate_attitude(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_attitude()", rate_hz) @@ -4595,7 +4595,7 @@ async def set_rate_camera_attitude(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_camera_attitude()", rate_hz) @@ -4621,7 +4621,7 @@ async def set_rate_velocity_ned(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_velocity_ned()", rate_hz) @@ -4647,7 +4647,7 @@ async def set_rate_gps_info(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_gps_info()", rate_hz) @@ -4673,7 +4673,7 @@ async def set_rate_battery(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_battery()", rate_hz) @@ -4699,7 +4699,7 @@ async def set_rate_rc_status(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_rc_status()", rate_hz) @@ -4725,7 +4725,7 @@ async def set_rate_actuator_control_target(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_actuator_control_target()", rate_hz) @@ -4751,7 +4751,7 @@ async def set_rate_actuator_output_status(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_actuator_output_status()", rate_hz) @@ -4777,7 +4777,7 @@ async def set_rate_odometry(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_odometry()", rate_hz) @@ -4803,7 +4803,7 @@ async def set_rate_position_velocity_ned(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_position_velocity_ned()", rate_hz) @@ -4829,7 +4829,7 @@ async def set_rate_ground_truth(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_ground_truth()", rate_hz) @@ -4855,7 +4855,7 @@ async def set_rate_fixedwing_metrics(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_fixedwing_metrics()", rate_hz) @@ -4881,7 +4881,7 @@ async def set_rate_imu(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_imu()", rate_hz) @@ -4907,7 +4907,7 @@ async def set_rate_scaled_imu(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_scaled_imu()", rate_hz) @@ -4933,7 +4933,7 @@ async def set_rate_raw_imu(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_raw_imu()", rate_hz) @@ -4959,7 +4959,7 @@ async def set_rate_unix_epoch_time(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_unix_epoch_time()", rate_hz) @@ -4985,7 +4985,7 @@ async def set_rate_distance_sensor(self, rate_hz): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "set_rate_distance_sensor()", rate_hz) @@ -5009,7 +5009,7 @@ async def get_gps_global_origin(self): result = self._extract_result(response) - if result.result is not TelemetryResult.Result.SUCCESS: + if result.result != TelemetryResult.Result.SUCCESS: raise TelemetryError(result, "get_gps_global_origin()") diff --git a/mavsdk/telemetry_server.py b/mavsdk/telemetry_server.py index 72c4b9ef..10101dcd 100644 --- a/mavsdk/telemetry_server.py +++ b/mavsdk/telemetry_server.py @@ -320,7 +320,7 @@ def __init__( self.absolute_altitude_m = absolute_altitude_m self.relative_altitude_m = relative_altitude_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Position are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -411,7 +411,7 @@ def __init__( """ Initializes the Heading object """ self.heading_deg = heading_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Heading are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -496,7 +496,7 @@ def __init__( self.z = z self.timestamp_us = timestamp_us - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Quaternion are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -618,7 +618,7 @@ def __init__( self.yaw_deg = yaw_deg self.timestamp_us = timestamp_us - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two EulerAngle are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -719,7 +719,7 @@ def __init__( self.pitch_rad_s = pitch_rad_s self.yaw_rad_s = yaw_rad_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AngularVelocityBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -804,7 +804,7 @@ def __init__( self.num_satellites = num_satellites self.fix_type = fix_type - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GpsInfo are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -941,7 +941,7 @@ def __init__( self.heading_uncertainty_deg = heading_uncertainty_deg self.yaw_deg = yaw_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two RawGps are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1147,7 +1147,7 @@ def __init__( self.voltage_v = voltage_v self.remaining_percent = remaining_percent - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Battery are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1226,7 +1226,7 @@ def __init__( self.is_available = is_available self.signal_strength_percent = signal_strength_percent - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two RcStatus are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1311,7 +1311,7 @@ def __init__( self.type = type self.text = text - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two StatusText are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1385,7 +1385,7 @@ def __init__( self.group = group self.controls = controls - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActuatorControlTarget are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1460,7 +1460,7 @@ def __init__( self.active = active self.actuator = actuator - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ActuatorOutputStatus are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1534,7 +1534,7 @@ def __init__( """ Initializes the Covariance object """ self.covariance_matrix = covariance_matrix - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Covariance are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1603,7 +1603,7 @@ def __init__( self.y_m_s = y_m_s self.z_m_s = z_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VelocityBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1693,7 +1693,7 @@ def __init__( self.y_m = y_m self.z_m = z_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionBody are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -1865,7 +1865,7 @@ def __init__( self.pose_covariance = pose_covariance self.velocity_covariance = velocity_covariance - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Odometry are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2021,7 +2021,7 @@ def __init__( self.maximum_distance_m = maximum_distance_m self.current_distance_m = current_distance_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two DistanceSensor are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2121,7 +2121,7 @@ def __init__( self.temperature_deg = temperature_deg self.differential_pressure_temperature_deg = differential_pressure_temperature_deg - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two ScaledPressure are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2233,7 +2233,7 @@ def __init__( self.east_m = east_m self.down_m = down_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2323,7 +2323,7 @@ def __init__( self.east_m_s = east_m_s self.down_m_s = down_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two VelocityNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2408,7 +2408,7 @@ def __init__( self.position = position self.velocity = velocity - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two PositionVelocityNed are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2487,7 +2487,7 @@ def __init__( self.longitude_deg = longitude_deg self.absolute_altitude_m = absolute_altitude_m - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two GroundTruth are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2577,7 +2577,7 @@ def __init__( self.throttle_percentage = throttle_percentage self.climb_rate_m_s = climb_rate_m_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two FixedwingMetrics are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2667,7 +2667,7 @@ def __init__( self.right_m_s2 = right_m_s2 self.down_m_s2 = down_m_s2 - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AccelerationFrd are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2757,7 +2757,7 @@ def __init__( self.right_rad_s = right_rad_s self.down_rad_s = down_rad_s - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AngularVelocityFrd are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2847,7 +2847,7 @@ def __init__( self.right_gauss = right_gauss self.down_gauss = down_gauss - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two MagneticFieldFrd are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -2947,7 +2947,7 @@ def __init__( self.temperature_degc = temperature_degc self.timestamp_us = timestamp_us - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two Imu are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3138,7 +3138,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TelemetryServerResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -3261,7 +3261,7 @@ async def publish_position(self, position, velocity_ned, heading): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_position()", position, velocity_ned, heading) @@ -3290,7 +3290,7 @@ async def publish_home(self, home): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_home()", home) @@ -3335,7 +3335,7 @@ async def publish_sys_status(self, battery, rc_receiver_status, gyro_status, acc result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_sys_status()", battery, rc_receiver_status, gyro_status, accel_status, mag_status, gps_status) @@ -3369,7 +3369,7 @@ async def publish_extended_sys_state(self, vtol_state, landed_state): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_extended_sys_state()", vtol_state, landed_state) @@ -3405,7 +3405,7 @@ async def publish_raw_gps(self, raw_gps, gps_info): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_raw_gps()", raw_gps, gps_info) @@ -3434,7 +3434,7 @@ async def publish_battery(self, battery): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_battery()", battery) @@ -3463,7 +3463,7 @@ async def publish_status_text(self, status_text): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_status_text()", status_text) @@ -3492,7 +3492,7 @@ async def publish_odometry(self, odometry): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_odometry()", odometry) @@ -3521,7 +3521,7 @@ async def publish_position_velocity_ned(self, position_velocity_ned): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_position_velocity_ned()", position_velocity_ned) @@ -3550,7 +3550,7 @@ async def publish_ground_truth(self, ground_truth): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_ground_truth()", ground_truth) @@ -3579,7 +3579,7 @@ async def publish_imu(self, imu): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_imu()", imu) @@ -3608,7 +3608,7 @@ async def publish_scaled_imu(self, imu): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_scaled_imu()", imu) @@ -3637,7 +3637,7 @@ async def publish_raw_imu(self, imu): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_raw_imu()", imu) @@ -3663,6 +3663,6 @@ async def publish_unix_epoch_time(self, time_us): result = self._extract_result(response) - if result.result is not TelemetryServerResult.Result.SUCCESS: + if result.result != TelemetryServerResult.Result.SUCCESS: raise TelemetryServerError(result, "publish_unix_epoch_time()", time_us) \ No newline at end of file diff --git a/mavsdk/tracking_server.py b/mavsdk/tracking_server.py index a28c01a9..607fabd4 100644 --- a/mavsdk/tracking_server.py +++ b/mavsdk/tracking_server.py @@ -95,7 +95,7 @@ def __init__( self.point_y = point_y self.radius = radius - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TrackPoint are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -190,7 +190,7 @@ def __init__( self.bottom_right_corner_x = bottom_right_corner_x self.bottom_right_corner_y = bottom_right_corner_y - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TrackRectangle are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -338,7 +338,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TrackingServerResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -572,7 +572,7 @@ async def respond_tracking_point_command(self, command_answer): result = self._extract_result(response) - if result.result is not TrackingServerResult.Result.SUCCESS: + if result.result != TrackingServerResult.Result.SUCCESS: raise TrackingServerError(result, "respond_tracking_point_command()", command_answer) @@ -601,7 +601,7 @@ async def respond_tracking_rectangle_command(self, command_answer): result = self._extract_result(response) - if result.result is not TrackingServerResult.Result.SUCCESS: + if result.result != TrackingServerResult.Result.SUCCESS: raise TrackingServerError(result, "respond_tracking_rectangle_command()", command_answer) @@ -630,6 +630,6 @@ async def respond_tracking_off_command(self, command_answer): result = self._extract_result(response) - if result.result is not TrackingServerResult.Result.SUCCESS: + if result.result != TrackingServerResult.Result.SUCCESS: raise TrackingServerError(result, "respond_tracking_off_command()", command_answer) \ No newline at end of file diff --git a/mavsdk/transponder.py b/mavsdk/transponder.py index 15bfd59c..5dd92d15 100644 --- a/mavsdk/transponder.py +++ b/mavsdk/transponder.py @@ -250,7 +250,7 @@ def __init__( self.emitter_type = emitter_type self.squawk = squawk - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two AdsbVehicle are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -488,7 +488,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TransponderResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -618,6 +618,6 @@ async def set_rate_transponder(self, rate_hz): result = self._extract_result(response) - if result.result is not TransponderResult.Result.SUCCESS: + if result.result != TransponderResult.Result.SUCCESS: raise TransponderError(result, "set_rate_transponder()", rate_hz) \ No newline at end of file diff --git a/mavsdk/tune.py b/mavsdk/tune.py index 3599a150..b7a041bf 100644 --- a/mavsdk/tune.py +++ b/mavsdk/tune.py @@ -218,7 +218,7 @@ def __init__( self.song_elements = song_elements self.tempo = tempo - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TuneDescription are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -365,7 +365,7 @@ def __init__( self.result = result self.result_str = result_str - def __equals__(self, to_compare): + def __eq__(self, to_compare): """ Checks if two TuneResult are the same """ try: # Try to compare - this likely fails when it is compared to a non @@ -473,6 +473,6 @@ async def play_tune(self, tune_description): result = self._extract_result(response) - if result.result is not TuneResult.Result.SUCCESS: + if result.result != TuneResult.Result.SUCCESS: raise TuneError(result, "play_tune()", tune_description) \ No newline at end of file diff --git a/proto b/proto index 757979ee..5b5bae46 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 757979eeebaef378446622c3807e114bc358f547 +Subproject commit 5b5bae46bb332f0e28e7e9bd6bcfa006c4a8d44b