Skip to content

Commit 724fda5

Browse files
Merge pull request #185 from mavlink/mavsdk-server-0.26.0
Update to latest proto and bump mavsdk_server to 0.26.0
2 parents 218169b + b68699c commit 724fda5

File tree

5 files changed

+197
-23
lines changed

5 files changed

+197
-23
lines changed

MAVSDK_SERVER_VERSION

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
v0.25.0
1+
v0.26.0

mavsdk/generated/calibration.py

Lines changed: 49 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,9 @@ class Result(Enum):
5656
CANCELLED
5757
Calibration process was cancelled
5858
59+
FAILED_ARMED
60+
Calibration process failed since the vehicle is armed
61+
5962
"""
6063

6164

@@ -69,6 +72,7 @@ class Result(Enum):
6972
COMMAND_DENIED = 7
7073
TIMEOUT = 8
7174
CANCELLED = 9
75+
FAILED_ARMED = 10
7276

7377
def translate_to_rpc(self, rpcResult):
7478
if self == CalibrationResult.Result.UNKNOWN:
@@ -91,6 +95,8 @@ def translate_to_rpc(self, rpcResult):
9195
return calibration_pb2.CalibrationResult.RESULT_TIMEOUT
9296
if self == CalibrationResult.Result.CANCELLED:
9397
return calibration_pb2.CalibrationResult.RESULT_CANCELLED
98+
if self == CalibrationResult.Result.FAILED_ARMED:
99+
return calibration_pb2.CalibrationResult.RESULT_FAILED_ARMED
94100

95101
@staticmethod
96102
def translate_from_rpc(rpc_enum_value):
@@ -115,6 +121,8 @@ def translate_from_rpc(rpc_enum_value):
115121
return CalibrationResult.Result.TIMEOUT
116122
if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_CANCELLED:
117123
return CalibrationResult.Result.CANCELLED
124+
if rpc_enum_value == calibration_pb2.CalibrationResult.RESULT_FAILED_ARMED:
125+
return CalibrationResult.Result.FAILED_ARMED
118126

119127
def __str__(self):
120128
return self.name
@@ -401,7 +409,7 @@ async def calibrate_accelerometer(self):
401409

402410
async def calibrate_magnetometer(self):
403411
"""
404-
Perform magnetometer caliration.
412+
Perform magnetometer calibration.
405413
406414
Yields
407415
-------
@@ -439,6 +447,46 @@ async def calibrate_magnetometer(self):
439447
finally:
440448
calibrate_magnetometer_stream.cancel()
441449

450+
async def calibrate_level_horizon(self):
451+
"""
452+
Perform board level horizon calibration.
453+
454+
Yields
455+
-------
456+
progress_data : ProgressData
457+
Progress data
458+
459+
Raises
460+
------
461+
CalibrationError
462+
If the request fails. The error contains the reason for the failure.
463+
"""
464+
465+
request = calibration_pb2.SubscribeCalibrateLevelHorizonRequest()
466+
calibrate_level_horizon_stream = self._stub.SubscribeCalibrateLevelHorizon(request)
467+
468+
try:
469+
async for response in calibrate_level_horizon_stream:
470+
471+
result = self._extract_result(response)
472+
473+
success_codes = [CalibrationResult.Result.SUCCESS]
474+
if 'NEXT' in [return_code.name for return_code in CalibrationResult.Result]:
475+
success_codes.append(CalibrationResult.Result.NEXT)
476+
477+
if result.result not in success_codes:
478+
raise CalibrationError(result, "calibrate_level_horizon()")
479+
480+
if result.result is CalibrationResult.Result.SUCCESS:
481+
calibrate_level_horizon_stream.cancel();
482+
return
483+
484+
485+
486+
yield ProgressData.translate_from_rpc(response.progress_data)
487+
finally:
488+
calibrate_level_horizon_stream.cancel()
489+
442490
async def calibrate_gimbal_accelerometer(self):
443491
"""
444492
Perform gimbal accelerometer calibration.

mavsdk/generated/calibration_pb2.py

Lines changed: 112 additions & 19 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

0 commit comments

Comments
 (0)