Skip to content

Commit

Permalink
Merge pull request #401 from mavlink/pr-update
Browse files Browse the repository at this point in the history
Update mavsdk_server version and proto submodule
  • Loading branch information
julianoes authored Oct 31, 2021
2 parents 927ff95 + 2f627b3 commit ea70be2
Show file tree
Hide file tree
Showing 31 changed files with 376 additions and 337 deletions.
2 changes: 1 addition & 1 deletion MAVSDK_SERVER_VERSION
Original file line number Diff line number Diff line change
@@ -1 +1 @@
v0.44.0
v0.46.1
44 changes: 22 additions & 22 deletions mavsdk/action.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand Down Expand Up @@ -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)


Expand Down Expand Up @@ -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)


Expand All @@ -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()")


Expand Down Expand Up @@ -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)


Expand All @@ -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()")


Expand All @@ -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()")


Expand All @@ -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()")


Expand Down Expand Up @@ -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)


Expand All @@ -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()")


Expand Down Expand Up @@ -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)


Expand All @@ -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()")


Expand Down Expand Up @@ -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)

28 changes: 14 additions & 14 deletions mavsdk/action_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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)


Expand Down Expand Up @@ -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)


Expand Down Expand Up @@ -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)


Expand Down Expand Up @@ -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)


Expand Down
16 changes: 8 additions & 8 deletions mavsdk/calibration.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand All @@ -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()")

Loading

0 comments on commit ea70be2

Please sign in to comment.