Skip to content

Commit

Permalink
Update to latest proto and bump mavsdk_server to 0.26.0
Browse files Browse the repository at this point in the history
  • Loading branch information
JonasVautherin committed May 13, 2020
1 parent 218169b commit b68699c
Show file tree
Hide file tree
Showing 5 changed files with 197 additions and 23 deletions.
2 changes: 1 addition & 1 deletion MAVSDK_SERVER_VERSION
Original file line number Diff line number Diff line change
@@ -1 +1 @@
v0.25.0
v0.26.0
50 changes: 49 additions & 1 deletion mavsdk/generated/calibration.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,9 @@ class Result(Enum):
CANCELLED
Calibration process was cancelled
FAILED_ARMED
Calibration process failed since the vehicle is armed
"""


Expand All @@ -69,6 +72,7 @@ class Result(Enum):
COMMAND_DENIED = 7
TIMEOUT = 8
CANCELLED = 9
FAILED_ARMED = 10

def translate_to_rpc(self, rpcResult):
if self == CalibrationResult.Result.UNKNOWN:
Expand All @@ -91,6 +95,8 @@ def translate_to_rpc(self, rpcResult):
return calibration_pb2.CalibrationResult.RESULT_TIMEOUT
if self == CalibrationResult.Result.CANCELLED:
return calibration_pb2.CalibrationResult.RESULT_CANCELLED
if self == CalibrationResult.Result.FAILED_ARMED:
return calibration_pb2.CalibrationResult.RESULT_FAILED_ARMED

@staticmethod
def translate_from_rpc(rpc_enum_value):
Expand All @@ -115,6 +121,8 @@ def translate_from_rpc(rpc_enum_value):
return CalibrationResult.Result.TIMEOUT
if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_CANCELLED:
return CalibrationResult.Result.CANCELLED
if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_FAILED_ARMED:
return CalibrationResult.Result.FAILED_ARMED

def __str__(self):
return self.name
Expand Down Expand Up @@ -401,7 +409,7 @@ async def calibrate_accelerometer(self):

async def calibrate_magnetometer(self):
"""
Perform magnetometer caliration.
Perform magnetometer calibration.
Yields
-------
Expand Down Expand Up @@ -439,6 +447,46 @@ async def calibrate_magnetometer(self):
finally:
calibrate_magnetometer_stream.cancel()

async def calibrate_level_horizon(self):
"""
Perform board level horizon calibration.
Yields
-------
progress_data : ProgressData
Progress data
Raises
------
CalibrationError
If the request fails. The error contains the reason for the failure.
"""

request = calibration_pb2.SubscribeCalibrateLevelHorizonRequest()
calibrate_level_horizon_stream = self._stub.SubscribeCalibrateLevelHorizon(request)

try:
async for response in calibrate_level_horizon_stream:

result = self._extract_result(response)

success_codes = [CalibrationResult.Result.SUCCESS]
if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]:
success_codes.append(CalibrationResult.Result.NEXT)

if result.result not in success_codes:
raise CalibrationError(result, "calibrate_level_horizon()")

if result.result is CalibrationResult.Result.SUCCESS:
calibrate_level_horizon_stream.cancel();
return



yield ProgressData.translate_from_rpc(response.progress_data)
finally:
calibrate_level_horizon_stream.cancel()

async def calibrate_gimbal_accelerometer(self):
"""
Perform gimbal accelerometer calibration.
Expand Down
131 changes: 112 additions & 19 deletions mavsdk/generated/calibration_pb2.py

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Loading

0 comments on commit b68699c

Please sign in to comment.